From cdee45bba6ddc2f2cf2a4467ad34eac3b4deffa6 Mon Sep 17 00:00:00 2001 From: Miles Macklin Date: Thu, 23 Nov 2023 09:04:34 +1300 Subject: [PATCH 01/50] Add content-type for PyPi setup --- pyproject.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/pyproject.toml b/pyproject.toml index 14ff5d984..6190136f0 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -37,7 +37,7 @@ find = {} [tool.setuptools.dynamic] version = {attr = "warp.config.version"} -readme = {file = ["README.md"]} +readme = {file = ["README.md"], content-type = "text/markdown"} [tool.black] line-length = 120 From cd77601f226537c14393decbf4fd48292bcf30e8 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Wed, 22 Nov 2023 15:19:59 +1300 Subject: [PATCH 02/50] Support passing the return value to adjoints --- warp/builtins.py | 20 +++++++++++++++++++- warp/codegen.py | 6 ++++-- warp/context.py | 5 +++++ warp/native/builtin.h | 26 ++++++++++++-------------- warp/native/intersect.h | 8 ++++---- warp/native/intersect_adj.h | 16 ++++++++-------- warp/native/mat.h | 8 ++++---- warp/native/quat.h | 13 +++++++++---- warp/native/vec.h | 17 +++++++++-------- 9 files changed, 74 insertions(+), 45 deletions(-) diff --git a/warp/builtins.py b/warp/builtins.py index 5df6e0de2..5869800b1 100644 --- a/warp/builtins.py +++ b/warp/builtins.py @@ -116,6 +116,7 @@ def fn(arg_types, kwds, _): value_func=sametype_value_func(Float), doc="Return the square root of ``x``, where ``x`` is positive.", group="Scalar Math", + require_original_output_arg=True, ) add_builtin( "cbrt", @@ -123,6 +124,7 @@ def fn(arg_types, kwds, _): value_func=sametype_value_func(Float), doc="Return the cube root of ``x``.", group="Scalar Math", + require_original_output_arg=True, ) add_builtin( "tan", @@ -165,6 +167,7 @@ def fn(arg_types, kwds, _): value_func=sametype_value_func(Float), doc="Return the tanh of ``x``.", group="Scalar Math", + require_original_output_arg=True, ) add_builtin( "degrees", @@ -208,6 +211,7 @@ def fn(arg_types, kwds, _): value_func=sametype_value_func(Float), doc="Return the value of the exponential function :math:`e^x`.", group="Scalar Math", + require_original_output_arg=True, ) add_builtin( "pow", @@ -215,6 +219,7 @@ def fn(arg_types, kwds, _): value_func=sametype_value_func(Float), doc="Return the result of ``x`` raised to power of ``y``.", group="Scalar Math", + require_original_output_arg=True, ) add_builtin( @@ -405,6 +410,7 @@ def value_func_outer(arg_types, kwds, _): value_func=sametype_scalar_value_func, group="Vector Math", doc="Compute the length of a vector ``x``.", + require_original_output_arg=True, ) add_builtin( "length", @@ -412,6 +418,7 @@ def value_func_outer(arg_types, kwds, _): value_func=sametype_scalar_value_func, group="Vector Math", doc="Compute the length of a quaternion ``x``.", + require_original_output_arg=True, ) add_builtin( "length_sq", @@ -433,6 +440,7 @@ def value_func_outer(arg_types, kwds, _): value_func=sametype_value_func(vector(length=Any, dtype=Scalar)), group="Vector Math", doc="Compute the normalized value of ``x``. If ``length(x)`` is 0 then the zero vector is returned.", + require_original_output_arg=True, ) add_builtin( "normalize", @@ -465,6 +473,7 @@ def value_func_mat_inv(arg_types, kwds, _): value_func=value_func_mat_inv, group="Vector Math", doc="Return the inverse of a 2x2 matrix ``m``.", + require_original_output_arg=True, ) add_builtin( @@ -473,6 +482,7 @@ def value_func_mat_inv(arg_types, kwds, _): value_func=value_func_mat_inv, group="Vector Math", doc="Return the inverse of a 3x3 matrix ``m``.", + require_original_output_arg=True, ) add_builtin( @@ -481,6 +491,7 @@ def value_func_mat_inv(arg_types, kwds, _): value_func=value_func_mat_inv, group="Vector Math", doc="Return the inverse of a 4x4 matrix ``m``.", + require_original_output_arg=True, ) @@ -580,6 +591,7 @@ def value_func_get_diag(arg_types, kwds, _): value_func=sametype_value_func(vector(length=Any, dtype=Scalar)), group="Vector Math", doc="Component-wise division of two 2D vectors.", + require_original_output_arg=True, ) add_builtin( @@ -595,6 +607,7 @@ def value_func_get_diag(arg_types, kwds, _): value_func=sametype_value_func(matrix(shape=(Any, Any), dtype=Scalar)), group="Vector Math", doc="Component-wise division of two 2D vectors.", + require_original_output_arg=True, ) @@ -1082,6 +1095,7 @@ def quat_identity_value_func(arg_types, kwds, templates): value_func=lambda arg_types, kwds, _: quaternion(dtype=infer_scalar_type(arg_types)), group="Quaternion Math", doc="Linearly interpolate between two quaternions.", + require_original_output_arg=True, ) add_builtin( "quat_to_matrix", @@ -3065,7 +3079,11 @@ def mul_matmat_value_func(arg_types, kwds, _): ) add_builtin( - "div", input_types={"x": Scalar, "y": Scalar}, value_func=sametype_value_func(Scalar), doc="", group="Operators" + "div", + input_types={"x": Scalar, "y": Scalar}, + value_func=sametype_value_func(Scalar), + doc="", group="Operators", + require_original_output_arg=True, ) add_builtin( "div", diff --git a/warp/codegen.py b/warp/codegen.py index 2e6a0eaf0..85184c671 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -683,10 +683,11 @@ def format_reverse_call_args( args_out, use_initializer_list, has_output_args=True, + require_original_output_arg=False, ): formatted_var = adj.format_args("var", args_var) formatted_out = [] - if has_output_args and len(args_out) > 1: + if has_output_args and (require_original_output_arg or len(args_out) > 1): formatted_out = adj.format_args("var", args_out) formatted_var_adj = adj.format_args( "&adj" if use_initializer_list else "adj", @@ -966,13 +967,14 @@ def add_call(adj, func, args, min_outputs=None, templates=[], kwds=None): adj.add_forward(forward_call, replay=replay_call) if not func.missing_grad and len(args): - reverse_has_output_args = len(output_list) > 1 and func.custom_grad_func is None + reverse_has_output_args = (func.require_original_output_arg or len(output_list) > 1) and func.custom_grad_func is None arg_str = adj.format_reverse_call_args( args_var, args, output_list, use_initializer_list, has_output_args=reverse_has_output_args, + require_original_output_arg=func.require_original_output_arg, ) if arg_str is not None: reverse_call = f"{func.namespace}adj_{func.native_func}({arg_str});" diff --git a/warp/context.py b/warp/context.py index e0422b550..863067717 100644 --- a/warp/context.py +++ b/warp/context.py @@ -79,6 +79,7 @@ def __init__( overloaded_annotations=None, code_transformers=[], skip_adding_overload=False, + require_original_output_arg=False, ): self.func = func # points to Python function decorated with @wp.func, may be None for builtins self.key = key @@ -97,6 +98,7 @@ def __init__( self.native_snippet = native_snippet self.adj_native_snippet = adj_native_snippet self.custom_grad_func = None + self.require_original_output_arg = require_original_output_arg if initializer_list_func is None: self.initializer_list_func = lambda x, y: False @@ -841,6 +843,7 @@ def add_builtin( missing_grad=False, native_func=None, defaults=None, + require_original_output_arg=False, ): # wrap simple single-type functions with a value_func() if value_func is None: @@ -965,6 +968,7 @@ def typelist(param): hidden=True, skip_replay=skip_replay, missing_grad=missing_grad, + require_original_output_arg=require_original_output_arg, ) func = Function( @@ -985,6 +989,7 @@ def typelist(param): generic=generic, native_func=native_func, defaults=defaults, + require_original_output_arg=require_original_output_arg, ) if key in builtin_functions: diff --git a/warp/native/builtin.h b/warp/native/builtin.h index 4011312d9..ad33cf575 100644 --- a/warp/native/builtin.h +++ b/warp/native/builtin.h @@ -295,7 +295,7 @@ inline CUDA_CALLABLE T rshift(T a, T b) { return a>>b; } \ inline CUDA_CALLABLE T invert(T x) { return ~x; } \ inline CUDA_CALLABLE bool isfinite(T x) { return true; } \ inline CUDA_CALLABLE void adj_mul(T a, T b, T& adj_a, T& adj_b, T adj_ret) { } \ -inline CUDA_CALLABLE void adj_div(T a, T b, T& adj_a, T& adj_b, T adj_ret) { } \ +inline CUDA_CALLABLE void adj_div(T a, T b, T ret, T& adj_a, T& adj_b, T adj_ret) { } \ inline CUDA_CALLABLE void adj_add(T a, T b, T& adj_a, T& adj_b, T adj_ret) { } \ inline CUDA_CALLABLE void adj_sub(T a, T b, T& adj_a, T& adj_b, T adj_ret) { } \ inline CUDA_CALLABLE void adj_mod(T a, T b, T& adj_a, T& adj_b, T adj_ret) { } \ @@ -443,10 +443,10 @@ inline CUDA_CALLABLE T div(T a, T b)\ })\ return a/b;\ }\ -inline CUDA_CALLABLE void adj_div(T a, T b, T& adj_a, T& adj_b, T adj_ret)\ +inline CUDA_CALLABLE void adj_div(T a, T b, T ret, T& adj_a, T& adj_b, T adj_ret)\ {\ adj_a += adj_ret/b;\ - adj_b -= adj_ret*(a/b)/b;\ + adj_b -= adj_ret*(ret)/b;\ DO_IF_FPCHECK(\ if (!isfinite(adj_a) || !isfinite(adj_b))\ {\ @@ -859,11 +859,11 @@ inline CUDA_CALLABLE void adj_log10(T a, T& adj_a, T adj_ret)\ assert(0);\ })\ }\ -inline CUDA_CALLABLE void adj_exp(T a, T& adj_a, T adj_ret) { adj_a += exp(a)*adj_ret; }\ -inline CUDA_CALLABLE void adj_pow(T a, T b, T& adj_a, T& adj_b, T adj_ret)\ +inline CUDA_CALLABLE void adj_exp(T a, T ret, T& adj_a, T adj_ret) { adj_a += ret*adj_ret; }\ +inline CUDA_CALLABLE void adj_pow(T a, T b, T ret, T& adj_a, T& adj_b, T adj_ret)\ { \ adj_a += b*pow(a, b-T(1))*adj_ret;\ - adj_b += log(a)*pow(a, b)*adj_ret;\ + adj_b += log(a)*ret*adj_ret;\ DO_IF_FPCHECK(if (!isfinite(adj_a) || !isfinite(adj_b))\ {\ printf("%s:%d - adj_pow(%f, %f, %f, %f, %f)\n", __FILE__, __LINE__, float(a), float(b), float(adj_a), float(adj_b), float(adj_ret));\ @@ -962,24 +962,22 @@ inline CUDA_CALLABLE void adj_cosh(T x, T& adj_x, T adj_ret)\ {\ adj_x += sinh(x)*adj_ret;\ }\ -inline CUDA_CALLABLE void adj_tanh(T x, T& adj_x, T adj_ret)\ +inline CUDA_CALLABLE void adj_tanh(T x, T ret, T& adj_x, T adj_ret)\ {\ - T tanh_x = tanh(x);\ - adj_x += (T(1) - tanh_x*tanh_x)*adj_ret;\ + adj_x += (T(1) - ret*ret)*adj_ret;\ }\ -inline CUDA_CALLABLE void adj_sqrt(T x, T& adj_x, T adj_ret)\ +inline CUDA_CALLABLE void adj_sqrt(T x, T ret, T& adj_x, T adj_ret)\ {\ - adj_x += T(0.5)*(T(1)/sqrt(x))*adj_ret;\ + adj_x += T(0.5)*(T(1)/ret)*adj_ret;\ DO_IF_FPCHECK(if (!isfinite(adj_x))\ {\ printf("%s:%d - adj_sqrt(%f, %f, %f)\n", __FILE__, __LINE__, float(x), float(adj_x), float(adj_ret));\ assert(0);\ })\ }\ -inline CUDA_CALLABLE void adj_cbrt(T x, T& adj_x, T adj_ret)\ +inline CUDA_CALLABLE void adj_cbrt(T x, T ret, T& adj_x, T adj_ret)\ {\ - T cbrt_x = cbrt(x);\ - adj_x += (T(1)/T(3))*(T(1)/(cbrt_x*cbrt_x))*adj_ret;\ + adj_x += (T(1)/T(3))*(T(1)/(ret*ret))*adj_ret;\ DO_IF_FPCHECK(if (!isfinite(adj_x))\ {\ printf("%s:%d - adj_cbrt(%f, %f, %f)\n", __FILE__, __LINE__, float(x), float(adj_x), float(adj_ret));\ diff --git a/warp/native/intersect.h b/warp/native/intersect.h index 7513772bd..e170dcd05 100644 --- a/warp/native/intersect.h +++ b/warp/native/intersect.h @@ -869,7 +869,7 @@ CUDA_CALLABLE inline void adj_closest_point_to_triangle( wp::adj_sub(var_9, var_71, adj_9, adj_71, adj_73); wp::adj_mul(var_21, var_70, adj_21, adj_70, adj_72); wp::adj_mul(var_41, var_70, adj_41, adj_70, adj_71); - wp::adj_div(var_9, var_69, adj_9, adj_69, adj_70); + wp::adj_div(var_9, var_69, var_70, adj_9, adj_69, adj_70); wp::adj_add(var_68, var_21, adj_68, adj_21, adj_69); wp::adj_add(var_53, var_41, adj_53, adj_41, adj_68); wp::adj_select(var_64, var_50, var_66, adj_64, adj_50, adj_66, adj_67); @@ -881,7 +881,7 @@ CUDA_CALLABLE inline void adj_closest_point_to_triangle( } wp::adj_sub(var_32, var_33, adj_32, adj_33, adj_62); wp::adj_sub(var_13, var_12, adj_13, adj_12, adj_60); - wp::adj_div(var_54, var_57, adj_54, adj_57, adj_58); + wp::adj_div(var_54, var_57, var_58, adj_54, adj_57, adj_58); wp::adj_add(var_55, var_56, adj_55, adj_56, adj_57); wp::adj_sub(var_32, var_33, adj_32, adj_33, adj_56); wp::adj_sub(var_13, var_12, adj_13, adj_12, adj_55); @@ -896,7 +896,7 @@ CUDA_CALLABLE inline void adj_closest_point_to_triangle( wp::adj_vec2(var_48, var_5, adj_48, adj_5, adj_49); wp::adj_sub(var_9, var_43, adj_9, adj_43, adj_48); } - wp::adj_div(var_4, var_42, adj_4, adj_42, adj_43); + wp::adj_div(var_4, var_42, var_43, adj_4, adj_42, adj_43); wp::adj_sub(var_4, var_33, adj_4, adj_33, adj_42); wp::adj_sub(var_39, var_40, adj_39, adj_40, adj_41); wp::adj_mul(var_3, var_33, adj_3, adj_33, adj_40); @@ -917,7 +917,7 @@ CUDA_CALLABLE inline void adj_closest_point_to_triangle( wp::adj_vec2(var_28, var_23, adj_28, adj_23, adj_29); wp::adj_sub(var_9, var_23, adj_9, adj_23, adj_28); } - wp::adj_div(var_3, var_22, adj_3, adj_22, adj_23); + wp::adj_div(var_3, var_22, var_23, adj_3, adj_22, adj_23); wp::adj_sub(var_3, var_12, adj_3, adj_12, adj_22); wp::adj_sub(var_19, var_20, adj_19, adj_20, adj_21); wp::adj_mul(var_12, var_4, adj_12, adj_4, adj_20); diff --git a/warp/native/intersect_adj.h b/warp/native/intersect_adj.h index e64a9ad53..23c95af99 100644 --- a/warp/native/intersect_adj.h +++ b/warp/native/intersect_adj.h @@ -276,7 +276,7 @@ static CUDA_CALLABLE void adj_closest_point_edge_edge(vec3 var_p1, label1:; adj_71 += adj_ret; wp::adj_vec3(var_61, var_62, var_70, adj_61, adj_62, adj_70, adj_71); - wp::adj_length(var_69, adj_69, adj_70); + wp::adj_length(var_69, var_70, adj_69, adj_70); wp::adj_sub(var_68, var_65, adj_68, adj_65, adj_69); wp::adj_add(var_p2, var_67, adj_p2, adj_67, adj_68); wp::adj_mul(var_66, var_62, adj_66, adj_62, adj_67); @@ -297,7 +297,7 @@ static CUDA_CALLABLE void adj_closest_point_edge_edge(vec3 var_p1, wp::adj_select(var_51, var_49, var_54, adj_51, adj_49, adj_54, adj_55); if (var_51) { wp::adj_clamp(var_53, var_6, var_25, adj_53, adj_6, adj_25, adj_54); - wp::adj_div(var_52, var_3, adj_52, adj_3, adj_53); + wp::adj_div(var_52, var_3, var_53, adj_52, adj_3, adj_53); wp::adj_sub(var_30, var_21, adj_30, adj_21, adj_52); } } @@ -305,10 +305,10 @@ static CUDA_CALLABLE void adj_closest_point_edge_edge(vec3 var_p1, wp::adj_select(var_45, var_41, var_48, adj_45, adj_41, adj_48, adj_49); if (var_45) { wp::adj_clamp(var_47, var_6, var_25, adj_47, adj_6, adj_25, adj_48); - wp::adj_div(var_46, var_3, adj_46, adj_3, adj_47); + wp::adj_div(var_46, var_3, var_47, adj_46, adj_3, adj_47); wp::adj_neg(var_21, adj_21, adj_46); } - wp::adj_div(var_43, var_4, adj_43, adj_4, adj_44); + wp::adj_div(var_43, var_4, var_44, adj_43, adj_4, adj_44); wp::adj_add(var_42, var_5, adj_42, adj_5, adj_43); wp::adj_mul(var_30, var_41, adj_30, adj_41, adj_42); wp::adj_select(var_34, var_6, var_40, adj_34, adj_6, adj_40, adj_41); @@ -317,7 +317,7 @@ static CUDA_CALLABLE void adj_closest_point_edge_edge(vec3 var_p1, wp::adj_select(var_34, var_28, var_39, adj_34, adj_28, adj_39, adj_40); if (var_34) { wp::adj_clamp(var_38, var_6, var_25, adj_38, adj_6, adj_25, adj_39); - wp::adj_div(var_37, var_33, adj_37, adj_33, adj_38); + wp::adj_div(var_37, var_33, var_38, adj_37, adj_33, adj_38); wp::adj_sub(var_35, var_36, adj_35, adj_36, adj_37); wp::adj_mul(var_21, var_4, adj_21, adj_4, adj_36); wp::adj_mul(var_30, var_5, adj_30, adj_5, adj_35); @@ -332,7 +332,7 @@ static CUDA_CALLABLE void adj_closest_point_edge_edge(vec3 var_p1, if (var_22) { wp::adj_cast_float(var_6, adj_6, adj_27); wp::adj_clamp(var_24, var_6, var_25, adj_24, adj_6, adj_25, adj_26); - wp::adj_div(var_23, var_3, adj_23, adj_3, adj_24); + wp::adj_div(var_23, var_3, var_24, adj_23, adj_3, adj_24); wp::adj_neg(var_21, adj_21, adj_23); } wp::adj_dot(var_0, var_2, adj_0, adj_2, adj_21); @@ -341,7 +341,7 @@ static CUDA_CALLABLE void adj_closest_point_edge_edge(vec3 var_p1, wp::adj_select(var_15, var_7, var_16, adj_15, adj_7, adj_16, adj_19); if (var_15) { wp::adj_cast_float(var_17, adj_17, adj_18); - wp::adj_div(var_5, var_4, adj_5, adj_4, adj_17); + wp::adj_div(var_5, var_4, var_17, adj_5, adj_4, adj_17); wp::adj_cast_float(var_6, adj_6, adj_16); } if (var_13) { @@ -349,7 +349,7 @@ static CUDA_CALLABLE void adj_closest_point_edge_edge(vec3 var_p1, adj_14 += adj_ret; wp::adj_vec3(var_7, var_8, var_10, adj_7, adj_8, adj_10, adj_14); } - wp::adj_length(var_9, adj_9, adj_10); + wp::adj_length(var_9, var_10, adj_9, adj_10); wp::adj_sub(var_p2, var_p1, adj_p2, adj_p1, adj_9); wp::adj_cast_float(var_6, adj_6, adj_8); wp::adj_cast_float(var_6, adj_6, adj_7); diff --git a/warp/native/mat.h b/warp/native/mat.h index d5839f186..d3853f689 100644 --- a/warp/native/mat.h +++ b/warp/native/mat.h @@ -1105,10 +1105,10 @@ inline CUDA_CALLABLE void adj_determinant(const mat_t<4,4,Type>& m, mat_t<4,4,Ty } template -inline CUDA_CALLABLE void adj_inverse(const mat_t& m, mat_t& adj_m, const mat_t& adj_ret) +inline CUDA_CALLABLE void adj_inverse(const mat_t& m, mat_t& ret, mat_t& adj_m, const mat_t& adj_ret) { // todo: how to cache this from the forward pass? - mat_t invt = transpose(inverse(m)); + mat_t invt = transpose(ret); // see https://people.maths.ox.ac.uk/gilesm/files/NA-08-01.pdf 2.2.3 adj_m -= mul(mul(invt, adj_ret), invt); @@ -1150,10 +1150,10 @@ inline CUDA_CALLABLE void adj_cw_mul(const mat_t& a, const mat_t } template -inline CUDA_CALLABLE void adj_cw_div(const mat_t& a, const mat_t& b, mat_t& adj_a, mat_t& adj_b, const mat_t& adj_ret) +inline CUDA_CALLABLE void adj_cw_div(const mat_t& a, const mat_t& b, mat_t& ret, mat_t& adj_a, mat_t& adj_b, const mat_t& adj_ret) { adj_a += cw_div(adj_ret, b); - adj_b -= cw_mul(adj_ret, cw_div(cw_div(a, b), b)); + adj_b -= cw_mul(adj_ret, cw_div(ret, b)); } // adjoint for the constant constructor: diff --git a/warp/native/quat.h b/warp/native/quat.h index f65ad321a..c554e243c 100644 --- a/warp/native/quat.h +++ b/warp/native/quat.h @@ -523,9 +523,14 @@ inline CUDA_CALLABLE void tensordot(const quat_t& a, const quat_t& b } template -inline CUDA_CALLABLE void adj_length(const quat_t& a, quat_t& adj_a, const Type adj_ret) +inline CUDA_CALLABLE void adj_length(const quat_t& a, Type ret, quat_t& adj_a, const Type adj_ret) { - adj_a += normalize(a)*adj_ret; + if (ret > Type(kEps)) + { + Type inv_l = Type(1)/ret; + + adj_a += quat_t(a.x*inv_l, a.y*inv_l, a.z*inv_l, a.w*inv_l) * adj_ret; + } } template @@ -677,7 +682,7 @@ inline CUDA_CALLABLE void adj_quat_rotate_inv(const quat_t& q, const vec_t } template -inline CUDA_CALLABLE void adj_quat_slerp(const quat_t& q0, const quat_t& q1, Type t, quat_t& adj_q0, quat_t& adj_q1, Type& adj_t, const quat_t& adj_ret) +inline CUDA_CALLABLE void adj_quat_slerp(const quat_t& q0, const quat_t& q1, Type t, quat_t& ret, quat_t& adj_q0, quat_t& adj_q1, Type& adj_t, const quat_t& adj_ret) { vec_t<3,Type> axis; Type angle; @@ -688,7 +693,7 @@ inline CUDA_CALLABLE void adj_quat_slerp(const quat_t& q0, const quat_t(angle*axis[0], angle*axis[1], angle*axis[2], Type(0))), adj_ret); + adj_t += dot(mul(ret, quat_t(angle*axis[0], angle*axis[1], angle*axis[2], Type(0))), adj_ret); // adj_q0 quat_t q_inc_x_q0; diff --git a/warp/native/vec.h b/warp/native/vec.h index 287b6366e..9c70864cb 100644 --- a/warp/native/vec.h +++ b/warp/native/vec.h @@ -735,9 +735,9 @@ inline CUDA_CALLABLE void adj_div(vec_t a, Type s, vec_t -inline CUDA_CALLABLE void adj_cw_div(vec_t a, vec_t b, vec_t& adj_a, vec_t& adj_b, const vec_t& adj_ret) { +inline CUDA_CALLABLE void adj_cw_div(vec_t a, vec_t b, vec_t& ret, vec_t& adj_a, vec_t& adj_b, const vec_t& adj_ret) { adj_a += cw_div(adj_ret, b); - adj_b -= cw_mul(adj_ret, cw_div(cw_div(a, b), b)); + adj_b -= cw_mul(adj_ret, cw_div(ret, b)); } template @@ -850,9 +850,12 @@ inline CUDA_CALLABLE void adj_extract(const vec_t & a, int idx, ve } template -inline CUDA_CALLABLE void adj_length(vec_t a, vec_t& adj_a, const Type adj_ret) +inline CUDA_CALLABLE void adj_length(vec_t a, Type ret, vec_t& adj_a, const Type adj_ret) { - adj_a += normalize(a)*adj_ret; + if (ret > Type(kEps)) + { + adj_a += div(a, ret) * adj_ret; + } #if FP_CHECK if (!isfinite(adj_a)) @@ -880,7 +883,7 @@ inline CUDA_CALLABLE void adj_length_sq(vec_t a, vec_t -inline CUDA_CALLABLE void adj_normalize(vec_t a, vec_t& adj_a, const vec_t& adj_ret) +inline CUDA_CALLABLE void adj_normalize(vec_t a, vec_t& ret, vec_t& adj_a, const vec_t& adj_ret) { Type d = length(a); @@ -888,9 +891,7 @@ inline CUDA_CALLABLE void adj_normalize(vec_t a, vec_t ahat = normalize(a); - - adj_a += (adj_ret*invd - ahat*(dot(ahat, adj_ret))*invd); + adj_a += (adj_ret*invd - ret*(dot(ret, adj_ret))*invd); #if FP_CHECK if (!isfinite(adj_a)) From db417403c0dd2635cfa261e5363d531499f6d0e5 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Tue, 28 Nov 2023 09:54:39 +1300 Subject: [PATCH 03/50] Edit the message for accessing non-existing attrs --- warp/codegen.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/warp/codegen.py b/warp/codegen.py index 77cf87d80..726d8bf49 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -1344,7 +1344,7 @@ def emit_Attribute(adj, node): if isinstance(aggregate, Var): raise WarpCodegenAttributeError( - f"Error, `{node.attr}` is not an attribute of '{aggregate.label}' ({type_repr(aggregate.type)})" + f"Error, `{node.attr}` is not an attribute of '{node.value.id}' ({type_repr(aggregate.type)})" ) raise WarpCodegenAttributeError(f"Error, `{node.attr}` is not an attribute of '{aggregate}'") From 4885b43c9a802f7b89bec2b0f28755632436d974 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Thu, 30 Nov 2023 12:11:40 -0500 Subject: [PATCH 04/50] Only fetch prebuilt Clang/LLVM libraries when needed --- build_llvm.py | 50 ++++++++++++++++++++++++++------------------------ 1 file changed, 26 insertions(+), 24 deletions(-) diff --git a/build_llvm.py b/build_llvm.py index fc839bad0..24148bc2e 100644 --- a/build_llvm.py +++ b/build_llvm.py @@ -15,31 +15,33 @@ llvm_build_path = os.path.join(llvm_project_path, "out/build/") llvm_install_path = os.path.join(llvm_project_path, "out/install/") + # Fetch prebuilt Clang/LLVM libraries -if os.name == "nt": - packman = "tools\\packman\\packman.cmd" - packages = {"x86_64": "15.0.7-windows-x86_64-ptx-vs142"} -else: - packman = "./tools/packman/packman" - if sys.platform == "darwin": - packages = { - "arm64": "15.0.7-darwin-aarch64-macos11", - "x86_64": "15.0.7-darwin-x86_64-macos11", - } +def fetch_prebuilt_libraries(): + if os.name == "nt": + packman = "tools\\packman\\packman.cmd" + packages = {"x86_64": "15.0.7-windows-x86_64-ptx-vs142"} else: - packages = {"x86_64": "15.0.7-linux-x86_64-ptx-gcc7.5-cxx11abi0"} - -for arch in packages: - subprocess.check_call( - [ - packman, - "install", - "-l", - f"./_build/host-deps/llvm-project/release-{arch}", - "clang+llvm-warp", - packages[arch], - ] - ) + packman = "./tools/packman/packman" + if sys.platform == "darwin": + packages = { + "arm64": "15.0.7-darwin-aarch64-macos11", + "x86_64": "15.0.7-darwin-x86_64-macos11", + } + else: + packages = {"x86_64": "15.0.7-linux-x86_64-ptx-gcc7.5-cxx11abi0"} + + for arch in packages: + subprocess.check_call( + [ + packman, + "install", + "-l", + f"./_build/host-deps/llvm-project/release-{arch}", + "clang+llvm-warp", + packages[arch], + ] + ) def build_from_source_for_arch(args, arch): @@ -299,7 +301,7 @@ def build_warp_clang_for_arch(args, lib_name, arch): libpath = os.path.join(install_path, "lib") else: # obtain Clang and LLVM libraries from packman - assert os.path.exists("_build/host-deps/llvm-project"), "run build.bat / build.sh" + fetch_prebuilt_libraries() libpath = os.path.join(base_path, f"_build/host-deps/llvm-project/release-{arch}/lib") for _, _, libs in os.walk(libpath): From 18aff4d89a94d48ae2ddc976bbd2341e28ca4bc7 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Thu, 30 Nov 2023 14:59:26 -0500 Subject: [PATCH 05/50] Support overriding the LLVM project source directory path If `--build_llvm` is specified we previously cloned the LLVM project Git repository from https://github.com/llvm/llvm-project.git into `external/llvm-project`. This change adds an additional `--llvm_source_path` build argument for specifying a path to an existing LLVM project repo. Note that currently it needs to be the `llvmorg-15.0.7` tag revision. --- build_lib.py | 4 ++++ build_llvm.py | 46 +++++++++++++++++++++++++--------------------- 2 files changed, 29 insertions(+), 21 deletions(-) diff --git a/build_lib.py b/build_lib.py index 1738b5f3e..c78cc6698 100644 --- a/build_lib.py +++ b/build_lib.py @@ -49,6 +49,10 @@ parser.add_argument("--no_build_llvm", dest="build_llvm", action="store_false") parser.set_defaults(build_llvm=False) +parser.add_argument( + "--llvm_source_path", type=str, help="Path to the LLVM project source code (optional, repo cloned if not set)" +) + parser.add_argument("--debug_llvm", action="store_true", help="Enable LLVM compiler code debugging, default disabled") parser.add_argument("--no_debug_llvm", dest="debug_llvm", action="store_false") parser.set_defaults(debug_llvm=False) diff --git a/build_llvm.py b/build_llvm.py index 24148bc2e..ed4f21b04 100644 --- a/build_llvm.py +++ b/build_llvm.py @@ -9,9 +9,7 @@ base_path = os.path.dirname(os.path.realpath(__file__)) build_path = os.path.join(base_path, "warp") -llvm_project_dir = "external/llvm-project" -llvm_project_path = os.path.join(base_path, llvm_project_dir) -llvm_path = os.path.join(llvm_project_path, "llvm") +llvm_project_path = os.path.join(base_path, "external/llvm-project") llvm_build_path = os.path.join(llvm_project_path, "out/build/") llvm_install_path = os.path.join(llvm_project_path, "out/install/") @@ -44,29 +42,27 @@ def fetch_prebuilt_libraries(): ) -def build_from_source_for_arch(args, arch): - # Install dependencies - subprocess.check_call([sys.executable, "-m", "pip", "install", "gitpython"]) - subprocess.check_call([sys.executable, "-m", "pip", "install", "cmake"]) - subprocess.check_call([sys.executable, "-m", "pip", "install", "ninja"]) +def build_from_source_for_arch(args, arch, llvm_source): + # Check out the LLVM project Git repository, unless it already exists + if not os.path.exists(llvm_source): + # Install dependencies + subprocess.check_call([sys.executable, "-m", "pip", "install", "gitpython"]) + subprocess.check_call([sys.executable, "-m", "pip", "install", "cmake"]) + subprocess.check_call([sys.executable, "-m", "pip", "install", "ninja"]) - from git import Repo + from git import Repo - repo_url = "https://github.com/llvm/llvm-project.git" + repo_url = "https://github.com/llvm/llvm-project.git" + print(f"Cloning LLVM project from {repo_url}...") - if not os.path.exists(llvm_project_path): - print("Cloning LLVM project...") shallow_clone = True # https://github.blog/2020-12-21-get-up-to-speed-with-partial-clone-and-shallow-clone/ if shallow_clone: - repo = Repo.clone_from( - repo_url, to_path=llvm_project_path, single_branch=True, branch="llvmorg-15.0.7", depth=1 - ) + repo = Repo.clone_from(repo_url, to_path=llvm_source, single_branch=True, branch="llvmorg-15.0.7", depth=1) else: - repo = Repo.clone_from(repo_url, to_path=llvm_project_path) + repo = Repo.clone_from(repo_url, to_path=llvm_source) repo.git.checkout("tags/llvmorg-15.0.7", "-b", "llvm-15.0.7") - else: - print(f"Found existing {llvm_project_dir} directory") - repo = Repo(llvm_project_path) + + print(f"Using LLVM project source from {llvm_source}") # CMake supports Debug, Release, RelWithDebInfo, and MinSizeRel builds if warp.config.mode == "release": @@ -98,6 +94,7 @@ def build_from_source_for_arch(args, arch): else: host_triple = f"{arch}-pc-linux" + llvm_path = os.path.join(llvm_source, "llvm") build_path = os.path.join(llvm_build_path, f"{warp.config.mode}-{ arch}") install_path = os.path.join(llvm_install_path, f"{warp.config.mode}-{ arch}") @@ -278,10 +275,17 @@ def build_from_source_for_arch(args, arch): def build_from_source(args): - build_from_source_for_arch(args, "x86_64") + print("Building Clang/LLVM from source...") + + if args.llvm_source_path is not None: + llvm_source = args.llvm_source_path + else: + llvm_source = llvm_project_path + + build_from_source_for_arch(args, "x86_64", llvm_source) if sys.platform == "darwin": - build_from_source_for_arch(args, "arm64") + build_from_source_for_arch(args, "arm64", llvm_source) # build warp-clang.dll From 5f0633d91e43e4eae64e2198c6fc71adb18a4856 Mon Sep 17 00:00:00 2001 From: Eric Heiden Date: Sun, 3 Dec 2023 17:36:22 -0800 Subject: [PATCH 06/50] Flatten faces array for Mesh constructor in URDF parser --- warp/sim/import_urdf.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/warp/sim/import_urdf.py b/warp/sim/import_urdf.py index 974f98bb5..b1458b6da 100644 --- a/warp/sim/import_urdf.py +++ b/warp/sim/import_urdf.py @@ -180,7 +180,7 @@ def parse_shapes(link, collisions, density, incoming_xform=None): # multiple meshes are contained in a scene for geom in m.geometry.values(): vertices = np.array(geom.vertices, dtype=np.float32) * scaling - faces = np.array(geom.faces, dtype=np.int32) + faces = np.array(geom.faces.flatten(), dtype=np.int32) mesh = Mesh(vertices, faces) builder.add_shape_mesh( body=link, @@ -198,7 +198,7 @@ def parse_shapes(link, collisions, density, incoming_xform=None): else: # a single mesh vertices = np.array(m.vertices, dtype=np.float32) * scaling - faces = np.array(m.faces, dtype=np.int32) + faces = np.array(m.faces.flatten(), dtype=np.int32) mesh = Mesh(vertices, faces) builder.add_shape_mesh( body=link, From 77e99d013aed5e0e94772d55b56d1c0e30b54116 Mon Sep 17 00:00:00 2001 From: Gilles Daviet Date: Sun, 3 Dec 2023 17:53:19 -0800 Subject: [PATCH 07/50] [warp.fem] Add point basis space and explicit point-based quadrature --- docs/modules/fem.rst | 8 +- examples/fem/example_apic_fluid.py | 4 +- warp/fem/__init__.py | 4 +- warp/fem/integrate.py | 479 +++++++++++-------- warp/fem/quadrature/__init__.py | 2 +- warp/fem/quadrature/pic_quadrature.py | 191 ++++++-- warp/fem/quadrature/quadrature.py | 90 +++- warp/fem/space/__init__.py | 2 +- warp/fem/space/basis_space.py | 220 +++++++-- warp/fem/space/grid_2d_function_space.py | 4 +- warp/fem/space/grid_3d_function_space.py | 4 +- warp/fem/space/hexmesh_function_space.py | 4 +- warp/fem/space/quadmesh_2d_function_space.py | 4 +- warp/fem/space/tetmesh_function_space.py | 4 +- warp/fem/space/topology.py | 10 + warp/fem/space/trimesh_2d_function_space.py | 4 +- warp/tests/test_fem.py | 215 ++++++--- 17 files changed, 854 insertions(+), 395 deletions(-) diff --git a/docs/modules/fem.rst b/docs/modules/fem.rst index 359e42df9..75c4e6ed8 100644 --- a/docs/modules/fem.rst +++ b/docs/modules/fem.rst @@ -275,6 +275,9 @@ Geometry .. autoclass:: NodalQuadrature :show-inheritance: +.. autoclass:: ExplicitQuadrature + :show-inheritance: + .. autoclass:: PicQuadrature :show-inheritance: @@ -300,6 +303,9 @@ Function Spaces .. autoclass:: SkewSymmetricTensorMapper :show-inheritance: +.. autoclass:: PointBasisSpace + :show-inheritance: + Fields ------ @@ -350,7 +356,7 @@ Interface classes are not meant to be constructed directly, but can be derived f :members: dimension, geometry, node_count, element_node_indices, trace .. autoclass:: BasisSpace - :members: topology, geometry, shape, node_positions + :members: topology, geometry, node_positions .. autoclass:: warp.fem.space.shape.ShapeFunction diff --git a/examples/fem/example_apic_fluid.py b/examples/fem/example_apic_fluid.py index 1470c638f..211602f3c 100644 --- a/examples/fem/example_apic_fluid.py +++ b/examples/fem/example_apic_fluid.py @@ -64,8 +64,6 @@ def update_particles( pos_proj = domain(lookup(domain, pos_adv)) pos[s.qp_index] = pos_proj - return 0.0 - @integrand def velocity_boundary_projector_form(s: Sample, domain: Domain, u: Field, v: Field): @@ -331,7 +329,7 @@ def update(self): ) # (A)PIC advection - fem.integrate( + fem.interpolate( update_particles, quadrature=pic, values={ diff --git a/warp/fem/__init__.py b/warp/fem/__init__.py index 9a4091a1e..fe237a399 100644 --- a/warp/fem/__init__.py +++ b/warp/fem/__init__.py @@ -2,12 +2,12 @@ from .geometry import GeometryPartition, LinearGeometryPartition, ExplicitGeometryPartition from .space import FunctionSpace, make_polynomial_space, ElementBasis -from .space import BasisSpace, make_polynomial_basis_space, make_collocated_function_space +from .space import BasisSpace, PointBasisSpace, make_polynomial_basis_space, make_collocated_function_space from .space import DofMapper, SkewSymmetricTensorMapper, SymmetricTensorMapper from .space import SpaceTopology, SpacePartition, SpaceRestriction, make_space_partition, make_space_restriction from .domain import GeometryDomain, Cells, Sides, BoundarySides, FrontierSides -from .quadrature import Quadrature, RegularQuadrature, NodalQuadrature, PicQuadrature +from .quadrature import Quadrature, RegularQuadrature, NodalQuadrature, ExplicitQuadrature, PicQuadrature from .polynomial import Polynomial from .field import FieldLike, DiscreteField, make_test, make_trial, make_restriction diff --git a/warp/fem/integrate.py b/warp/fem/integrate.py index 409591403..0230aa663 100644 --- a/warp/fem/integrate.py +++ b/warp/fem/integrate.py @@ -420,36 +420,6 @@ def visit_Call(self, call: ast.Call): return call -def get_integrate_null_kernel( - integrand_func: wp.Function, - domain: GeometryDomain, - quadrature: Quadrature, - FieldStruct: wp.codegen.Struct, - ValueStruct: wp.codegen.Struct, -): - def integrate_kernel_fn( - qp_arg: quadrature.Arg, - domain_arg: domain.ElementArg, - domain_index_arg: domain.ElementIndexArg, - fields: FieldStruct, - values: ValueStruct, - ): - element_index = domain.element_index(domain_index_arg, wp.tid()) - - test_dof_index = NULL_DOF_INDEX - trial_dof_index = NULL_DOF_INDEX - - qp_point_count = quadrature.point_count(domain_arg, qp_arg, element_index) - for k in range(qp_point_count): - qp_index = quadrature.point_index(domain_arg, qp_arg, element_index, k) - qp_coords = quadrature.point_coords(domain_arg, qp_arg, element_index, k) - qp_weight = quadrature.point_weight(domain_arg, qp_arg, element_index, k) - sample = Sample(element_index, qp_coords, qp_index, qp_weight, test_dof_index, trial_dof_index) - integrand_func(sample, fields, values) - - return integrate_kernel_fn - - def get_integrate_constant_kernel( integrand_func: wp.Function, domain: GeometryDomain, @@ -477,7 +447,7 @@ def integrate_kernel_fn( qp_index = quadrature.point_index(domain_arg, qp_arg, element_index, k) coords = quadrature.point_coords(domain_arg, qp_arg, element_index, k) qp_weight = quadrature.point_weight(domain_arg, qp_arg, element_index, k) - + sample = Sample(element_index, coords, qp_index, qp_weight, test_dof_index, trial_dof_index) vol = domain.element_measure(domain_arg, sample) @@ -497,6 +467,7 @@ def get_integrate_linear_kernel( FieldStruct: wp.codegen.Struct, ValueStruct: wp.codegen.Struct, test: TestField, + output_dtype, accumulate_dtype, ): def integrate_kernel_fn( @@ -506,32 +477,36 @@ def integrate_kernel_fn( test_arg: test.space_restriction.NodeArg, fields: FieldStruct, values: ValueStruct, - result: wp.array2d(dtype=accumulate_dtype), + result: wp.array2d(dtype=output_dtype), ): - local_node_index = wp.tid() + local_node_index, test_dof = wp.tid() node_index = test.space_restriction.node_partition_index(test_arg, local_node_index) element_count = test.space_restriction.node_element_count(test_arg, local_node_index) trial_dof_index = NULL_DOF_INDEX + val_sum = accumulate_dtype(0.0) + for n in range(element_count): node_element_index = test.space_restriction.node_element_index(test_arg, local_node_index, n) element_index = domain.element_index(domain_index_arg, node_element_index.domain_element_index) + test_dof_index = DofIndex(node_element_index.node_index_in_element, test_dof) + qp_point_count = quadrature.point_count(domain_arg, qp_arg, element_index) for k in range(qp_point_count): qp_index = quadrature.point_index(domain_arg, qp_arg, element_index, k) - coords = quadrature.point_coords(domain_arg, qp_arg, element_index, k) - + qp_coords = quadrature.point_coords(domain_arg, qp_arg, element_index, k) qp_weight = quadrature.point_weight(domain_arg, qp_arg, element_index, k) - vol = domain.element_measure(domain_arg, make_free_sample(element_index, coords)) - for i in range(test.space.VALUE_DOF_COUNT): - test_dof_index = DofIndex(node_element_index.node_index_in_element, i) - sample = Sample(element_index, coords, qp_index, qp_weight, test_dof_index, trial_dof_index) - val = integrand_func(sample, fields, values) + vol = domain.element_measure(domain_arg, make_free_sample(element_index, qp_coords)) + + sample = Sample(element_index, qp_coords, qp_index, qp_weight, test_dof_index, trial_dof_index) + val = integrand_func(sample, fields, values) + + val_sum += accumulate_dtype(qp_weight * vol * val) - result[node_index, i] = result[node_index, i] + accumulate_dtype(qp_weight * vol * val) + result[node_index, test_dof] = output_dtype(val_sum) return integrate_kernel_fn @@ -542,6 +517,7 @@ def get_integrate_linear_nodal_kernel( FieldStruct: wp.codegen.Struct, ValueStruct: wp.codegen.Struct, test: TestField, + output_dtype, accumulate_dtype, ): def integrate_kernel_fn( @@ -550,7 +526,7 @@ def integrate_kernel_fn( test_restriction_arg: test.space_restriction.NodeArg, fields: FieldStruct, values: ValueStruct, - result: wp.array2d(dtype=accumulate_dtype), + result: wp.array2d(dtype=output_dtype), ): local_node_index, dof = wp.tid() @@ -595,7 +571,7 @@ def integrate_kernel_fn( val_sum += accumulate_dtype(node_weight * vol * val) - result[node_index, dof] = val_sum + result[node_index, dof] = output_dtype(val_sum) return integrate_kernel_fn @@ -608,6 +584,7 @@ def get_integrate_bilinear_kernel( ValueStruct: wp.codegen.Struct, test: TestField, trial: TrialField, + output_dtype, accumulate_dtype, ): NODES_PER_ELEMENT = trial.space.topology.NODES_PER_ELEMENT @@ -624,19 +601,26 @@ def integrate_kernel_fn( row_offsets: wp.array(dtype=int), triplet_rows: wp.array(dtype=int), triplet_cols: wp.array(dtype=int), - triplet_values: wp.array3d(dtype=accumulate_dtype), + triplet_values: wp.array3d(dtype=output_dtype), ): - test_local_node_index = wp.tid() + test_local_node_index, trial_node, test_dof, trial_dof = wp.tid() element_count = test.space_restriction.node_element_count(test_arg, test_local_node_index) test_node_index = test.space_restriction.node_partition_index(test_arg, test_local_node_index) + trial_dof_index = DofIndex(trial_node, trial_dof) + for element in range(element_count): test_element_index = test.space_restriction.node_element_index(test_arg, test_local_node_index, element) element_index = domain.element_index(domain_index_arg, test_element_index.domain_element_index) qp_point_count = quadrature.point_count(domain_arg, qp_arg, element_index) - start_offset = (row_offsets[test_node_index] + element) * NODES_PER_ELEMENT + test_dof_index = DofIndex( + test_element_index.node_index_in_element, + test_dof, + ) + + val_sum = accumulate_dtype(0.0) for k in range(qp_point_count): qp_index = quadrature.point_index(domain_arg, qp_arg, element_index, k) @@ -645,42 +629,28 @@ def integrate_kernel_fn( qp_weight = quadrature.point_weight(domain_arg, qp_arg, element_index, k) vol = domain.element_measure(domain_arg, make_free_sample(element_index, coords)) - offset_cur = start_offset - - for trial_n in range(NODES_PER_ELEMENT): - for i in range(test.space.VALUE_DOF_COUNT): - for j in range(trial.space.VALUE_DOF_COUNT): - test_dof_index = DofIndex( - test_element_index.node_index_in_element, - i, - ) - trial_dof_index = DofIndex(trial_n, j) - sample = Sample( - element_index, - coords, - qp_index, - qp_weight, - test_dof_index, - trial_dof_index, - ) - val = integrand_func(sample, fields, values) - triplet_values[offset_cur, i, j] = triplet_values[offset_cur, i, j] + accumulate_dtype( - qp_weight * vol * val - ) - - offset_cur += 1 - - # Set column indices - offset_cur = start_offset - for trial_n in range(NODES_PER_ELEMENT): + sample = Sample( + element_index, + coords, + qp_index, + qp_weight, + test_dof_index, + trial_dof_index, + ) + val = integrand_func(sample, fields, values) + val_sum += accumulate_dtype(qp_weight * vol * val) + + block_offset = (row_offsets[test_node_index] + element) * NODES_PER_ELEMENT + trial_node + triplet_values[block_offset, test_dof, trial_dof] = output_dtype(val_sum) + + # Set row and column indices + if test_dof == 0 and trial_dof == 0: trial_node_index = trial.space_partition.partition_node_index( trial_partition_arg, - trial.space.topology.element_node_index(domain_arg, trial_topology_arg, element_index, trial_n), + trial.space.topology.element_node_index(domain_arg, trial_topology_arg, element_index, trial_node), ) - - triplet_rows[offset_cur] = test_node_index - triplet_cols[offset_cur] = trial_node_index - offset_cur += 1 + triplet_rows[block_offset] = test_node_index + triplet_cols[block_offset] = trial_node_index return integrate_kernel_fn @@ -691,6 +661,7 @@ def get_integrate_bilinear_nodal_kernel( FieldStruct: wp.codegen.Struct, ValueStruct: wp.codegen.Struct, test: TestField, + output_dtype, accumulate_dtype, ): def integrate_kernel_fn( @@ -701,7 +672,7 @@ def integrate_kernel_fn( values: ValueStruct, triplet_rows: wp.array(dtype=int), triplet_cols: wp.array(dtype=int), - triplet_values: wp.array3d(dtype=accumulate_dtype), + triplet_values: wp.array3d(dtype=output_dtype), ): local_node_index, test_dof, trial_dof = wp.tid() @@ -729,7 +700,6 @@ def integrate_kernel_fn( node_element_index.node_index_in_element, ) - test_dof_index = DofIndex(node_element_index.node_index_in_element, test_dof) trial_dof_index = DofIndex(node_element_index.node_index_in_element, trial_dof) @@ -746,7 +716,7 @@ def integrate_kernel_fn( val_sum += accumulate_dtype(node_weight * vol * val) - triplet_values[local_node_index, test_dof, trial_dof] = val_sum + triplet_values[local_node_index, test_dof, trial_dof] = output_dtype(val_sum) triplet_rows[local_node_index] = node_index triplet_cols[local_node_index] = node_index @@ -763,9 +733,12 @@ def _generate_integrate_kernel( trial: Optional[TrialField], trial_name: str, fields: Dict[str, FieldLike], + output_dtype: type, accumulate_dtype: type, kernel_options: Dict[str, Any] = {}, ) -> wp.Kernel: + output_dtype = wp.types.type_scalar_type(output_dtype) + # Extract field arguments from integrand field_args, value_args, domain_name, sample_name = _get_integrand_field_arguments( integrand, fields=fields, domain=domain @@ -775,7 +748,7 @@ def _generate_integrate_kernel( ValueStruct = _gen_value_struct(value_args) # Check if kernel exist in cache - kernel_suffix = f"_itg_{wp.types.type_typestr(accumulate_dtype)}_{domain.name}_{FieldStruct.key}" + kernel_suffix = f"_itg_{wp.types.type_typestr(output_dtype)}{wp.types.type_typestr(accumulate_dtype)}_{domain.name}_{FieldStruct.key}" if nodal: kernel_suffix += "_nodal" else: @@ -819,6 +792,7 @@ def _generate_integrate_kernel( FieldStruct, ValueStruct, test=test, + output_dtype=output_dtype, accumulate_dtype=accumulate_dtype, ) else: @@ -829,6 +803,7 @@ def _generate_integrate_kernel( FieldStruct, ValueStruct, test=test, + output_dtype=output_dtype, accumulate_dtype=accumulate_dtype, ) else: @@ -839,6 +814,7 @@ def _generate_integrate_kernel( FieldStruct, ValueStruct, test=test, + output_dtype=output_dtype, accumulate_dtype=accumulate_dtype, ) else: @@ -850,6 +826,7 @@ def _generate_integrate_kernel( ValueStruct, test=test, trial=trial, + output_dtype=output_dtype, accumulate_dtype=accumulate_dtype, ) @@ -949,32 +926,46 @@ def _launch_integrate_kernel( # Linear form if trial is None: - if test.space.VALUE_DOF_COUNT == 1: - accumulate_array_dtype = accumulate_dtype - else: - accumulate_array_dtype = cache.cached_vec_type(length=test.space.VALUE_DOF_COUNT, dtype=accumulate_dtype) - - if output is not None and output.size < test.space_partition.node_count(): - raise RuntimeError(f"Output array must be of size at least {test.space_partition.node_count()}") - - accumulate_in_place = wp.types.types_equal(accumulate_array_dtype, output_dtype) - # If an output array is provided with the correct type, accumulate directly into it # Otherwise, grab a temporary array - if output is not None and accumulate_in_place: - accumulate_array = output - else: - accumulate_temporary = cache.borrow_temporary( + if output is None: + if type_length(output_dtype) == test.space.VALUE_DOF_COUNT: + output_shape = (test.space_partition.node_count(),) + elif type_length(output_dtype) == 1: + output_shape = (test.space_partition.node_count(), test.space.VALUE_DOF_COUNT) + else: + raise RuntimeError( + f"Incompatible output type {wp.types.type_repr(output_dtype)}, must be scalar or vector of length {test.space.VALUE_DOF_COUNT}" + ) + + output_temporary = cache.borrow_temporary( temporary_store=temporary_store, - shape=test.space_partition.node_count(), - dtype=accumulate_array_dtype, + shape=output_shape, + dtype=output_dtype, device=device, - requires_grad=output is not None and output.requires_grad, ) - accumulate_array = accumulate_temporary.array + + output = output_temporary.array + + else: + output_temporary = None + + if output.shape[0] < test.space_partition.node_count(): + raise RuntimeError(f"Output array must have at least {test.space_partition.node_count()} rows") + + output_dtype = output.dtype + if type_length(output_dtype) != test.space.VALUE_DOF_COUNT: + if type_length(output_dtype) != 1: + raise RuntimeError( + f"Incompatible output type {wp.types.type_repr(output_dtype)}, must be scalar or vector of length {test.space.VALUE_DOF_COUNT}" + ) + if output.ndim != 2 and output.shape[1] != test.space.VALUE_DOF_COUNT: + raise RuntimeError( + f"Incompatible output array shape, last dimension must be of size {test.space.VALUE_DOF_COUNT}" + ) # Launch the integration on the kernel on a 2d scalar view of the actual array - accumulate_array.zero_() + output.zero_() def as_2d_array(array): return wp.array( @@ -984,11 +975,11 @@ def as_2d_array(array): owner=False, device=array.device, shape=(test.space_partition.node_count(), test.space.VALUE_DOF_COUNT), - dtype=accumulate_dtype, + dtype=wp.types.type_scalar_type(output_dtype), grad=None if array.grad is None else as_2d_array(array.grad), ) - accumulate_2d_view = as_2d_array(accumulate_array) + output_view = output if output.ndim == 2 else as_2d_array(output) if nodal: wp.launch( @@ -1000,14 +991,14 @@ def as_2d_array(array): test_arg, field_arg_values, value_struct_values, - accumulate_2d_view, + output_view, ], device=device, ) else: wp.launch( kernel=kernel, - dim=test.space_restriction.node_count(), + dim=(test.space_restriction.node_count(), test.space.VALUE_DOF_COUNT), inputs=[ qp_arg, domain_elt_arg, @@ -1015,47 +1006,23 @@ def as_2d_array(array): test_arg, field_arg_values, value_struct_values, - accumulate_2d_view, + output_view, ], device=device, ) - # Accumulate and output dtypes are simular -- return accumulation array directly - if output == accumulate_array: - return output + if output_temporary is not None: + return output_temporary.detach() - if accumulate_in_place: - return accumulate_temporary.detach() - - # Different types -- need to cast result - if output is not None: - cast_result = output - elif type_length(output_dtype) == test.space.VALUE_DOF_COUNT: - cast_result = wp.empty( - dtype=output_dtype, - shape=accumulate_array.shape, - device=device, - requires_grad=accumulate_array.requires_grad, - ) - else: - cast_result = wp.empty( - dtype=output_dtype, - shape=accumulate_2d_view.shape, - device=device, - requires_grad=accumulate_array.requires_grad, - ) - - array_cast(in_array=accumulate_array, out_array=cast_result) - accumulate_temporary.release() # Do not wait for garbage collection - return cast_result + return output # Bilinear form if test.space.VALUE_DOF_COUNT == 1 and trial.space.VALUE_DOF_COUNT == 1: - block_type = accumulate_dtype + block_type = output_dtype else: block_type = cache.cached_mat_type( - shape=(test.space.VALUE_DOF_COUNT, trial.space.VALUE_DOF_COUNT), dtype=accumulate_dtype + shape=(test.space.VALUE_DOF_COUNT, trial.space.VALUE_DOF_COUNT), dtype=output_dtype ) if nodal: @@ -1072,7 +1039,7 @@ def as_2d_array(array): test.space.VALUE_DOF_COUNT, trial.space.VALUE_DOF_COUNT, ), - dtype=accumulate_dtype, + dtype=output_dtype, device=device, ) triplet_cols = triplet_cols_temp.array @@ -1105,7 +1072,12 @@ def as_2d_array(array): trial_topology_arg = trial.space_partition.space_topology.topo_arg_value(device) wp.launch( kernel=kernel, - dim=test.space_restriction.node_count(), + dim=( + test.space_restriction.node_count(), + trial.space.topology.NODES_PER_ELEMENT, + test.space.VALUE_DOF_COUNT, + trial.space.VALUE_DOF_COUNT, + ), inputs=[ qp_arg, domain_elt_arg, @@ -1123,38 +1095,27 @@ def as_2d_array(array): device=device, ) - compress_in_place = accumulate_dtype == output_dtype - if output is not None: if output.nrow != test.space_partition.node_count() or output.ncol != trial.space_partition.node_count(): raise RuntimeError( f"Output matrix must have {test.space_partition.node_count()} rows and {trial.space_partition.node_count()} columns of blocks" ) - if output is not None and compress_in_place: - bsr_matrix = output else: - bsr_matrix = bsr_zeros( + output = bsr_zeros( rows_of_blocks=test.space_partition.node_count(), cols_of_blocks=trial.space_partition.node_count(), block_type=block_type, device=device, ) - - bsr_set_from_triplets(bsr_matrix, triplet_rows, triplet_cols, triplet_values) + + bsr_set_from_triplets(output, triplet_rows, triplet_cols, triplet_values) # Do not wait for garbage collection triplet_values_temp.release() triplet_rows_temp.release() triplet_cols_temp.release() - if compress_in_place: - return bsr_matrix - - if output is None: - return bsr_copy(bsr_matrix, scalar_type=output_dtype) - - bsr_assign(src=bsr_matrix, dest=output) return output @@ -1181,7 +1142,7 @@ def integrate( quadrature: Quadrature formula. If None, deduced from domain and fields degree. nodal: For linear or bilinear form only, use the test function nodes as the quadrature points. Assumes Lagrange interpolation functions are used, and no differential or DG operator is evaluated on the test or trial functions. fields: Discrete, test, and trial fields to be passed to the integrand. Keys in the dictionary must match integrand parameter names. - values: Additional variable values to be passed to the integrand, can by of any type accepted by warp kernel launchs. Keys in the dictionary must match integrand parameter names. + values: Additional variable values to be passed to the integrand, can be of any type accepted by warp kernel launchs. Keys in the dictionary must match integrand parameter names. temporary_store: shared pool from which to allocate temporary arrays accumulate_dtype: Scalar type to be used for accumulating integration samples output: Sparse matrix or warp array into which to store the result of the integration @@ -1246,6 +1207,7 @@ def integrate( trial_name=trial_name, fields=fields, accumulate_dtype=accumulate_dtype, + output_dtype=output_dtype, kernel_options=kernel_options, ) @@ -1268,7 +1230,7 @@ def integrate( ) -def get_interpolate_kernel( +def get_interpolate_to_field_kernel( integrand_func: wp.Function, domain: GeometryDomain, FieldStruct: wp.codegen.Struct, @@ -1277,7 +1239,7 @@ def get_interpolate_kernel( ): value_type = dest.space.dtype - def interpolate_kernel_fn( + def interpolate_to_field_kernel_fn( domain_arg: domain.ElementArg, domain_index_arg: domain.ElementIndexArg, dest_node_arg: dest.space_restriction.NodeArg, @@ -1331,12 +1293,82 @@ def interpolate_kernel_fn( if vol_sum > 0.0: dest.field.set_node_value(dest_eval_arg, node_index, val_sum / vol_sum) - return interpolate_kernel_fn + return interpolate_to_field_kernel_fn + + +def get_interpolate_to_array_kernel( + integrand_func: wp.Function, + domain: GeometryDomain, + quadrature: Quadrature, + FieldStruct: wp.codegen.Struct, + ValueStruct: wp.codegen.Struct, + value_type: type, +): + def interpolate_to_array_kernel_fn( + qp_arg: quadrature.Arg, + domain_arg: quadrature.domain.ElementArg, + domain_index_arg: quadrature.domain.ElementIndexArg, + fields: FieldStruct, + values: ValueStruct, + result: wp.array(dtype=value_type), + ): + element_index = domain.element_index(domain_index_arg, wp.tid()) + + test_dof_index = NULL_DOF_INDEX + trial_dof_index = NULL_DOF_INDEX + + qp_point_count = quadrature.point_count(domain_arg, qp_arg, element_index) + for k in range(qp_point_count): + qp_index = quadrature.point_index(domain_arg, qp_arg, element_index, k) + coords = quadrature.point_coords(domain_arg, qp_arg, element_index, k) + qp_weight = quadrature.point_weight(domain_arg, qp_arg, element_index, k) + + sample = Sample(element_index, coords, qp_index, qp_weight, test_dof_index, trial_dof_index) + + result[qp_index] = integrand_func(sample, fields, values) + return interpolate_to_array_kernel_fn -def _generate_interpolate_kernel(integrand: Integrand, dest: FieldLike, fields: Dict[str, FieldLike]) -> wp.Kernel: - domain = dest.domain +def get_interpolate_nonvalued_kernel( + integrand_func: wp.Function, + domain: GeometryDomain, + quadrature: Quadrature, + FieldStruct: wp.codegen.Struct, + ValueStruct: wp.codegen.Struct, +): + def interpolate_nonvalued_kernel_fn( + qp_arg: quadrature.Arg, + domain_arg: quadrature.domain.ElementArg, + domain_index_arg: quadrature.domain.ElementIndexArg, + fields: FieldStruct, + values: ValueStruct, + ): + element_index = domain.element_index(domain_index_arg, wp.tid()) + + test_dof_index = NULL_DOF_INDEX + trial_dof_index = NULL_DOF_INDEX + + qp_point_count = quadrature.point_count(domain_arg, qp_arg, element_index) + for k in range(qp_point_count): + qp_index = quadrature.point_index(domain_arg, qp_arg, element_index, k) + coords = quadrature.point_coords(domain_arg, qp_arg, element_index, k) + qp_weight = quadrature.point_weight(domain_arg, qp_arg, element_index, k) + + sample = Sample(element_index, coords, qp_index, qp_weight, test_dof_index, trial_dof_index) + integrand_func(sample, fields, values) + + return interpolate_nonvalued_kernel_fn + + +def _generate_interpolate_kernel( + integrand: Integrand, + domain: GeometryDomain, + dest: Optional[Union[FieldLike, wp.array]], + quadrature: Optional[Quadrature], + fields: Dict[str, FieldLike], + kernel_options: Dict[str, Any] = {}, +) -> wp.Kernel: # Extract field arguments from integrand field_args, value_args, domain_name, sample_name = _get_integrand_field_arguments( integrand, fields=fields, domain=domain @@ -1354,9 +1386,14 @@ def _generate_interpolate_kernel(integrand: Integrand, dest: FieldLike, fields: ValueStruct = _gen_value_struct(value_args) # Check if kernel exist in cache - kernel_suffix = ( - f"_itp_{FieldStruct.key}_{dest.domain.name}_{dest.space_restriction.space_partition.name}_{dest.space.name}" - ) + if isinstance(dest, FieldRestriction): + kernel_suffix = ( + f"_itp_{FieldStruct.key}_{dest.domain.name}_{dest.space_restriction.space_partition.name}_{dest.space.name}" + ) + elif wp.types.is_array(dest): + kernel_suffix = f"_itp_{FieldStruct.key}_{quadrature.name}_{wp.types.type_repr(dest.dtype)}" + else: + kernel_suffix = f"_itp_{FieldStruct.key}_{quadrature.name}" kernel = cache.get_integrand_kernel( integrand=integrand, @@ -1366,18 +1403,37 @@ def _generate_interpolate_kernel(integrand: Integrand, dest: FieldLike, fields: return kernel, FieldStruct, ValueStruct # Generate interpolation kernel - interpolate_kernel_fn = get_interpolate_kernel( - integrand_func, - domain, - dest=dest, - FieldStruct=FieldStruct, - ValueStruct=ValueStruct, - ) + if isinstance(dest, FieldRestriction): + interpolate_kernel_fn = get_interpolate_to_field_kernel( + integrand_func, + domain, + dest=dest, + FieldStruct=FieldStruct, + ValueStruct=ValueStruct, + ) + elif wp.types.is_array(dest): + interpolate_kernel_fn = get_interpolate_to_array_kernel( + integrand_func, + domain=domain, + quadrature=quadrature, + value_type=dest.dtype, + FieldStruct=FieldStruct, + ValueStruct=ValueStruct, + ) + else: + interpolate_kernel_fn = get_interpolate_nonvalued_kernel( + integrand_func, + domain=domain, + quadrature=quadrature, + FieldStruct=FieldStruct, + ValueStruct=ValueStruct, + ) kernel = cache.get_integrand_kernel( integrand=integrand, kernel_fn=interpolate_kernel_fn, suffix=kernel_suffix, + kernel_options=kernel_options, code_transformers=[ PassFieldArgsToIntegrand( arg_names=integrand.argspec.args, @@ -1396,16 +1452,16 @@ def _launch_interpolate_kernel( kernel: wp.kernel, FieldStruct: wp.codegen.Struct, ValueStruct: wp.codegen.Struct, - dest: FieldLike, + domain: GeometryDomain, + dest: Optional[Union[FieldRestriction, wp.array]], + quadrature: Optional[Quadrature], fields: Dict[str, FieldLike], values: Dict[str, Any], device, ) -> wp.Kernel: # Set-up launch arguments - elt_arg = dest.domain.element_arg_value(device=device) - elt_index_arg = dest.domain.element_index_arg_value(device=device) - dest_node_arg = dest.space_restriction.node_arg(device=device) - dest_eval_arg = dest.field.eval_arg_value(device=device) + elt_arg = domain.element_arg_value(device=device) + elt_index_arg = domain.element_index_arg_value(device=device) field_arg_values = FieldStruct() for k, v in fields.items(): @@ -1415,37 +1471,65 @@ def _launch_interpolate_kernel( for k, v in values.items(): setattr(value_struct_values, k, v) - wp.launch( - kernel=kernel, - dim=dest.space_restriction.node_count(), - inputs=[ - elt_arg, - elt_index_arg, - dest_node_arg, - dest_eval_arg, - field_arg_values, - value_struct_values, - ], - device=device, - ) + if isinstance(dest, FieldRestriction): + dest_node_arg = dest.space_restriction.node_arg(device=device) + dest_eval_arg = dest.field.eval_arg_value(device=device) + + wp.launch( + kernel=kernel, + dim=dest.space_restriction.node_count(), + inputs=[ + elt_arg, + elt_index_arg, + dest_node_arg, + dest_eval_arg, + field_arg_values, + value_struct_values, + ], + device=device, + ) + elif wp.types.is_array(dest): + qp_arg = quadrature.arg_value(device) + wp.launch( + kernel=kernel, + dim=domain.element_count(), + inputs=[qp_arg, elt_arg, elt_index_arg, field_arg_values, value_struct_values, dest], + device=device, + ) + else: + qp_arg = quadrature.arg_value(device) + wp.launch( + kernel=kernel, + dim=domain.element_count(), + inputs=[qp_arg, elt_arg, elt_index_arg, field_arg_values, value_struct_values], + device=device, + ) def interpolate( integrand: Integrand, - dest: Union[DiscreteField, FieldRestriction], + dest: Optional[Union[DiscreteField, FieldRestriction, wp.array]] = None, + quadrature: Optional[Quadrature] = None, fields: Dict[str, FieldLike] = {}, values: Dict[str, Any] = {}, device=None, + kernel_options: Dict[str, Any] = {}, ): """ - Interpolates a function and assigns the result to a discrete field. + Interpolates a function at a finite set of sample points and optionally assigns the result to a discrete field or a raw warp array. Args: integrand: Function to be interpolated, must have :func:`integrand` decorator - dest: Discrete field, or restriction of a discrete field to a domain, to which the interpolation result will be assigned + dest: Where to store the interpolation result. Can be either + + - a :class:`DiscreteField`, or restriction of a discrete field to a domain (from :func:`make_restriction`). In this case, interpolation will be performed at each node. + - a normal warp array. In this case, the `quadrature` argument defining the interpolation locations must be provided and the result of the `integrand` at each quadrature point will be assigned to the array. + - ``None``. In this case, the `quadrature` argument must also be provided and the `integrand` function is reponsible for dealing with the interpolation result. + quadrature: Quadrature formula defining the interpolation samples if `dest` is not a discrete field or field restriction. fields: Discrete fields to be passed to the integrand. Keys in the dictionary must match integrand parameters names. - values: Additional variable values to be passed to the integrand, can by of any type accepted by warp kernel launchs. Keys in the dictionary must match integrand parameter names. + values: Additional variable values to be passed to the integrand, can be of any type accepted by warp kernel launchs. Keys in the dictionary must match integrand parameter names. device: Device on which to perform the interpolation + kernel_options: Overloaded options to be passed to the kernel builder (e.g, ``{"enable_backward": True}``) """ if not isinstance(integrand, Integrand): raise ValueError("integrand must be tagged with @integrand decorator") @@ -1454,20 +1538,33 @@ def interpolate( if test is not None or trial is not None: raise ValueError("Test or Trial fields should not be used for interpolation") - if not isinstance(dest, FieldRestriction): + if isinstance(dest, DiscreteField): dest = make_restriction(dest) + if isinstance(dest, FieldRestriction): + domain = dest.domain + else: + if quadrature is None: + raise ValueError("When not interpolating to a field, a quadrature formula must be provided") + + domain = quadrature.domain + kernel, FieldStruct, ValueStruct = _generate_interpolate_kernel( integrand=integrand, + domain=domain, dest=dest, + quadrature=quadrature, fields=fields, + kernel_options=kernel_options, ) return _launch_interpolate_kernel( kernel=kernel, FieldStruct=FieldStruct, ValueStruct=ValueStruct, + domain=domain, dest=dest, + quadrature=quadrature, fields=fields, values=values, device=device, diff --git a/warp/fem/quadrature/__init__.py b/warp/fem/quadrature/__init__.py index 6f7798827..5e5b91e5d 100644 --- a/warp/fem/quadrature/__init__.py +++ b/warp/fem/quadrature/__init__.py @@ -1,2 +1,2 @@ -from .quadrature import Quadrature, RegularQuadrature, NodalQuadrature +from .quadrature import Quadrature, RegularQuadrature, NodalQuadrature, ExplicitQuadrature from .pic_quadrature import PicQuadrature diff --git a/warp/fem/quadrature/pic_quadrature.py b/warp/fem/quadrature/pic_quadrature.py index 746e48745..ebed52bfd 100644 --- a/warp/fem/quadrature/pic_quadrature.py +++ b/warp/fem/quadrature/pic_quadrature.py @@ -1,11 +1,11 @@ -from typing import Any +from typing import Union, Tuple, Any, Optional import warp as wp from warp.fem.domain import GeometryDomain -from warp.fem.types import ElementIndex, Coords +from warp.fem.types import ElementIndex, Coords, make_free_sample from warp.fem.utils import compress_node_indices -from warp.fem.cache import cached_arg_value, TemporaryStore, borrow_temporary +from warp.fem.cache import cached_arg_value, TemporaryStore, borrow_temporary, dynamic_kernel from .quadrature import Quadrature @@ -14,24 +14,36 @@ class PicQuadrature(Quadrature): - """Particle-based quadrature formula, using a global set of points irregularely spread out over geometry elements. + """Particle-based quadrature formula, using a global set of points unevenly spread out over geometry elements. Useful for Particle-In-Cell and derived methods. + + Args: + domain: Undelying domain for the qaudrature + positions: Either an array containing the world positions of all particles, or a tuple of arrays containing + the cell indices and coordinates for each particle. Note that the former requires the underlying geometry to + define a global :meth:`Geometry.cell_lookup` method; currently this is only available for :class:`Grid2D` and :class:`Grid3D`. + measures: Array containing the measure (area/volume) of each particle, used to defined the integration weights. + If ``None``, defaults to the cell measure divided by the number of particles in the cell. + temporary_store: shared pool from which to allocate temporary arrays """ def __init__( self, domain: GeometryDomain, - positions: "wp.array()", - measures: "wp.array(dtype=float)", + positions: Union[ + "wp.array(dtype=wp.vecXd)", + Tuple[ + "wp.array(dtype=ElementIndex)", + "wp.array(dtype=Coords)", + ], + ], + measures: Optional["wp.array(dtype=float)"] = None, temporary_store: TemporaryStore = None, ): super().__init__(domain) - self.positions = positions - self.measures = measures - - self._bin_particles(temporary_store) + self._bin_particles(positions, measures, temporary_store) @property def name(self): @@ -61,12 +73,16 @@ def arg_value(self, device) -> Arg: arg = PicQuadrature.Arg() arg.cell_particle_offsets = self._cell_particle_offsets.array.to(device) arg.cell_particle_indices = self._cell_particle_indices.array.to(device) - arg.particle_fraction = self._particle_fraction.array.to(device) - arg.particle_coords = self._particle_coords.array.to(device) + arg.particle_fraction = self._particle_fraction.to(device) + arg.particle_coords = self._particle_coords.to(device) return arg def total_point_count(self): - return self.positions.shape[0] + return self._particle_coords.shape[0] + + def active_cell_count(self): + """Number of cells containing at least one particle""" + return self._cell_count @wp.func def point_count(elt_arg: Any, qp_arg: Arg, element_index: ElementIndex): @@ -109,52 +125,121 @@ def _fill_mask_kernel( i = wp.tid() element_mask[i] = wp.select(element_particle_offsets[i] == element_particle_offsets[i + 1], 1, 0) - def _bin_particles(self, temporary_store: TemporaryStore): - from warp.fem import cache - - @cache.dynamic_kernel(suffix=f"{self.domain.name}") - def bin_particles( - cell_arg_value: self.domain.ElementArg, - positions: wp.array(dtype=self.positions.dtype), - measures: wp.array(dtype=float), - cell_index: wp.array(dtype=ElementIndex), - cell_coords: wp.array(dtype=Coords), - cell_fraction: wp.array(dtype=float), - ): - p = wp.tid() - sample = self.domain.element_lookup(cell_arg_value, positions[p]) + @wp.kernel + def _compute_uniform_fraction( + cell_index: wp.array(dtype=ElementIndex), + cell_particle_offsets: wp.array(dtype=int), + cell_fraction: wp.array(dtype=float), + ): + p = wp.tid() - cell_index[p] = sample.element_index + cell = cell_index[p] + cell_particle_count = cell_particle_offsets[cell + 1] - cell_particle_offsets[cell] - cell_coords[p] = sample.element_coords - cell_fraction[p] = measures[p] / self.domain.element_measure(cell_arg_value, sample) + cell_fraction[p] = 1.0 / float(cell_particle_count) - device = self.positions.device + def _bin_particles(self, positions, measures, temporary_store: TemporaryStore): + if wp.types.is_array(positions): + # Initialize from positions + @dynamic_kernel(suffix=f"{self.domain.name}") + def bin_particles( + cell_arg_value: self.domain.ElementArg, + positions: wp.array(dtype=positions.dtype), + cell_index: wp.array(dtype=ElementIndex), + cell_coords: wp.array(dtype=Coords), + ): + p = wp.tid() + sample = self.domain.element_lookup(cell_arg_value, positions[p]) - cell_index = borrow_temporary(temporary_store, shape=self.positions.shape, dtype=int, device=device) - self._particle_coords = borrow_temporary( - temporary_store, shape=self.positions.shape, dtype=Coords, device=device - ) - self._particle_fraction = borrow_temporary( - temporary_store, shape=self.positions.shape, dtype=float, device=device - ) + cell_index[p] = sample.element_index + cell_coords[p] = sample.element_coords - wp.launch( - dim=self.positions.shape[0], - kernel=bin_particles, - inputs=[ - self.domain.element_arg_value(device), - self.positions, - self.measures, - cell_index.array, - self._particle_coords.array, - self._particle_fraction.array, - ], - device=device, - ) + device = positions.device + + cell_index_temp = borrow_temporary(temporary_store, shape=positions.shape, dtype=int, device=device) + cell_index = cell_index_temp.array + + self._particle_coords_temp = borrow_temporary( + temporary_store, shape=positions.shape, dtype=Coords, device=device + ) + self._particle_coords = self._particle_coords_temp.array + + wp.launch( + dim=positions.shape[0], + kernel=bin_particles, + inputs=[ + self.domain.element_arg_value(device), + positions, + cell_index, + self._particle_coords, + ], + device=device, + ) + + else: + cell_index, self._particle_coords = positions + if cell_index.shape != self._particle_coords.shape: + raise ValueError("Cell index and coordinates arrays must have the same shape") + + cell_index_temp = None + self._particle_coords_temp = None self._cell_particle_offsets, self._cell_particle_indices, self._cell_count, _ = compress_node_indices( - self.domain.geometry_element_count(), cell_index.array + self.domain.geometry_element_count(), cell_index ) - cell_index.release() + self._compute_fraction(cell_index, measures, temporary_store) + + def _compute_fraction(self, cell_index, measures, temporary_store: TemporaryStore): + device = cell_index.device + + self._particle_fraction_temp = borrow_temporary( + temporary_store, shape=cell_index.shape, dtype=float, device=device + ) + self._particle_fraction = self._particle_fraction_temp.array + + if measures is None: + # Split fraction uniformly over all particles in cell + + wp.launch( + dim=cell_index.shape, + kernel=PicQuadrature._compute_uniform_fraction, + inputs=[ + cell_index, + self._cell_particle_offsets.array, + self._particle_fraction, + ], + device=device, + ) + + else: + # Fraction from particle measure + + if measures.shape != cell_index.shape: + raise ValueError("Measures should be an 1d array or length equal to particle count") + + @dynamic_kernel(suffix=f"{self.domain.name}") + def compute_fraction( + cell_arg_value: self.domain.ElementArg, + measures: wp.array(dtype=float), + cell_index: wp.array(dtype=ElementIndex), + cell_coords: wp.array(dtype=Coords), + cell_fraction: wp.array(dtype=float), + ): + p = wp.tid() + sample = make_free_sample(cell_index[p], cell_coords[p]) + + cell_fraction[p] = measures[p] / self.domain.element_measure(cell_arg_value, sample) + + wp.launch( + dim=measures.shape[0], + kernel=compute_fraction, + inputs=[ + self.domain.element_arg_value(device), + measures, + cell_index, + self._particle_coords, + self._particle_fraction, + ], + device=device, + ) diff --git a/warp/fem/quadrature/quadrature.py b/warp/fem/quadrature/quadrature.py index 3712080fc..e0208da3d 100644 --- a/warp/fem/quadrature/quadrature.py +++ b/warp/fem/quadrature/quadrature.py @@ -35,33 +35,37 @@ def arg_value(self, device) -> "Arg": def total_point_count(self): """Total number of quadrature points over the domain""" - pass + raise NotImplementedError() + + def points_per_element(self): + """Number of points per element if constant, or ``None`` if varying""" + return None @staticmethod def point_count(elt_arg: "domain.GeometryDomain.ElementArg", qp_arg: Arg, element_index: ElementIndex): """Number of quadrature points for a given element""" - pass + raise NotImplementedError() @staticmethod def point_coords( elt_arg: "domain.GeometryDomain.ElementArg", qp_arg: Arg, element_index: ElementIndex, qp_index: int ): """Coordinates in element of the element's qp_index'th quadrature point""" - pass + raise NotImplementedError() @staticmethod def point_weight( elt_arg: "domain.GeometryDomain.ElementArg", qp_arg: Arg, element_index: ElementIndex, qp_index: int ): """Weight of the element's qp_index'th quadrature point""" - pass + raise NotImplementedError() @staticmethod def point_index( elt_arg: "domain.GeometryDomain.ElementArg", qp_arg: Arg, element_index: ElementIndex, qp_index: int ): """Global index of the element's qp_index'th quadrature point""" - pass + raise NotImplementedError() def __str__(self) -> str: return self.name @@ -98,13 +102,14 @@ def __init__( @property def name(self): - return ( - f"{self.__class__.__name__}_{self.domain.name}_{self.family}_{self.order}" - ) + return f"{self.__class__.__name__}_{self.domain.name}_{self.family}_{self.order}" def total_point_count(self): return len(self.points) * self.domain.geometry_element_count() + def points_per_element(self): + return self._N + @property def points(self): return self._element_quadrature[0] @@ -153,7 +158,7 @@ def point_index(elt_arg: self.domain.ElementArg, qp_arg: self.Arg, element_index class NodalQuadrature(Quadrature): """Quadrature using space node points as quadrature points - Note that in constant to the `nodal=True` flag for :func:`integrate`, this quadrature odes not make any assumption + Note that in contrast to the `nodal=True` flag for :func:`integrate`, this quadrature odes not make any assumption about orthogonality of shape functions, and is thus safe to use for arbitrary integrands. """ @@ -176,6 +181,9 @@ def name(self): def total_point_count(self): return self._space.node_count() + def points_per_element(self): + return self._space.topology.NODES_PER_ELEMENT + def _make_arg(self): @cache.dynamic_struct(suffix=self.name) class Arg: @@ -220,3 +228,67 @@ def point_index(elt_arg: self.domain.ElementArg, qp_arg: self.Arg, element_index return self._space.topology.element_node_index(elt_arg, qp_arg.topo_arg, element_index, qp_index) return point_index + + +class ExplicitQuadrature(Quadrature): + """Quadrature using explicit per-cell points and weights. The number of quadrature points per cell is assumed + to be constant and deduced from the shape of the points and weights arrays. + + Args: + domain: Domain of definition of the quadrature formula + points: 2d array of shape ``(domain.geometry_element-count(), points_per_cell)`` containing the coordinates of each quadrature point. + weights: 2d array of shape ``(domain.geometry_element-count(), points_per_cell)`` containing the weight for each quadrature point. + + See also: :class:`PicQuadrature` + """ + + @wp.struct + class Arg: + points_per_cell: int + points: wp.array2d(dtype=Coords) + weights: wp.array2d(dtype=float) + + def __init__(self, domain: domain.GeometryDomain, points: "wp.array2d(dtype=Coords)", weights: "wp.array2d(dtype=float)"): + super().__init__(domain) + + if points.shape != weights.shape: + raise ValueError("Points and weights arrays must have the same shape") + + self._points_per_cell = points.shape[1] + self._points = points + self._weights = weights + + @property + def name(self): + return f"{self.__class__.__name__}" + + def total_point_count(self): + return self._weights.size + + def points_per_element(self): + return self._points_per_cell + + @cache.cached_arg_value + def arg_value(self, device): + arg = self.Arg() + arg.points_per_cell = self._points_per_cell + arg.points = self._points.to(device) + arg.weights = self._weights.to(device) + + return arg + + @wp.func + def point_count(elt_arg: Any, qp_arg: Arg, element_index: ElementIndex): + return qp_arg.points_per_cell + + @wp.func + def point_coords(elt_arg: Any, qp_arg: Arg, element_index: ElementIndex, qp_index: int): + return qp_arg.points[element_index, qp_index] + + @wp.func + def point_weight(elt_arg: Any, qp_arg: Arg, element_index: ElementIndex, qp_index: int): + return qp_arg.weights[element_index, qp_index] + + @wp.func + def point_index(elt_arg: Any, qp_arg: Arg, element_index: ElementIndex, qp_index: int): + return qp_arg.points_per_cell * element_index + qp_index diff --git a/warp/fem/space/__init__.py b/warp/fem/space/__init__.py index a984fd405..bfa455dc2 100644 --- a/warp/fem/space/__init__.py +++ b/warp/fem/space/__init__.py @@ -7,7 +7,7 @@ from .function_space import FunctionSpace from .topology import SpaceTopology -from .basis_space import BasisSpace +from .basis_space import BasisSpace, PointBasisSpace from .collocated_function_space import CollocatedFunctionSpace from .grid_2d_function_space import ( diff --git a/warp/fem/space/basis_space.py b/warp/fem/space/basis_space.py index 47e1a8161..ba8446788 100644 --- a/warp/fem/space/basis_space.py +++ b/warp/fem/space/basis_space.py @@ -4,9 +4,10 @@ from warp.fem.types import ElementIndex, Coords, make_free_sample from warp.fem.geometry import Geometry -from warp.fem import cache, utils +from warp.fem.quadrature import Quadrature +from warp.fem import cache -from .topology import SpaceTopology +from .topology import SpaceTopology, DiscontinuousSpaceTopology from .shape import ShapeFunction @@ -25,19 +26,10 @@ class BasisArg: pass - def __init__(self, topology: SpaceTopology, shape: ShapeFunction): + def __init__(self, topology: SpaceTopology): self._topology = topology - self._shape = shape self.NODES_PER_ELEMENT = self._topology.NODES_PER_ELEMENT - self.ORDER = self._shape.ORDER - - if hasattr(shape, "element_node_triangulation"): - self.node_triangulation = self._node_triangulation - if hasattr(shape, "element_node_tets"): - self.node_tets = self._node_tets - if hasattr(shape, "element_node_hexes"): - self.node_hexes = self._node_hexes @property def topology(self) -> SpaceTopology: @@ -49,19 +41,10 @@ def geometry(self) -> Geometry: """Underlying geometry of the basis space""" return self._topology.geometry - @property - def shape(self) -> ShapeFunction: - """Shape functions used for defining individual element basis""" - return self._shape - def basis_arg_value(self, device) -> "BasisArg": """Value for the argument structure to be passed to device functions""" return BasisSpace.BasisArg() - @property - def name(self): - return f"{self.topology.name}_{self._shape.name}" - # Helpers for generating node positions def node_positions(self, out: Optional[wp.array] = None) -> wp.array: @@ -117,6 +100,56 @@ def fill_node_positions( return node_positions + def make_node_coords_in_element(self): + raise NotImplementedError() + + def make_node_quadrature_weight(self): + raise NotImplementedError() + + def make_element_inner_weight(self): + raise NotImplementedError() + + def make_element_outer_weight(self): + return self.make_element_inner_weight() + + def make_element_inner_weight_gradient(self): + raise NotImplementedError() + + def make_element_outer_weight_gradient(self): + return self.make_element_inner_weight_gradient() + + def make_trace_node_quadrature_weight(self): + raise NotImplementedError() + + def trace(self) -> "TraceBasisSpace": + return TraceBasisSpace(self) + + +class ShapeBasisSpace(BasisSpace): + """Base class for defining shape-function-based basis spaces.""" + + def __init__(self, topology: SpaceTopology, shape: ShapeFunction): + super().__init__(topology) + self._shape = shape + + self.ORDER = self._shape.ORDER + + if hasattr(shape, "element_node_triangulation"): + self.node_triangulation = self._node_triangulation + if hasattr(shape, "element_node_tets"): + self.node_tets = self._node_tets + if hasattr(shape, "element_node_hexes"): + self.node_hexes = self._node_hexes + + @property + def shape(self) -> ShapeFunction: + """Shape functions used for defining individual element basis""" + return self._shape + + @property + def name(self): + return f"{self.topology.name}_{self._shape.name}" + def make_node_coords_in_element(self): shape_node_coords_in_element = self._shape.make_node_coords_in_element() @@ -156,14 +189,10 @@ def element_inner_weight( coords: Coords, node_index_in_elt: int, ): - a = self.BasisArg() return shape_element_inner_weight(coords, node_index_in_elt) return element_inner_weight - def make_element_outer_weight(self): - return self.make_element_inner_weight() - def make_element_inner_weight_gradient(self): shape_element_inner_weight_gradient = self._shape.make_element_inner_weight_gradient() @@ -179,11 +208,22 @@ def element_inner_weight_gradient( return element_inner_weight_gradient - def make_element_outer_weight_gradient(self): - return self.make_element_inner_weight_gradient() + def make_trace_node_quadrature_weight(self, trace_basis): + shape_trace_node_quadrature_weight = self._shape.make_trace_node_quadrature_weight() - def trace(self) -> "TraceBasisSpace": - return TraceBasisSpace(self) + @cache.dynamic_func(suffix=self.name) + def trace_node_quadrature_weight( + geo_side_arg: trace_basis.geometry.SideArg, + basis_arg: trace_basis.BasisArg, + element_index: ElementIndex, + node_index_in_elt: int, + ): + neighbour_elem, index_in_neighbour = trace_basis.topology.neighbor_cell_index( + geo_side_arg, element_index, node_index_in_elt + ) + return shape_trace_node_quadrature_weight(index_in_neighbour) + + return trace_node_quadrature_weight def _node_triangulation(self): element_node_indices = self._topology.element_node_indices().numpy() @@ -211,7 +251,9 @@ class TraceBasisSpace(BasisSpace): """Auto-generated trace space evaluating the cell-defined basis on the geometry sides""" def __init__(self, basis: BasisSpace): - super().__init__(basis.topology.trace(), basis.shape) + super().__init__(basis.topology.trace()) + + self.ORDER = basis.ORDER self._basis = basis self.BasisArg = self._basis.BasisArg @@ -247,21 +289,7 @@ def trace_node_coords_in_element( return trace_node_coords_in_element def make_node_quadrature_weight(self): - shape_trace_node_quadrature_weight = self._shape.make_trace_node_quadrature_weight() - - @cache.dynamic_func(suffix=self._basis.name) - def trace_node_quadrature_weight( - geo_side_arg: self.geometry.SideArg, - basis_arg: self.BasisArg, - element_index: ElementIndex, - node_index_in_elt: int, - ): - neighbour_elem, index_in_neighbour = self.topology.neighbor_cell_index( - geo_side_arg, element_index, node_index_in_elt - ) - return shape_trace_node_quadrature_weight(index_in_neighbour) - - return trace_node_quadrature_weight + return self._basis.make_trace_node_quadrature_weight(self) def make_element_inner_weight(self): cell_inner_weight = self._basis.make_element_inner_weight() @@ -337,9 +365,7 @@ def trace_element_inner_weight_gradient( cell_coords = self.geometry.side_inner_cell_coords(geo_side_arg, element_index, coords) geo_cell_arg = self.geometry.side_to_cell_arg(geo_side_arg) - return cell_inner_weight_gradient( - geo_cell_arg, basis_arg, cell_index, cell_coords, index_in_cell - ) + return cell_inner_weight_gradient(geo_cell_arg, basis_arg, cell_index, cell_coords, index_in_cell) return trace_element_inner_weight_gradient @@ -361,11 +387,103 @@ def trace_element_outer_weight_gradient( cell_coords = self.geometry.side_outer_cell_coords(geo_side_arg, element_index, coords) geo_cell_arg = self.geometry.side_to_cell_arg(geo_side_arg) - return cell_outer_weight_gradient( - geo_cell_arg, basis_arg, cell_index, cell_coords, index_in_cell - ) + return cell_outer_weight_gradient(geo_cell_arg, basis_arg, cell_index, cell_coords, index_in_cell) return trace_element_outer_weight_gradient def __eq__(self, other: "TraceBasisSpace") -> bool: return self._topo == other._topo + + +class PointBasisSpace(BasisSpace): + """An unstructured :class:`BasisSpace` that is non-zero at a finite set of points only. + + The node locations and nodal quadrature weights are defined by a :class:`Quadrature` formula. + """ + + def __init__(self, quadrature: Quadrature): + self._quadrature = quadrature + + if quadrature.points_per_element() is None: + raise NotImplementedError("Varying number of points per element is not supported yet") + + topology = DiscontinuousSpaceTopology( + geometry=quadrature.domain.geometry, nodes_per_element=quadrature.points_per_element() + ) + super().__init__(topology) + + self.BasisArg = quadrature.Arg + self.basis_arg_value = quadrature.arg_value + self.ORDER = 0 + + self.make_element_outer_weight = self.make_element_inner_weight + self.make_element_outer_weight_gradient = self.make_element_outer_weight_gradient + + @property + def name(self): + return f"{self._quadrature.name}_Point" + + def make_node_coords_in_element(self): + @cache.dynamic_func(suffix=self.name) + def node_coords_in_element( + elt_arg: self._quadrature.domain.ElementArg, + basis_arg: self.BasisArg, + element_index: ElementIndex, + node_index_in_elt: int, + ): + return self._quadrature.point_coords(elt_arg, basis_arg, element_index, node_index_in_elt) + + return node_coords_in_element + + def make_node_quadrature_weight(self): + @cache.dynamic_func(suffix=self.name) + def node_quadrature_weight( + elt_arg: self._quadrature.domain.ElementArg, + basis_arg: self.BasisArg, + element_index: ElementIndex, + node_index_in_elt: int, + ): + return self._quadrature.point_weight(elt_arg, basis_arg, element_index, node_index_in_elt) + + return node_quadrature_weight + + def make_element_inner_weight(self): + @cache.dynamic_func(suffix=self.name) + def element_inner_weight( + elt_arg: self._quadrature.domain.ElementArg, + basis_arg: self.BasisArg, + element_index: ElementIndex, + coords: Coords, + node_index_in_elt: int, + ): + qp_coord = self._quadrature.point_coords(elt_arg, basis_arg, element_index, node_index_in_elt) + return wp.select(wp.length_sq(coords - qp_coord) < 0.001, 0.0, 1.0) + + return element_inner_weight + + def make_element_inner_weight_gradient(self): + gradient_vec = cache.cached_vec_type(length=self.geometry.dimension, dtype=float) + + @cache.dynamic_func(suffix=self.name) + def element_inner_weight_gradient( + elt_arg: self._quadrature.domain.ElementArg, + basis_arg: self.BasisArg, + element_index: ElementIndex, + coords: Coords, + node_index_in_elt: int, + ): + return gradient_vec(0.0) + + return element_inner_weight_gradient + + def make_trace_node_quadrature_weight(self, trace_basis): + @cache.dynamic_func(suffix=self.name) + def trace_node_quadrature_weight( + elt_arg: trace_basis.geometry.SideArg, + basis_arg: trace_basis.BasisArg, + element_index: ElementIndex, + node_index_in_elt: int, + ): + return 0.0 + + return trace_node_quadrature_weight diff --git a/warp/fem/space/grid_2d_function_space.py b/warp/fem/space/grid_2d_function_space.py index 9b238202e..d808f9b75 100644 --- a/warp/fem/space/grid_2d_function_space.py +++ b/warp/fem/space/grid_2d_function_space.py @@ -7,7 +7,7 @@ from warp.fem import cache from .topology import SpaceTopology, DiscontinuousSpaceTopologyMixin, forward_base_topology -from .basis_space import BasisSpace, TraceBasisSpace +from .basis_space import ShapeBasisSpace, TraceBasisSpace from .shape import ShapeFunction, ConstantShapeFunction from .shape import ( @@ -44,7 +44,7 @@ class Grid2DDiscontinuousSpaceTopology( pass -class Grid2DBasisSpace(BasisSpace): +class Grid2DBasisSpace(ShapeBasisSpace): def __init__(self, topology: Grid2DSpaceTopology, shape: ShapeFunction): super().__init__(topology, shape) diff --git a/warp/fem/space/grid_3d_function_space.py b/warp/fem/space/grid_3d_function_space.py index 877994dde..7d9dd1483 100644 --- a/warp/fem/space/grid_3d_function_space.py +++ b/warp/fem/space/grid_3d_function_space.py @@ -7,7 +7,7 @@ from warp.fem import cache from .topology import SpaceTopology, DiscontinuousSpaceTopologyMixin, forward_base_topology -from .basis_space import BasisSpace, TraceBasisSpace +from .basis_space import ShapeBasisSpace, TraceBasisSpace from .shape import ShapeFunction, ConstantShapeFunction from .shape.cube_shape_function import ( @@ -45,7 +45,7 @@ class Grid3DDiscontinuousSpaceTopology( pass -class Grid3DBasisSpace(BasisSpace): +class Grid3DBasisSpace(ShapeBasisSpace): def __init__(self, topology: Grid3DSpaceTopology, shape: ShapeFunction): super().__init__(topology, shape) diff --git a/warp/fem/space/hexmesh_function_space.py b/warp/fem/space/hexmesh_function_space.py index d6b3c96f9..1afe472ca 100644 --- a/warp/fem/space/hexmesh_function_space.py +++ b/warp/fem/space/hexmesh_function_space.py @@ -6,7 +6,7 @@ from warp.fem import cache from .topology import SpaceTopology, DiscontinuousSpaceTopologyMixin, forward_base_topology -from .basis_space import BasisSpace, TraceBasisSpace +from .basis_space import ShapeBasisSpace, TraceBasisSpace from .shape import ShapeFunction, ConstantShapeFunction from .shape import ( @@ -121,7 +121,7 @@ def __init__(self, mesh: Hexmesh, shape: ShapeFunction): super().__init__(mesh, shape.NODES_PER_ELEMENT) -class HexmeshBasisSpace(BasisSpace): +class HexmeshBasisSpace(ShapeBasisSpace): def __init__(self, topology: HexmeshSpaceTopology, shape: ShapeFunction): super().__init__(topology, shape) diff --git a/warp/fem/space/quadmesh_2d_function_space.py b/warp/fem/space/quadmesh_2d_function_space.py index 7c7881b8b..6258a1a12 100644 --- a/warp/fem/space/quadmesh_2d_function_space.py +++ b/warp/fem/space/quadmesh_2d_function_space.py @@ -6,7 +6,7 @@ from warp.fem import cache from .topology import SpaceTopology, DiscontinuousSpaceTopologyMixin, forward_base_topology -from .basis_space import BasisSpace, TraceBasisSpace +from .basis_space import ShapeBasisSpace, TraceBasisSpace from .shape import ShapeFunction, ConstantShapeFunction from .shape import ( @@ -116,7 +116,7 @@ def __init__(self, mesh: Quadmesh2D, shape: ShapeFunction): super().__init__(mesh, shape.NODES_PER_ELEMENT) -class Quadmesh2DBasisSpace(BasisSpace): +class Quadmesh2DBasisSpace(ShapeBasisSpace): def __init__(self, topology: Quadmesh2DSpaceTopology, shape: ShapeFunction): super().__init__(topology, shape) diff --git a/warp/fem/space/tetmesh_function_space.py b/warp/fem/space/tetmesh_function_space.py index 0f8714ae0..4d6037ae2 100644 --- a/warp/fem/space/tetmesh_function_space.py +++ b/warp/fem/space/tetmesh_function_space.py @@ -5,7 +5,7 @@ from warp.fem import cache from .topology import SpaceTopology, DiscontinuousSpaceTopologyMixin, forward_base_topology -from .basis_space import BasisSpace, TraceBasisSpace +from .basis_space import ShapeBasisSpace, TraceBasisSpace from .shape import ShapeFunction, ConstantShapeFunction from .shape import TetrahedronPolynomialShapeFunctions, TetrahedronNonConformingPolynomialShapeFunctions @@ -136,7 +136,7 @@ def __init__(self, mesh: Tetmesh, shape: ShapeFunction): super().__init__(mesh, shape.NODES_PER_ELEMENT) -class TetmeshBasisSpace(BasisSpace): +class TetmeshBasisSpace(ShapeBasisSpace): def __init__(self, topology: TetmeshSpaceTopology, shape: ShapeFunction): super().__init__(topology, shape) diff --git a/warp/fem/space/topology.py b/warp/fem/space/topology.py index 23e866434..bc76a8102 100644 --- a/warp/fem/space/topology.py +++ b/warp/fem/space/topology.py @@ -227,6 +227,10 @@ def __init__(self, *args, **kwargs): def node_count(self): return self.geometry.cell_count() * self.NODES_PER_ELEMENT + @property + def name(self): + return f"{self.geometry.name}_D{self.NODES_PER_ELEMENT}" + def _make_element_node_index(self): NODES_PER_ELEMENT = self.NODES_PER_ELEMENT @@ -242,6 +246,12 @@ def element_node_index( return element_node_index +class DiscontinuousSpaceTopology(DiscontinuousSpaceTopologyMixin, SpaceTopology): + """Topology for generic discontinuous spaces""" + + pass + + class DeformedGeometrySpaceTopology(SpaceTopology): def __init__(self, geometry: DeformedGeometry, base_topology: SpaceTopology): super().__init__(geometry, base_topology.NODES_PER_ELEMENT) diff --git a/warp/fem/space/trimesh_2d_function_space.py b/warp/fem/space/trimesh_2d_function_space.py index 567a665d1..21f45ab6c 100644 --- a/warp/fem/space/trimesh_2d_function_space.py +++ b/warp/fem/space/trimesh_2d_function_space.py @@ -5,7 +5,7 @@ from warp.fem import cache from .topology import SpaceTopology, DiscontinuousSpaceTopologyMixin, forward_base_topology -from .basis_space import BasisSpace, TraceBasisSpace +from .basis_space import ShapeBasisSpace, TraceBasisSpace from .shape import ShapeFunction, ConstantShapeFunction from .shape import Triangle2DPolynomialShapeFunctions, Triangle2DNonConformingPolynomialShapeFunctions @@ -101,7 +101,7 @@ def __init__(self, mesh: Trimesh2D, shape: ShapeFunction): super().__init__(mesh, shape.NODES_PER_ELEMENT) -class Trimesh2DBasisSpace(BasisSpace): +class Trimesh2DBasisSpace(ShapeBasisSpace): def __init__(self, topology: Trimesh2DSpaceTopology, shape: ShapeFunction): super().__init__(topology, shape) diff --git a/warp/tests/test_fem.py b/warp/tests/test_fem.py index acf89fd34..70a6da628 100644 --- a/warp/tests/test_fem.py +++ b/warp/tests/test_fem.py @@ -14,13 +14,9 @@ from warp.fem import Field, Sample, Domain, Coords -from warp.fem import Grid2D, Grid3D, Trimesh2D, Tetmesh, Quadmesh2D, Hexmesh, Geometry -from warp.fem import make_polynomial_space, SymmetricTensorMapper, SkewSymmetricTensorMapper -from warp.fem import make_test -from warp.fem import Cells, Sides, BoundarySides -from warp.fem import integrate, interpolate from warp.fem import integrand, div, grad, curl, D, normal -from warp.fem import RegularQuadrature, Polynomial +import warp.fem as fem + from warp.fem.types import make_free_sample from warp.fem.geometry.closest_point import project_on_tri_at_origin, project_on_tet_at_origin from warp.fem.geometry import DeformedGeometry @@ -39,13 +35,13 @@ def linear_form(s: Sample, u: Field): def test_integrate_gradient(test_case, device): with wp.ScopedDevice(device): # Grid geometry - geo = Grid2D(res=wp.vec2i(5)) + geo = fem.Grid2D(res=wp.vec2i(5)) # Domain and function spaces - domain = Cells(geometry=geo) - quadrature = RegularQuadrature(domain=domain, order=3) + domain = fem.Cells(geometry=geo) + quadrature = fem.RegularQuadrature(domain=domain, order=3) - scalar_space = make_polynomial_space(geo, degree=3) + scalar_space = fem.make_polynomial_space(geo, degree=3) u = scalar_space.make_field() u.dof_values = wp.zeros_like(u.dof_values, requires_grad=True) @@ -56,12 +52,12 @@ def test_integrate_gradient(test_case, device): # forward pass with tape: - integrate(linear_form, quadrature=quadrature, fields={"u": u}, output=result) + fem.integrate(linear_form, quadrature=quadrature, fields={"u": u}, output=result) tape.backward(result) - test = make_test(space=scalar_space, domain=domain) - rhs = integrate(linear_form, quadrature=quadrature, fields={"u": test}) + test = fem.make_test(space=scalar_space, domain=domain) + rhs = fem.integrate(linear_form, quadrature=quadrature, fields={"u": test}) err = np.linalg.norm(rhs.numpy() - u.dof_values.grad.numpy()) test_case.assertLess(err, 1.0e-8) @@ -87,14 +83,14 @@ def test_vector_divergence_theorem(test_case, device): with wp.ScopedDevice(device): # Grid geometry - geo = Grid2D(res=wp.vec2i(5)) + geo = fem.Grid2D(res=wp.vec2i(5)) # Domain and function spaces - interior = Cells(geometry=geo) - boundary = BoundarySides(geometry=geo) + interior = fem.Cells(geometry=geo) + boundary = fem.BoundarySides(geometry=geo) - vector_space = make_polynomial_space(geo, degree=2, dtype=wp.vec2) - scalar_space = make_polynomial_space(geo, degree=1, dtype=float) + vector_space = fem.make_polynomial_space(geo, degree=2, dtype=wp.vec2) + scalar_space = fem.make_polynomial_space(geo, degree=1, dtype=float) u = vector_space.make_field() u.dof_values = rng.random(size=(u.dof_values.shape[0], 2)) @@ -103,15 +99,15 @@ def test_vector_divergence_theorem(test_case, device): constant_one = scalar_space.make_field() constant_one.dof_values.fill_(1.0) - interior_quadrature = RegularQuadrature(domain=interior, order=vector_space.degree) - boundary_quadrature = RegularQuadrature(domain=boundary, order=vector_space.degree) - div_int = integrate( + interior_quadrature = fem.RegularQuadrature(domain=interior, order=vector_space.degree) + boundary_quadrature = fem.RegularQuadrature(domain=boundary, order=vector_space.degree) + div_int = fem.integrate( vector_divergence_form, quadrature=interior_quadrature, fields={"u": u, "q": constant_one}, kernel_options={"enable_backward": False}, ) - boundary_int = integrate( + boundary_int = fem.integrate( vector_boundary_form, quadrature=boundary_quadrature, fields={"u": u.trace(), "q": constant_one.trace()}, @@ -124,21 +120,21 @@ def test_vector_divergence_theorem(test_case, device): q = scalar_space.make_field() q.dof_values = rng.random(size=q.dof_values.shape[0]) - interior_quadrature = RegularQuadrature(domain=interior, order=vector_space.degree + scalar_space.degree) - boundary_quadrature = RegularQuadrature(domain=boundary, order=vector_space.degree + scalar_space.degree) - div_int = integrate( + interior_quadrature = fem.RegularQuadrature(domain=interior, order=vector_space.degree + scalar_space.degree) + boundary_quadrature = fem.RegularQuadrature(domain=boundary, order=vector_space.degree + scalar_space.degree) + div_int = fem.integrate( vector_divergence_form, quadrature=interior_quadrature, fields={"u": u, "q": q}, kernel_options={"enable_backward": False}, ) - grad_int = integrate( + grad_int = fem.integrate( vector_grad_form, quadrature=interior_quadrature, fields={"u": u, "q": q}, kernel_options={"enable_backward": False}, ) - boundary_int = integrate( + boundary_int = fem.integrate( vector_boundary_form, quadrature=boundary_quadrature, fields={"u": u.trace(), "q": q.trace()}, @@ -168,14 +164,14 @@ def test_tensor_divergence_theorem(test_case, device): with wp.ScopedDevice(device): # Grid geometry - geo = Grid2D(res=wp.vec2i(5)) + geo = fem.Grid2D(res=wp.vec2i(5)) # Domain and function spaces - interior = Cells(geometry=geo) - boundary = BoundarySides(geometry=geo) + interior = fem.Cells(geometry=geo) + boundary = fem.BoundarySides(geometry=geo) - tensor_space = make_polynomial_space(geo, degree=2, dtype=wp.mat22) - vector_space = make_polynomial_space(geo, degree=1, dtype=wp.vec2) + tensor_space = fem.make_polynomial_space(geo, degree=2, dtype=wp.mat22) + vector_space = fem.make_polynomial_space(geo, degree=1, dtype=wp.vec2) tau = tensor_space.make_field() tau.dof_values = rng.random(size=(tau.dof_values.shape[0], 2, 2)) @@ -184,15 +180,15 @@ def test_tensor_divergence_theorem(test_case, device): constant_vec = vector_space.make_field() constant_vec.dof_values.fill_(wp.vec2(0.5, 2.0)) - interior_quadrature = RegularQuadrature(domain=interior, order=tensor_space.degree) - boundary_quadrature = RegularQuadrature(domain=boundary, order=tensor_space.degree) - div_int = integrate( + interior_quadrature = fem.RegularQuadrature(domain=interior, order=tensor_space.degree) + boundary_quadrature = fem.RegularQuadrature(domain=boundary, order=tensor_space.degree) + div_int = fem.integrate( tensor_divergence_form, quadrature=interior_quadrature, fields={"tau": tau, "v": constant_vec}, kernel_options={"enable_backward": False}, ) - boundary_int = integrate( + boundary_int = fem.integrate( tensor_boundary_form, quadrature=boundary_quadrature, fields={"tau": tau.trace(), "v": constant_vec.trace()}, @@ -205,21 +201,21 @@ def test_tensor_divergence_theorem(test_case, device): v = vector_space.make_field() v.dof_values = rng.random(size=(v.dof_values.shape[0], 2)) - interior_quadrature = RegularQuadrature(domain=interior, order=tensor_space.degree + vector_space.degree) - boundary_quadrature = RegularQuadrature(domain=boundary, order=tensor_space.degree + vector_space.degree) - div_int = integrate( + interior_quadrature = fem.RegularQuadrature(domain=interior, order=tensor_space.degree + vector_space.degree) + boundary_quadrature = fem.RegularQuadrature(domain=boundary, order=tensor_space.degree + vector_space.degree) + div_int = fem.integrate( tensor_divergence_form, quadrature=interior_quadrature, fields={"tau": tau, "v": v}, kernel_options={"enable_backward": False}, ) - grad_int = integrate( + grad_int = fem.integrate( tensor_grad_form, quadrature=interior_quadrature, fields={"tau": tau, "v": v}, kernel_options={"enable_backward": False}, ) - boundary_int = integrate( + boundary_int = fem.integrate( tensor_boundary_form, quadrature=boundary_quadrature, fields={"tau": tau.trace(), "v": v.trace()}, @@ -239,18 +235,18 @@ def test_grad_decomposition(test_case, device): with wp.ScopedDevice(device): # Grid geometry - geo = Grid3D(res=wp.vec3i(5)) + geo = fem.Grid3D(res=wp.vec3i(5)) # Domain and function spaces - domain = Cells(geometry=geo) - quadrature = RegularQuadrature(domain=domain, order=4) + domain = fem.Cells(geometry=geo) + quadrature = fem.RegularQuadrature(domain=domain, order=4) - vector_space = make_polynomial_space(geo, degree=2, dtype=wp.vec3) + vector_space = fem.make_polynomial_space(geo, degree=2, dtype=wp.vec3) u = vector_space.make_field() u.dof_values = rng.random(size=(u.dof_values.shape[0], 3)) - err = integrate(grad_decomposition, quadrature=quadrature, fields={"u": u, "v": u}) + err = fem.integrate(grad_decomposition, quadrature=quadrature, fields={"u": u, "v": u}) test_case.assertLess(err, 1.0e-8) @@ -300,7 +296,7 @@ def _gen_hexmesh(N): return wp.array(positions, dtype=wp.vec3), wp.array(vidx, dtype=int) -def _launch_test_geometry_kernel(geo: Geometry, device): +def _launch_test_geometry_kernel(geo: fem.Geometry, device): @dynamic_kernel(suffix=geo.name, kernel_options={"enable_backward": False}) def test_geo_cells_kernel( cell_arg: geo.CellArg, @@ -368,7 +364,7 @@ def test_geo_sides_kernel( cell_measures = wp.zeros(dtype=float, device=device, shape=geo.cell_count()) - cell_quadrature = RegularQuadrature(Cells(geo), order=2) + cell_quadrature = fem.RegularQuadrature(fem.Cells(geo), order=2) cell_qps = wp.array(cell_quadrature.points, dtype=Coords, device=device) cell_qp_weights = wp.array(cell_quadrature.weights, dtype=float, device=device) @@ -381,7 +377,7 @@ def test_geo_sides_kernel( side_measures = wp.zeros(dtype=float, device=device, shape=geo.side_count()) - side_quadrature = RegularQuadrature(Sides(geo), order=2) + side_quadrature = fem.RegularQuadrature(fem.Sides(geo), order=2) side_qps = wp.array(side_quadrature.points, dtype=Coords, device=device) side_qp_weights = wp.array(side_quadrature.weights, dtype=float, device=device) @@ -398,7 +394,7 @@ def test_geo_sides_kernel( def test_grid_2d(test_case, device): N = 3 - geo = Grid2D(res=wp.vec2i(N)) + geo = fem.Grid2D(res=wp.vec2i(N)) test_case.assertEqual(geo.cell_count(), N**2) test_case.assertEqual(geo.vertex_count(), (N + 1) ** 2) @@ -417,7 +413,7 @@ def test_triangle_mesh(test_case, device): with wp.ScopedDevice(device): positions, tri_vidx = _gen_trimesh(N) - geo = Trimesh2D(tri_vertex_indices=tri_vidx, positions=positions) + geo = fem.Trimesh2D(tri_vertex_indices=tri_vidx, positions=positions) test_case.assertEqual(geo.cell_count(), 2 * (N) ** 2) test_case.assertEqual(geo.vertex_count(), (N + 1) ** 2) @@ -436,7 +432,7 @@ def test_quad_mesh(test_case, device): with wp.ScopedDevice(device): positions, quad_vidx = _gen_quadmesh(N) - geo = Quadmesh2D(quad_vertex_indices=quad_vidx, positions=positions) + geo = fem.Quadmesh2D(quad_vertex_indices=quad_vidx, positions=positions) test_case.assertEqual(geo.cell_count(), N**2) test_case.assertEqual(geo.vertex_count(), (N + 1) ** 2) @@ -452,7 +448,7 @@ def test_quad_mesh(test_case, device): def test_grid_3d(test_case, device): N = 3 - geo = Grid3D(res=wp.vec3i(N)) + geo = fem.Grid3D(res=wp.vec3i(N)) test_case.assertEqual(geo.cell_count(), (N) ** 3) test_case.assertEqual(geo.vertex_count(), (N + 1) ** 3) @@ -472,7 +468,7 @@ def test_tet_mesh(test_case, device): with wp.ScopedDevice(device): positions, tet_vidx = _gen_tetmesh(N) - geo = Tetmesh(tet_vertex_indices=tet_vidx, positions=positions) + geo = fem.Tetmesh(tet_vertex_indices=tet_vidx, positions=positions) test_case.assertEqual(geo.cell_count(), 5 * (N) ** 3) test_case.assertEqual(geo.vertex_count(), (N + 1) ** 3) @@ -492,7 +488,7 @@ def test_hex_mesh(test_case, device): with wp.ScopedDevice(device): positions, tet_vidx = _gen_hexmesh(N) - geo = Hexmesh(hex_vertex_indices=tet_vidx, positions=positions) + geo = fem.Hexmesh(hex_vertex_indices=tet_vidx, positions=positions) test_case.assertEqual(geo.cell_count(), (N) ** 3) test_case.assertEqual(geo.vertex_count(), (N + 1) ** 3) @@ -518,15 +514,15 @@ def test_deformed_geometry(test_case, device): with wp.ScopedDevice(device): positions, tet_vidx = _gen_tetmesh(N) - geo = Tetmesh(tet_vertex_indices=tet_vidx, positions=positions) + geo = fem.Tetmesh(tet_vertex_indices=tet_vidx, positions=positions) translation = [1.0, 2.0, 3.0] rotation = [0.0, math.pi / 4.0, 0.0] scale = 2.0 - vector_space = make_polynomial_space(geo, dtype=wp.vec3, degree=2) + vector_space = fem.make_polynomial_space(geo, dtype=wp.vec3, degree=2) pos_field = vector_space.make_field() - interpolate( + fem.interpolate( _rigid_deformation_field, dest=pos_field, values={"translation": translation, "rotation": rotation, "scale": scale}, @@ -705,9 +701,9 @@ def test_dof_mapper(test_case, device): matrix_types = [wp.mat22, wp.mat33] # Symmetric mapper - for mapping in SymmetricTensorMapper.Mapping: + for mapping in fem.SymmetricTensorMapper.Mapping: for dtype in matrix_types: - mapper = SymmetricTensorMapper(dtype, mapping=mapping) + mapper = fem.SymmetricTensorMapper(dtype, mapping=mapping) dof_dtype = mapper.dof_dtype for k in range(dof_dtype._length_): @@ -727,7 +723,7 @@ def test_dof_mapper(test_case, device): # Skew-symmetric mapper for dtype in matrix_types: - mapper = SkewSymmetricTensorMapper(dtype) + mapper = fem.SkewSymmetricTensorMapper(dtype) dof_dtype = mapper.dof_dtype if hasattr(dof_dtype, "_length_"): @@ -879,9 +875,9 @@ def square_coord_delta_sampler(epsilon: float, state: wp.uint32): param_delta = wp.normalize(wp.vec2(wp.randf(state), wp.randf(state))) * epsilon return param_delta, Coords(param_delta[0], param_delta[1], 0.0) - Q_1 = shape.SquareBipolynomialShapeFunctions(degree=1, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) - Q_2 = shape.SquareBipolynomialShapeFunctions(degree=2, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) - Q_3 = shape.SquareBipolynomialShapeFunctions(degree=3, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) + Q_1 = shape.SquareBipolynomialShapeFunctions(degree=1, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) + Q_2 = shape.SquareBipolynomialShapeFunctions(degree=2, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) + Q_3 = shape.SquareBipolynomialShapeFunctions(degree=3, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) test_shape_function_weight(test_case, Q_1, square_coord_sampler, SQUARE_CENTER_COORDS) test_shape_function_weight(test_case, Q_2, square_coord_sampler, SQUARE_CENTER_COORDS) @@ -893,8 +889,8 @@ def square_coord_delta_sampler(epsilon: float, state: wp.uint32): test_shape_function_gradient(test_case, Q_2, square_coord_sampler, square_coord_delta_sampler) test_shape_function_gradient(test_case, Q_3, square_coord_sampler, square_coord_delta_sampler) - S_2 = shape.SquareSerendipityShapeFunctions(degree=2, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) - S_3 = shape.SquareSerendipityShapeFunctions(degree=3, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) + S_2 = shape.SquareSerendipityShapeFunctions(degree=2, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) + S_3 = shape.SquareSerendipityShapeFunctions(degree=3, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) test_shape_function_weight(test_case, S_2, square_coord_sampler, SQUARE_CENTER_COORDS) test_shape_function_weight(test_case, S_3, square_coord_sampler, SQUARE_CENTER_COORDS) @@ -930,9 +926,9 @@ def cube_coord_delta_sampler(epsilon: float, state: wp.uint32): param_delta = wp.normalize(wp.vec3(wp.randf(state), wp.randf(state), wp.randf(state))) * epsilon return param_delta, param_delta - Q_1 = shape.CubeTripolynomialShapeFunctions(degree=1, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) - Q_2 = shape.CubeTripolynomialShapeFunctions(degree=2, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) - Q_3 = shape.CubeTripolynomialShapeFunctions(degree=3, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) + Q_1 = shape.CubeTripolynomialShapeFunctions(degree=1, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) + Q_2 = shape.CubeTripolynomialShapeFunctions(degree=2, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) + Q_3 = shape.CubeTripolynomialShapeFunctions(degree=3, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) test_shape_function_weight(test_case, Q_1, cube_coord_sampler, CUBE_CENTER_COORDS) test_shape_function_weight(test_case, Q_2, cube_coord_sampler, CUBE_CENTER_COORDS) @@ -944,8 +940,8 @@ def cube_coord_delta_sampler(epsilon: float, state: wp.uint32): test_shape_function_gradient(test_case, Q_2, cube_coord_sampler, cube_coord_delta_sampler) test_shape_function_gradient(test_case, Q_3, cube_coord_sampler, cube_coord_delta_sampler) - S_2 = shape.CubeSerendipityShapeFunctions(degree=2, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) - S_3 = shape.CubeSerendipityShapeFunctions(degree=3, family=Polynomial.LOBATTO_GAUSS_LEGENDRE) + S_2 = shape.CubeSerendipityShapeFunctions(degree=2, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) + S_3 = shape.CubeSerendipityShapeFunctions(degree=3, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) test_shape_function_weight(test_case, S_2, cube_coord_sampler, CUBE_CENTER_COORDS) test_shape_function_weight(test_case, S_3, cube_coord_sampler, CUBE_CENTER_COORDS) @@ -1054,6 +1050,81 @@ def tet_coord_delta_sampler(epsilon: float, state: wp.uint32): wp.synchronize() +def test_point_basis(test_case, device): + geo = fem.Grid2D(res=wp.vec2i(2)) + + domain = fem.Cells(geo) + + quadrature = fem.RegularQuadrature(domain, order=2, family=fem.Polynomial.GAUSS_LEGENDRE) + point_basis = fem.PointBasisSpace(quadrature) + + point_space = fem.make_collocated_function_space(point_basis) + point_test = fem.make_test(point_space, domain=domain) + + # Sample at particle positions + ones = fem.integrate(linear_form, fields={"u": point_test}, nodal=True) + test_case.assertAlmostEqual(np.sum(ones.numpy()), 1.0, places=5) + + # Sampling outside of particle positions + other_quadrature = fem.RegularQuadrature(domain, order=2, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) + zeros = fem.integrate(linear_form, quadrature=other_quadrature, fields={"u": point_test}) + + test_case.assertAlmostEqual(np.sum(zeros.numpy()), 0.0, places=5) + + +@fem.integrand +def _bicubic(s: Sample, domain: Domain): + x = domain(s) + return wp.pow(x[0], 3.0) * wp.pow(x[1], 3.0) + + +@fem.integrand +def _piecewise_constant(s: Sample): + return float(s.element_index) + + +def test_particle_quadratures(test_case, device): + geo = fem.Grid2D(res=wp.vec2i(2)) + + domain = fem.Cells(geo) + points, weights = domain.reference_element().instantiate_quadrature(order=4, family=fem.Polynomial.GAUSS_LEGENDRE) + points_per_cell = len(points) + + points = points * domain.element_count() + weights = weights * domain.element_count() + + points = wp.array(points, shape=(domain.element_count(), points_per_cell), dtype=Coords, device=device) + weights = wp.array(weights, shape=(domain.element_count(), points_per_cell), dtype=float, device=device) + + explicit_quadrature = fem.ExplicitQuadrature(domain, points, weights) + + test_case.assertEqual(explicit_quadrature.points_per_element(), points_per_cell) + test_case.assertEqual(explicit_quadrature.total_point_count(), points_per_cell * geo.cell_count()) + + val = fem.integrate(_bicubic, quadrature=explicit_quadrature) + test_case.assertAlmostEqual(val, 1.0 / 16, places=5) + + element_indices = wp.array([3, 3, 2], dtype=int, device=device) + element_coords = wp.array( + [ + [0.25, 0.5, 0.0], + [0.5, 0.25, 0.0], + [0.5, 0.5, 0.0], + ], + dtype=Coords, + device=device, + ) + + pic_quadrature = fem.PicQuadrature(domain, positions=(element_indices, element_coords)) + + test_case.assertIsNone(pic_quadrature.points_per_element()) + test_case.assertEqual(pic_quadrature.total_point_count(), 3) + test_case.assertEqual(pic_quadrature.active_cell_count(), 2) + + val = fem.integrate(_piecewise_constant, quadrature=pic_quadrature) + test_case.assertAlmostEqual(val, 1.25, places=5) + + def register(parent): devices = get_test_devices() @@ -1078,6 +1149,8 @@ class TestFem(parent): add_function_test(TestFem, "test_cube_shape_functions", test_cube_shape_functions) add_function_test(TestFem, "test_tri_shape_functions", test_tri_shape_functions) add_function_test(TestFem, "test_tet_shape_functions", test_tet_shape_functions) + add_function_test(TestFem, "test_point_basis", test_point_basis) + add_function_test(TestFem, "test_particle_quadratures", test_particle_quadratures) return TestFem From cb179c28ec9255c628f706496349a314587cf162 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Tue, 21 Nov 2023 11:43:06 +1300 Subject: [PATCH 08/50] Expose user-friendly mesh query overloads These overloads return structs instead of writing the results to arguments passed by reference. --- warp/__init__.py | 4 +- warp/builtins.py | 131 ++++++++++++++++++++++++++++ warp/native/exports.h | 6 ++ warp/native/mesh.h | 131 ++++++++++++++++++++++++++-- warp/tests/test_mesh_query_point.py | 28 ++++++ warp/types.py | 35 +++++++- 6 files changed, 328 insertions(+), 7 deletions(-) diff --git a/warp/__init__.py b/warp/__init__.py index 685bdea87..3ef997ad6 100644 --- a/warp/__init__.py +++ b/warp/__init__.py @@ -26,7 +26,9 @@ # geometry types from warp.types import Bvh, Mesh, HashGrid, Volume, MarchingCubes -from warp.types import bvh_query_t, mesh_query_aabb_t, hash_grid_query_t +from warp.types import bvh_query_t, hash_grid_query_t, mesh_query_aabb_t, mesh_query_point_t, mesh_query_ray_t + + # device-wide gemms from warp.types import matmul, adj_matmul, batched_matmul, adj_batched_matmul, from_ptr diff --git a/warp/builtins.py b/warp/builtins.py index 5869800b1..d655dc819 100644 --- a/warp/builtins.py +++ b/warp/builtins.py @@ -1541,6 +1541,27 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param bary_v: Returns the barycentric v coordinate of the closest point""", ) +add_builtin( + "mesh_query_point", + input_types={ + "id": uint64, + "point": vec3, + "max_dist": float, + }, + value_type=mesh_query_point_t, + group="Geometry", + doc="""Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given ``point`` in space. + + Identifies the sign of the distance using additional ray-casts to determine if the point is inside or outside. + This method is relatively robust, but does increase computational cost. + See below for additional sign determination methods. + + :param id: The mesh identifier + :param point: The point in space to query + :param max_dist: Mesh faces above this distance will not be considered by the query""", + require_original_output_arg=True, +) + add_builtin( "mesh_query_point_no_sign", input_types={ @@ -1565,6 +1586,25 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param bary_v: Returns the barycentric v coordinate of the closest point""", ) +add_builtin( + "mesh_query_point_no_sign", + input_types={ + "id": uint64, + "point": vec3, + "max_dist": float, + }, + value_type=mesh_query_point_t, + group="Geometry", + doc="""Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given ``point`` in space. + + This method does not compute the sign of the point (inside/outside) which makes it faster than other point query methods. + + :param id: The mesh identifier + :param point: The point in space to query + :param max_dist: Mesh faces above this distance will not be considered by the query""", + require_original_output_arg=True, +) + add_builtin( "mesh_query_furthest_point_no_sign", input_types={ @@ -1589,6 +1629,25 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param bary_v: Returns the barycentric v coordinate of the furthest point""", ) +add_builtin( + "mesh_query_furthest_point_no_sign", + input_types={ + "id": uint64, + "point": vec3, + "min_dist": float, + }, + value_type=mesh_query_point_t, + group="Geometry", + doc="""Computes the furthest point on the mesh with identifier `id` to the given point in space. + + This method does not compute the sign of the point (inside/outside). + + :param id: The mesh identifier + :param point: The point in space to query + :param min_dist: Mesh faces below this distance will not be considered by the query""", + require_original_output_arg=True, +) + add_builtin( "mesh_query_point_sign_normal", input_types={ @@ -1622,6 +1681,31 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): fraction of the average edge length, also for treating closest point as being on edge/vertex default 1e-3""", ) +add_builtin( + "mesh_query_point_sign_normal", + input_types={ + "id": uint64, + "point": vec3, + "max_dist": float, + "epsilon": float, + }, + defaults={"epsilon": 1.0e-3}, + value_type=mesh_query_point_t, + group="Geometry", + doc="""Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given ``point`` in space. + + Identifies the sign of the distance (inside/outside) using the angle-weighted pseudo normal. + This approach to sign determination is robust for well conditioned meshes that are watertight and non-self intersecting. + It is also comparatively fast to compute. + + :param id: The mesh identifier + :param point: The point in space to query + :param max_dist: Mesh faces above this distance will not be considered by the query + :param epsilon: Epsilon treating distance values as equal, when locating the minimum distance vertex/face/edge, as a + fraction of the average edge length, also for treating closest point as being on edge/vertex default 1e-3""", + require_original_output_arg=True, +) + add_builtin( "mesh_query_point_sign_winding_number", input_types={ @@ -1658,6 +1742,34 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param threshold: The threshold of the winding number to be considered inside, default 0.5""", ) +add_builtin( + "mesh_query_point_sign_winding_number", + input_types={ + "id": uint64, + "point": vec3, + "max_dist": float, + "accuracy": float, + "threshold": float, + }, + defaults={"accuracy": 2.0, "threshold": 0.5}, + value_type=mesh_query_point_t, + group="Geometry", + doc="""Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given point in space. + + Identifies the sign using the winding number of the mesh relative to the query point. This method of sign determination is robust for poorly conditioned meshes + and provides a smooth approximation to sign even when the mesh is not watertight. This method is the most robust and accurate of the sign determination meshes + but also the most expensive. + + .. note:: The :class:`Mesh` object must be constructed with ``support_winding_number=True`` for this method to return correct results. + + :param id: The mesh identifier + :param point: The point in space to query + :param max_dist: Mesh faces above this distance will not be considered by the query + :param accuracy: Accuracy for computing the winding number with fast winding number method utilizing second-order dipole approximation, default 2.0 + :param threshold: The threshold of the winding number to be considered inside, default 0.5""", + require_original_output_arg=True, +) + add_builtin( "mesh_query_ray", input_types={ @@ -1688,6 +1800,25 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param face: Returns the index of the hit face""", ) +add_builtin( + "mesh_query_ray", + input_types={ + "id": uint64, + "start": vec3, + "dir": vec3, + "max_t": float, + }, + value_type=mesh_query_ray_t, + group="Geometry", + doc="""Computes the closest ray hit on the :class:`Mesh` with identifier ``id``. + + :param id: The mesh identifier + :param start: The start point of the ray + :param dir: The ray direction (should be normalized) + :param max_t: The maximum distance along the ray to check for intersections""", + require_original_output_arg=True, +) + add_builtin( "mesh_query_aabb", input_types={"id": uint64, "lower": vec3, "upper": vec3}, diff --git a/warp/native/exports.h b/warp/native/exports.h index d737c1fa9..78b2f14d2 100644 --- a/warp/native/exports.h +++ b/warp/native/exports.h @@ -747,11 +747,17 @@ WP_API void builtin_bvh_query_aabb_uint64_vec3f_vec3f(uint64 id, vec3f lower, ve WP_API void builtin_bvh_query_ray_uint64_vec3f_vec3f(uint64 id, vec3f start, vec3f dir, bvh_query_t* ret) { *ret = wp::bvh_query_ray(id, start, dir); } WP_API void builtin_bvh_query_next_bvh_query_t_int32(bvh_query_t query, int32 index, bool* ret) { *ret = wp::bvh_query_next(query, index); } WP_API void builtin_mesh_query_point_uint64_vec3f_float32_float32_int32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_point(id, point, max_dist, inside, face, bary_u, bary_v); } +WP_API void builtin_mesh_query_point_uint64_vec3f_float32(uint64 id, vec3f point, float32 max_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_point(id, point, max_dist); } WP_API void builtin_mesh_query_point_no_sign_uint64_vec3f_float32_int32_float32_float32(uint64 id, vec3f point, float32 max_dist, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_point_no_sign(id, point, max_dist, face, bary_u, bary_v); } +WP_API void builtin_mesh_query_point_no_sign_uint64_vec3f_float32(uint64 id, vec3f point, float32 max_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_no_sign(id, point, max_dist); } WP_API void builtin_mesh_query_furthest_point_no_sign_uint64_vec3f_float32_int32_float32_float32(uint64 id, vec3f point, float32 min_dist, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_furthest_point_no_sign(id, point, min_dist, face, bary_u, bary_v); } +WP_API void builtin_mesh_query_furthest_point_no_sign_uint64_vec3f_float32(uint64 id, vec3f point, float32 min_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_furthest_point_no_sign(id, point, min_dist); } WP_API void builtin_mesh_query_point_sign_normal_uint64_vec3f_float32_float32_int32_float32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, float32 epsilon, bool* ret) { *ret = wp::mesh_query_point_sign_normal(id, point, max_dist, inside, face, bary_u, bary_v, epsilon); } +WP_API void builtin_mesh_query_point_sign_normal_uint64_vec3f_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 epsilon, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_sign_normal(id, point, max_dist, epsilon); } WP_API void builtin_mesh_query_point_sign_winding_number_uint64_vec3f_float32_float32_int32_float32_float32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, float32 accuracy, float32 threshold, bool* ret) { *ret = wp::mesh_query_point_sign_winding_number(id, point, max_dist, inside, face, bary_u, bary_v, accuracy, threshold); } +WP_API void builtin_mesh_query_point_sign_winding_number_uint64_vec3f_float32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 accuracy, float32 threshold, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_sign_winding_number(id, point, max_dist, accuracy, threshold); } WP_API void builtin_mesh_query_ray_uint64_vec3f_vec3f_float32_float32_float32_float32_float32_vec3f_int32(uint64 id, vec3f start, vec3f dir, float32 max_t, float32 t, float32 bary_u, float32 bary_v, float32 sign, vec3f normal, int32 face, bool* ret) { *ret = wp::mesh_query_ray(id, start, dir, max_t, t, bary_u, bary_v, sign, normal, face); } +WP_API void builtin_mesh_query_ray_uint64_vec3f_vec3f_float32(uint64 id, vec3f start, vec3f dir, float32 max_t, mesh_query_ray_t* ret) { *ret = wp::mesh_query_ray(id, start, dir, max_t); } WP_API void builtin_mesh_query_aabb_uint64_vec3f_vec3f(uint64 id, vec3f lower, vec3f upper, mesh_query_aabb_t* ret) { *ret = wp::mesh_query_aabb(id, lower, upper); } WP_API void builtin_mesh_query_aabb_next_mesh_query_aabb_t_int32(mesh_query_aabb_t query, int32 index, bool* ret) { *ret = wp::mesh_query_aabb_next(query, index); } WP_API void builtin_mesh_eval_position_uint64_int32_float32_float32(uint64 id, int32 face, float32 bary_u, float32 bary_v, vec3f* ret) { *ret = wp::mesh_eval_position(id, face, bary_u, bary_v); } diff --git a/warp/native/mesh.h b/warp/native/mesh.h index b3febe53c..c536ad132 100644 --- a/warp/native/mesh.h +++ b/warp/native/mesh.h @@ -1181,7 +1181,7 @@ CUDA_CALLABLE inline bool mesh_query_point_sign_winding_number(uint64_t id, cons } } -CUDA_CALLABLE inline void adj_mesh_query_point_no_sign(uint64_t id, const vec3& point, float max_dist, int& face, float& u, float& v, +CUDA_CALLABLE inline void adj_mesh_query_point_no_sign(uint64_t id, const vec3& point, float max_dist, const int& face, const float& u, const float& v, uint64_t adj_id, vec3& adj_point, float& adj_max_dist, int& adj_face, float& adj_u, float& adj_v, bool& adj_ret) { Mesh mesh = mesh_get(id); @@ -1202,7 +1202,7 @@ CUDA_CALLABLE inline void adj_mesh_query_point_no_sign(uint64_t id, const vec3& adj_closest_point_to_triangle(p, q, r, point, adj_p, adj_q, adj_r, adj_point, adj_uv); } -CUDA_CALLABLE inline void adj_mesh_query_furthest_point_no_sign(uint64_t id, const vec3& point, float min_dist, int& face, float& u, float& v, +CUDA_CALLABLE inline void adj_mesh_query_furthest_point_no_sign(uint64_t id, const vec3& point, float min_dist, const int& face, const float& u, const float& v, uint64_t adj_id, vec3& adj_point, float& adj_min_dist, int& adj_face, float& adj_u, float& adj_v, bool& adj_ret) { Mesh mesh = mesh_get(id); @@ -1223,24 +1223,116 @@ CUDA_CALLABLE inline void adj_mesh_query_furthest_point_no_sign(uint64_t id, con adj_closest_point_to_triangle(p, q, r, point, adj_p, adj_q, adj_r, adj_point, adj_uv); // Todo for Miles :> } -CUDA_CALLABLE inline void adj_mesh_query_point(uint64_t id, const vec3& point, float max_dist, float& inside, int& face, float& u, float& v, +CUDA_CALLABLE inline void adj_mesh_query_point(uint64_t id, const vec3& point, float max_dist, const float& inside, const int& face, const float& u, const float& v, uint64_t adj_id, vec3& adj_point, float& adj_max_dist, float& adj_inside, int& adj_face, float& adj_u, float& adj_v, bool& adj_ret) { adj_mesh_query_point_no_sign(id, point, max_dist, face, u, v, adj_id, adj_point, adj_max_dist, adj_face, adj_u, adj_v, adj_ret); } -CUDA_CALLABLE inline void adj_mesh_query_point_sign_normal(uint64_t id, const vec3& point, float max_dist, float& inside, int& face, float& u, float& v, const float epsilon, +CUDA_CALLABLE inline void adj_mesh_query_point_sign_normal(uint64_t id, const vec3& point, float max_dist, const float& inside, const int& face, const float& u, const float& v, const float epsilon, uint64_t adj_id, vec3& adj_point, float& adj_max_dist, float& adj_inside, int& adj_face, float& adj_u, float& adj_v, float& adj_epsilon, bool& adj_ret) { adj_mesh_query_point_no_sign(id, point, max_dist, face, u, v, adj_id, adj_point, adj_max_dist, adj_face, adj_u, adj_v, adj_ret); } -CUDA_CALLABLE inline void adj_mesh_query_point_sign_winding_number(uint64_t id, const vec3& point, float max_dist, float& inside, int& face, float& u, float& v, const float accuracy, const float winding_number_threshold, +CUDA_CALLABLE inline void adj_mesh_query_point_sign_winding_number(uint64_t id, const vec3& point, float max_dist, const float& inside, const int& face, const float& u, const float& v, const float accuracy, const float winding_number_threshold, uint64_t adj_id, vec3& adj_point, float& adj_max_dist, float& adj_inside, int& adj_face, float& adj_u, float& adj_v, float& adj_accuracy, float& adj_winding_number_threshold, bool& adj_ret) { adj_mesh_query_point_no_sign(id, point, max_dist, face, u, v, adj_id, adj_point, adj_max_dist, adj_face, adj_u, adj_v, adj_ret); } + +// Stores the result of querying the closest point on a mesh. +struct mesh_query_point_t +{ + CUDA_CALLABLE mesh_query_point_t() + { + } + + CUDA_CALLABLE mesh_query_point_t(int) + { + // For backward pass. + } + + bool result; + float sign; + int face; + float u; + float v; +}; + +CUDA_CALLABLE inline mesh_query_point_t mesh_query_point(uint64_t id, const vec3& point, float max_dist) +{ + mesh_query_point_t query; + query.result = mesh_query_point(id, point, max_dist, query.sign, query.face, query.u, query.v); + return query; +} + +CUDA_CALLABLE inline mesh_query_point_t mesh_query_point_no_sign(uint64_t id, const vec3& point, float max_dist) +{ + mesh_query_point_t query; + query.sign = 0.0; + query.result = mesh_query_point_no_sign(id, point, max_dist, query.face, query.u, query.v); + return query; +} + +CUDA_CALLABLE inline mesh_query_point_t mesh_query_furthest_point_no_sign(uint64_t id, const vec3& point, float min_dist) +{ + mesh_query_point_t query; + query.sign = 0.0; + query.result = mesh_query_furthest_point_no_sign(id, point, min_dist, query.face, query.u, query.v); + return query; +} + +CUDA_CALLABLE inline mesh_query_point_t mesh_query_point_sign_normal(uint64_t id, const vec3& point, float max_dist, const float epsilon = 1e-3f) +{ + mesh_query_point_t query; + query.result = mesh_query_point_sign_normal(id, point, max_dist, query.sign, query.face, query.u, query.v, epsilon); + return query; +} + +CUDA_CALLABLE inline mesh_query_point_t mesh_query_point_sign_winding_number(uint64_t id, const vec3& point, float max_dist, float accuracy, float winding_number_threshold) +{ + mesh_query_point_t query; + query.result = mesh_query_point_sign_winding_number(id, point, max_dist, query.sign, query.face, query.u, query.v, accuracy, winding_number_threshold); + return query; +} + +CUDA_CALLABLE inline void adj_mesh_query_point(uint64_t id, const vec3& point, float max_dist, const mesh_query_point_t& ret, + uint64_t adj_id, vec3& adj_point, float& adj_max_dist, mesh_query_point_t& adj_ret) +{ + adj_mesh_query_point(id, point, max_dist, ret.sign, ret.face, ret.u, ret.v, + adj_id, adj_point, adj_max_dist, adj_ret.sign, adj_ret.face, adj_ret.u, adj_ret.v, adj_ret.result); +} + +CUDA_CALLABLE inline void adj_mesh_query_point_no_sign(uint64_t id, const vec3& point, float max_dist, const mesh_query_point_t& ret, + uint64_t adj_id, vec3& adj_point, float& adj_max_dist, mesh_query_point_t& adj_ret) +{ + adj_mesh_query_point_no_sign(id, point, max_dist, ret.face, ret.u, ret.v, + adj_id, adj_point, adj_max_dist, adj_ret.face, adj_ret.u, adj_ret.v, adj_ret.result); +} + +CUDA_CALLABLE inline void adj_mesh_query_furthest_point_no_sign(uint64_t id, const vec3& point, float min_dist, const mesh_query_point_t& ret, + uint64_t adj_id, vec3& adj_point, float& adj_min_dist, mesh_query_point_t& adj_ret) +{ + adj_mesh_query_furthest_point_no_sign(id, point, min_dist, ret.face, ret.u, ret.v, + adj_id, adj_point, adj_min_dist, adj_ret.face, adj_ret.u, adj_ret.v, adj_ret.result); +} + +CUDA_CALLABLE inline void adj_mesh_query_point_sign_normal(uint64_t id, const vec3& point, float max_dist, float epsilon, const mesh_query_point_t& ret, + uint64_t adj_id, vec3& adj_point, float& adj_max_dist, float& adj_epsilon, mesh_query_point_t& adj_ret) +{ + adj_mesh_query_point_sign_normal(id, point, max_dist, ret.sign, ret.face, ret.u, ret.v, epsilon, + adj_id, adj_point, adj_max_dist, adj_ret.sign, adj_ret.face, adj_ret.u, adj_ret.v, epsilon, adj_ret.result); +} + +CUDA_CALLABLE inline void adj_mesh_query_point_sign_winding_number(uint64_t id, const vec3& point, float max_dist, float accuracy, float winding_number_threshold, const mesh_query_point_t& ret, + uint64_t adj_id, vec3& adj_point, float& adj_max_dist, float& adj_accuracy, float& adj_winding_number_threshold, mesh_query_point_t& adj_ret) +{ + adj_mesh_query_point_sign_winding_number(id, point, max_dist, ret.sign, ret.face, ret.u, ret.v, accuracy, winding_number_threshold, + adj_id, adj_point, adj_max_dist, adj_ret.sign, adj_ret.face, adj_ret.u, adj_ret.v, adj_accuracy, adj_winding_number_threshold, adj_ret.result); +} + CUDA_CALLABLE inline bool mesh_query_ray(uint64_t id, const vec3& start, const vec3& dir, float max_t, float& t, float& u, float& v, float& sign, vec3& normal, int& face) { Mesh mesh = mesh_get(id); @@ -1353,6 +1445,35 @@ CUDA_CALLABLE inline void adj_mesh_query_ray( } +// Stores the result of querying the closest point on a mesh. +struct mesh_query_ray_t +{ + CUDA_CALLABLE mesh_query_ray_t() + { + } + + CUDA_CALLABLE mesh_query_ray_t(int) + { + // For backward pass. + } + + bool result; + float sign; + int face; + float t; + float u; + float v; + vec3 normal; +}; + +CUDA_CALLABLE inline mesh_query_ray_t mesh_query_ray(uint64_t id, const vec3& start, const vec3& dir, float max_t) +{ + mesh_query_ray_t query; + query.result = mesh_query_ray(id, start, dir, max_t, query.t, query.u, query.v, query.sign, query.normal, query.face); + return query; +} + + // determine if a point is inside (ret < 0 ) or outside the mesh (ret > 0) CUDA_CALLABLE inline float mesh_query_inside(uint64_t id, const vec3& p) { diff --git a/warp/tests/test_mesh_query_point.py b/warp/tests/test_mesh_query_point.py index b04f81b33..9650287ed 100644 --- a/warp/tests/test_mesh_query_point.py +++ b/warp/tests/test_mesh_query_point.py @@ -44,6 +44,12 @@ def sample_mesh_query( query_faces[tid] = face_index query_dist[tid] = wp.length(cp - p) + query = wp.mesh_query_point(mesh, p, max_dist) + wp.expect_eq(query.sign, sign) + wp.expect_eq(query.face, face_index) + wp.expect_eq(query.u, face_u) + wp.expect_eq(query.v, face_v) + @wp.kernel def sample_mesh_query_no_sign( @@ -69,6 +75,11 @@ def sample_mesh_query_no_sign( query_faces[tid] = face_index query_dist[tid] = wp.length(cp - p) + query = wp.mesh_query_point_no_sign(mesh, p, max_dist) + wp.expect_eq(query.face, face_index) + wp.expect_eq(query.u, face_u) + wp.expect_eq(query.v, face_v) + @wp.kernel def sample_mesh_query_sign_normal( @@ -97,6 +108,12 @@ def sample_mesh_query_sign_normal( query_faces[tid] = face_index query_dist[tid] = wp.length(cp - p) + query = wp.mesh_query_point_sign_normal(mesh, p, max_dist) + wp.expect_eq(query.sign, sign) + wp.expect_eq(query.face, face_index) + wp.expect_eq(query.u, face_u) + wp.expect_eq(query.v, face_v) + @wp.kernel def sample_mesh_query_sign_winding_number( @@ -125,6 +142,12 @@ def sample_mesh_query_sign_winding_number( query_faces[tid] = face_index query_dist[tid] = wp.length(cp - p) + query = wp.mesh_query_point_sign_winding_number(mesh, p, max_dist) + wp.expect_eq(query.sign, sign) + wp.expect_eq(query.face, face_index) + wp.expect_eq(query.u, face_u) + wp.expect_eq(query.v, face_v) + @wp.func def triangle_closest_point(a: wp.vec3, b: wp.vec3, c: wp.vec3, p: wp.vec3): @@ -574,6 +597,11 @@ def sample_furthest_points(mesh: wp.uint64, query_points: wp.array(dtype=wp.vec3 query_result[tid] = wp.length_sq(p - closest) + query = wp.mesh_query_furthest_point_no_sign(mesh, p, 0.0) + wp.expect_eq(query.face, face) + wp.expect_eq(query.u, bary_u) + wp.expect_eq(query.v, bary_v) + @wp.kernel def sample_furthest_points_brute( diff --git a/warp/types.py b/warp/types.py index 61e8ba27b..c3a419290 100644 --- a/warp/types.py +++ b/warp/types.py @@ -2979,6 +2979,37 @@ def allocate_by_tiles( return volume +# definition just for kernel type (cannot be a parameter), see mesh.h +# NOTE: its layout must match the corresponding struct defined in C. +# NOTE: it needs to be defined after `indexedarray` to workaround a circular import issue. +class mesh_query_point_t: + from warp.codegen import Var + + vars = { + "result": Var("result", bool), + "sign": Var("sign", float32), + "face": Var("face", int32), + "u": Var("u", float32), + "v": Var("v", float32), + } + + +# definition just for kernel type (cannot be a parameter), see mesh.h +# NOTE: its layout must match the corresponding struct defined in C. +class mesh_query_ray_t: + from warp.codegen import Var + + vars = { + "result": Var("result", bool), + "sign": Var("sign", float32), + "face": Var("face", int32), + "t": Var("t", float32), + "u": Var("u", float32), + "v": Var("v", float32), + "normal": Var("normal", vec3), + } + + def matmul( a: array2d, b: array2d, @@ -3957,7 +3988,7 @@ def infer_argument_types(args, template_types, arg_names=None): arg_types.append(arg._cls) # elif arg_type in [warp.types.launch_bounds_t, warp.types.shape_t, warp.types.range_t]: # arg_types.append(arg_type) - # elif arg_type in [warp.hash_grid_query_t, warp.mesh_query_aabb_t, warp.bvh_query_t]: + # elif arg_type in [warp.hash_grid_query_t, warp.mesh_query_aabb_t, warp.mesh_query_point_t, warp.mesh_query_ray_t, warp.bvh_query_t]: # arg_types.append(arg_type) elif arg is None: # allow passing None for arrays @@ -3995,6 +4026,8 @@ def infer_argument_types(args, template_types, arg_names=None): launch_bounds_t: "lb", hash_grid_query_t: "hgq", mesh_query_aabb_t: "mqa", + mesh_query_point_t: "mqp", + mesh_query_ray_t: "mqr", bvh_query_t: "bvhq", } From 172591ea003abc6a02b36ebe902a00738c585dae Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Tue, 5 Dec 2023 08:29:54 +1300 Subject: [PATCH 09/50] Add documentation for query types --- warp/builtins.py | 11 +++++------ warp/context.py | 8 ++++++++ warp/types.py | 33 +++++++++++++++++++++++++++++++++ 3 files changed, 46 insertions(+), 6 deletions(-) diff --git a/warp/builtins.py b/warp/builtins.py index d655dc819..a7ac4e132 100644 --- a/warp/builtins.py +++ b/warp/builtins.py @@ -1483,7 +1483,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): value_type=bvh_query_t, group="Geometry", doc="""Construct an axis-aligned bounding box query against a BVH object. This query can be used to iterate over all bounds - inside a BVH. Returns an object that is used to track state during BVH traversal. + inside a BVH. :param id: The BVH identifier :param lower: The lower bound of the bounding box in BVH space @@ -1496,7 +1496,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): value_type=bvh_query_t, group="Geometry", doc="""Construct a ray query against a BVH object. This query can be used to iterate over all bounds - that intersect the ray. Returns an object that is used to track state during BVH traversal. + that intersect the ray. :param id: The BVH identifier :param start: The start of the ray in BVH space @@ -1786,7 +1786,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): }, value_type=builtins.bool, group="Geometry", - doc="""Computes the closest ray hit on the :class:`Mesh` with identifier ``id``, returns ``True`` if a point < ``max_t`` is found. + doc="""Computes the closest ray hit on the :class:`Mesh` with identifier ``id``, returns ``True`` if a hit < ``max_t`` is found. :param id: The mesh identifier :param start: The start point of the ray @@ -1795,7 +1795,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param t: Returns the distance of the closest hit along the ray :param bary_u: Returns the barycentric u coordinate of the closest hit :param bary_v: Returns the barycentric v coordinate of the closest hit - :param sign: Returns a value > 0 if the hit ray hit front of the face, returns < 0 otherwise + :param sign: Returns a value > 0 if the ray hit in front of the face, returns < 0 otherwise :param normal: Returns the face normal :param face: Returns the index of the hit face""", ) @@ -1826,7 +1826,6 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): group="Geometry", doc="""Construct an axis-aligned bounding box query against a :class:`Mesh`. This query can be used to iterate over all triangles inside a volume. - Returns an object that is used to track state during mesh traversal. :param id: The mesh identifier :param lower: The lower bound of the bounding box in mesh space @@ -1864,7 +1863,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): value_type=hash_grid_query_t, group="Geometry", doc="Construct a point query against a :class:`HashGrid`. This query can be used to iterate over all neighboring points " - "within a fixed radius from the query point. Returns an object that is used to track state during neighbor traversal.", + "within a fixed radius from the query point.", ) add_builtin( diff --git a/warp/context.py b/warp/context.py index a9688a56a..c1ccc20ee 100644 --- a/warp/context.py +++ b/warp/context.py @@ -4036,6 +4036,14 @@ def print_builtins(file): # pragma: no cover print(".. class:: Transformation", file=file) print(".. class:: Array", file=file) + print("\nQuery Types", file=file) + print("-------------", file=file) + print(".. autoclass:: bvh_query_t", file=file) + print(".. autoclass:: hash_grid_query_t", file=file) + print(".. autoclass:: mesh_query_aabb_t", file=file) + print(".. autoclass:: mesh_query_point_t", file=file) + print(".. autoclass:: mesh_query_ray_t", file=file) + # build dictionary of all functions by group groups = {} diff --git a/warp/types.py b/warp/types.py index c3a419290..3e056174b 100644 --- a/warp/types.py +++ b/warp/types.py @@ -910,18 +910,21 @@ def __init__(self): # definition just for kernel type (cannot be a parameter), see bvh.h class bvh_query_t: + """Object used to track state during BVH traversal.""" def __init__(self): pass # definition just for kernel type (cannot be a parameter), see mesh.h class mesh_query_aabb_t: + """Object used to track state during mesh traversal.""" def __init__(self): pass # definition just for kernel type (cannot be a parameter), see hash_grid.h class hash_grid_query_t: + """Object used to track state during neighbor traversal.""" def __init__(self): pass @@ -2983,6 +2986,22 @@ def allocate_by_tiles( # NOTE: its layout must match the corresponding struct defined in C. # NOTE: it needs to be defined after `indexedarray` to workaround a circular import issue. class mesh_query_point_t: + """Output for the mesh query point functions. + + Attributes: + result (bool): Whether a point is found within the given constraints. + sign (float32): A value < 0 if query point is inside the mesh, >=0 otherwise. + Note that mesh must be watertight for this to be robust + face (int32): Index of the closest face. + u (float32): Barycentric u coordinate of the closest point. + v (float32): Barycentric v coordinate of the closest point. + + See Also: + :func:`mesh_query_point`, :func:`mesh_query_point_no_sign`, + :func:`mesh_query_furthest_point_no_sign`, + :func:`mesh_query_point_sign_normal`, + and :func:`mesh_query_point_sign_winding_number`. + """ from warp.codegen import Var vars = { @@ -2997,6 +3016,20 @@ class mesh_query_point_t: # definition just for kernel type (cannot be a parameter), see mesh.h # NOTE: its layout must match the corresponding struct defined in C. class mesh_query_ray_t: + """Output for the mesh query ray functions. + + Attributes: + result (bool): Whether a hit is found within the given constraints. + sign (float32): A value > 0 if the ray hit in front of the face, returns < 0 otherwise. + face (int32): Index of the closest face. + t (float32): Distance of the closest hit along the ray. + u (float32): Barycentric u coordinate of the closest hit. + v (float32): Barycentric v coordinate of the closest hit. + normal (vec3f): Face normal. + + See Also: + :func:`mesh_query_ray`. + """ from warp.codegen import Var vars = { From bde240e0ade3f258b1b0c84e1022ba1d1b45f8a9 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Tue, 5 Dec 2023 08:36:21 +1300 Subject: [PATCH 10/50] Hide the previous mesh query builtins --- warp/builtins.py | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/warp/builtins.py b/warp/builtins.py index a7ac4e132..c7eb52014 100644 --- a/warp/builtins.py +++ b/warp/builtins.py @@ -1539,6 +1539,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param face: Returns the index of the closest face :param bary_u: Returns the barycentric u coordinate of the closest point :param bary_v: Returns the barycentric v coordinate of the closest point""", + hidden=True, ) add_builtin( @@ -1584,6 +1585,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param face: Returns the index of the closest face :param bary_u: Returns the barycentric u coordinate of the closest point :param bary_v: Returns the barycentric v coordinate of the closest point""", + hidden=True, ) add_builtin( @@ -1627,6 +1629,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param face: Returns the index of the furthest face :param bary_u: Returns the barycentric u coordinate of the furthest point :param bary_v: Returns the barycentric v coordinate of the furthest point""", + hidden=True, ) add_builtin( @@ -1679,6 +1682,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param bary_v: Returns the barycentric v coordinate of the closest point :param epsilon: Epsilon treating distance values as equal, when locating the minimum distance vertex/face/edge, as a fraction of the average edge length, also for treating closest point as being on edge/vertex default 1e-3""", + hidden=True, ) add_builtin( @@ -1740,6 +1744,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param bary_v: Returns the barycentric v coordinate of the closest point :param accuracy: Accuracy for computing the winding number with fast winding number method utilizing second-order dipole approximation, default 2.0 :param threshold: The threshold of the winding number to be considered inside, default 0.5""", + hidden=True, ) add_builtin( @@ -1798,6 +1803,7 @@ def spatial_vector_constructor_value_func(arg_types, kwds, templates): :param sign: Returns a value > 0 if the ray hit in front of the face, returns < 0 otherwise :param normal: Returns the face normal :param face: Returns the index of the hit face""", + hidden=True, ) add_builtin( From 14d1f09fd06b09ab349d36e3856bba8393899242 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Mon, 4 Dec 2023 16:15:20 -0500 Subject: [PATCH 11/50] Add a backward test for returning a reference Currently `test_grad()` fails when `lookup3()` directly returns a reference to an array element. --- warp/tests/test_lvalue.py | 54 ++++++++++++++++++++++++++++++++++++++- 1 file changed, 53 insertions(+), 1 deletion(-) diff --git a/warp/tests/test_lvalue.py b/warp/tests/test_lvalue.py index 789bf44dc..53fec71bd 100644 --- a/warp/tests/test_lvalue.py +++ b/warp/tests/test_lvalue.py @@ -1,4 +1,5 @@ import warp as wp +import numpy as np from warp.tests.test_base import * import unittest @@ -88,6 +89,56 @@ def test_lookup(test, device): raise AssertionError(f"Unexpected result, got: {f} expected: {1}") +@wp.func +def lookup3(foos: wp.array(dtype=wp.float32), index: int): + # FIXME: return foos[index] + x = foos[index] + return x + + +@wp.kernel +def grad_kernel(foos: wp.array(dtype=wp.float32), bars: wp.array(dtype=wp.float32)): + i = wp.tid() + + x = lookup3(foos, i) + bars[i] = x * wp.float32(i) + 1.0 + + +def test_grad(test, device): + num = 10 + data = np.linspace(20, 20 + num, num, endpoint=False, dtype=np.float32) + input = wp.array(data, device=device, requires_grad=True) + output = wp.zeros(num, dtype=wp.float32, device=device) + + ones = wp.array(np.ones(len(output)), dtype=wp.float32, device=device) + + tape = wp.Tape() + with tape: + wp.launch( + kernel=grad_kernel, + dim=(num,), + inputs=[input], + outputs=[output], + device=device, + ) + + tape.backward(grads={output: ones}) + + wp.synchronize() + + # test forward results + for i, f in enumerate(output.list()): + expected = data[i] * i + 1 + if f != expected: + raise AssertionError(f"Unexpected result, got: {f} expected: {expected}") + + # test backward results + for i, f in enumerate(tape.gradients[input].list()): + expected = i + if f != expected: + raise AssertionError(f"Unexpected result, got: {f} expected: {expected}") + + @wp.func def lookup2(foos: wp.array(dtype=wp.uint32), index: int): if index % 2 == 0: @@ -102,7 +153,7 @@ def lookup2(foos: wp.array(dtype=wp.uint32), index: int): def lookup2_kernel(foos: wp.array(dtype=wp.uint32)): i = wp.tid() - x = lookup(foos, i) + x = lookup2(foos, i) foos[i] = x + wp.uint32(1) @@ -425,6 +476,7 @@ class TestLValue(parent): add_function_test(TestLValue, "test_rmw_array_struct", test_rmw_array_struct, devices=devices) add_function_test(TestLValue, "test_lookup", test_lookup, devices=devices) add_function_test(TestLValue, "test_lookup2", test_lookup2, devices=devices) + add_function_test(TestLValue, "test_grad", test_grad, devices=devices) add_function_test(TestLValue, "test_unary", test_unary, devices=devices) add_function_test(TestLValue, "test_rvalue", test_rvalue, devices=devices) add_function_test(TestLValue, "test_intermediate", test_intermediate, devices=devices) From ceb4dbe9b0d72e542ad03e0420ab92b65f903fdf Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Mon, 4 Dec 2023 16:50:54 -0500 Subject: [PATCH 12/50] Fix backpropagation for returning array element references In the forward pass returning a reference would result in a `load()` operation, but this isn't differentiable. By instead emitting a `copy()` into a temporary variable, we can reuse the value from the forward pass in the backward pass. --- warp/codegen.py | 9 ++++++--- warp/tests/test_lvalue.py | 4 +--- 2 files changed, 7 insertions(+), 6 deletions(-) diff --git a/warp/codegen.py b/warp/codegen.py index f1db21796..30ab0fdb4 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -967,7 +967,9 @@ def add_call(adj, func, args, min_outputs=None, templates=[], kwds=None): adj.add_forward(forward_call, replay=replay_call) if not func.missing_grad and len(args): - reverse_has_output_args = (func.require_original_output_arg or len(output_list) > 1) and func.custom_grad_func is None + reverse_has_output_args = ( + func.require_original_output_arg or len(output_list) > 1 + ) and func.custom_grad_func is None arg_str = adj.format_reverse_call_args( args_var, args, @@ -1903,7 +1905,8 @@ def emit_Return(adj, node): if var is not None: adj.return_var = tuple() for ret in var: - ret = adj.load(ret) + if is_reference(ret.type): + ret = adj.add_builtin_call("copy", [ret]) adj.return_var += (ret,) adj.add_return(adj.return_var) @@ -1947,7 +1950,7 @@ def emit_Pass(adj, node): ast.AugAssign: emit_AugAssign, ast.Tuple: emit_Tuple, ast.Pass: emit_Pass, - ast.Ellipsis: emit_Ellipsis + ast.Ellipsis: emit_Ellipsis, } def eval(adj, node): diff --git a/warp/tests/test_lvalue.py b/warp/tests/test_lvalue.py index 53fec71bd..0eb7471c4 100644 --- a/warp/tests/test_lvalue.py +++ b/warp/tests/test_lvalue.py @@ -91,9 +91,7 @@ def test_lookup(test, device): @wp.func def lookup3(foos: wp.array(dtype=wp.float32), index: int): - # FIXME: return foos[index] - x = foos[index] - return x + return foos[index] @wp.kernel From cb6e90c75ea612f6b13b0bff77a07103d5198059 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Tue, 5 Dec 2023 09:19:25 -0500 Subject: [PATCH 13/50] Copy linux-x86_64 CI build script to linux-aarch64 Just a verbatim copy as a starting point. `step.sh` is based on a very outdated script. It's contents are added to `build.sh` as comment just for reference. --- .../ci/building/build-linux-aarch64/build.sh | 73 +++++++++++++++++++ tools/ci/building/build-linux-aarch64/step.sh | 22 ------ 2 files changed, 73 insertions(+), 22 deletions(-) create mode 100755 tools/ci/building/build-linux-aarch64/build.sh delete mode 100755 tools/ci/building/build-linux-aarch64/step.sh diff --git a/tools/ci/building/build-linux-aarch64/build.sh b/tools/ci/building/build-linux-aarch64/build.sh new file mode 100755 index 000000000..013e990a5 --- /dev/null +++ b/tools/ci/building/build-linux-aarch64/build.sh @@ -0,0 +1,73 @@ +##!/usr/bin/env bash +# +#set -e +# +#SCRIPT_DIR="$(dirname "${BASH_SOURCE}")" +# +## Verify formatting +## "$SCRIPT_DIR/../../../../format_code.sh" --verify +# +## Full rebuild +#"$SCRIPT_DIR/../../../../build.sh" -x --platform-target linux-aarch64 +# +## Package all +#"$SCRIPT_DIR/../../../../tools/package.sh" -a -c release --platform-target linux-aarch64 +# +## Package all +#"$SCRIPT_DIR/../../../../tools/package.sh" -a -c debug --platform-target linux-aarch64 +# +## publish artifacts to teamcity +#echo "##teamcity[publishArtifacts '_build/packages']" + +#!/bin/bash +set -e + +USE_LINBUILD=1 +BUILD_MODE="release" + +# scan command line for options +for arg; do + shift + case $arg in + --no-docker) + USE_LINBUILD=0 + ;; + --debug) + BUILD_MODE="debug" + ;; + esac + + # keep all options (including --no-docker) to pass to repo.sh + if [[ $arg != "--debug" ]]; then + set -- "$@" "$arg" + fi +done + +SCRIPT_DIR=$(dirname ${BASH_SOURCE}) +#source "$SCRIPT_DIR/repo.sh" build --fetch-only $@ || exit $? + +"$SCRIPT_DIR/../../../../repo.sh" build --fetch-only $@ + +PYTHON="$SCRIPT_DIR/../../../../_build/target-deps/python/python" +LINBUILD="$SCRIPT_DIR/../../../../_build/host-deps/linbuild/linbuild.sh" +CUDA="$SCRIPT_DIR/../../../../_build/target-deps/cuda" + +# pip deps +$PYTHON -m pip install --upgrade pip +$PYTHON -m pip install numpy +$PYTHON -m pip install gitpython +$PYTHON -m pip install cmake +$PYTHON -m pip install ninja + +if [[ "$OSTYPE" == "darwin"* ]]; then + $PYTHON "$SCRIPT_DIR/../../../../build_lib.py" +else + if [ ${USE_LINBUILD} -ne 0 ]; then + # build with docker for increased compatibility + $LINBUILD -- $PYTHON "$SCRIPT_DIR/../../../../build_lib.py" --cuda_path=$CUDA --mode=$BUILD_MODE + else + # build without docker + $PYTHON "$SCRIPT_DIR/../../../../build_lib.py" --cuda_path=$CUDA --mode=$BUILD_MODE + fi +fi + diff --git a/tools/ci/building/build-linux-aarch64/step.sh b/tools/ci/building/build-linux-aarch64/step.sh deleted file mode 100755 index 3ea1d4b82..000000000 --- a/tools/ci/building/build-linux-aarch64/step.sh +++ /dev/null @@ -1,22 +0,0 @@ -#!/usr/bin/env bash - -set -e - -SCRIPT_DIR="$(dirname "${BASH_SOURCE}")" - -# Verify formatting -# "$SCRIPT_DIR/../../../../format_code.sh" --verify - -# Full rebuild -"$SCRIPT_DIR/../../../../build.sh" -x --platform-target linux-aarch64 - -# Package all -"$SCRIPT_DIR/../../../../tools/package.sh" -a -c release --platform-target linux-aarch64 - -# Package all -"$SCRIPT_DIR/../../../../tools/package.sh" -a -c debug --platform-target linux-aarch64 - -# publish artifacts to teamcity -echo "##teamcity[publishArtifacts '_build/packages']" - - From bb57da3d785d2ec7483a8d00353f2eceeb8a952a Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Tue, 5 Dec 2023 09:39:34 -0500 Subject: [PATCH 14/50] Support building LLVM for AArch64 on non-Apple systems --- build_llvm.py | 25 +++++++++++++++++++++++-- 1 file changed, 23 insertions(+), 2 deletions(-) diff --git a/build_llvm.py b/build_llvm.py index ed4f21b04..f916eae76 100644 --- a/build_llvm.py +++ b/build_llvm.py @@ -1,6 +1,7 @@ import os import subprocess import sys +import platform import warp from warp.build_dll import build_dll_for_arch, run_cmd @@ -14,6 +15,18 @@ llvm_install_path = os.path.join(llvm_project_path, "out/install/") +# return a canonical machine architecture string +# - "x86_64" for x86-64, aka. AMD64, aka. x64 +# - "aarch64" for AArch64, aka. ARM64 +def machine_architecture() -> str: + machine = platform.machine() + if machine == "x86_64" or machine == "AMD64": + return "x86_64" + if machine == "aarch64" or machine == "arm64": + return "aarch64" + raise RuntimeError(f"Unrecognized machine architecture {machine}") + + # Fetch prebuilt Clang/LLVM libraries def fetch_prebuilt_libraries(): if os.name == "nt": @@ -282,10 +295,18 @@ def build_from_source(args): else: llvm_source = llvm_project_path - build_from_source_for_arch(args, "x86_64", llvm_source) + # build for the machine's architecture + if machine_architecture() == "x86_64": + build_from_source_for_arch(args, "x86_64", llvm_source) + else: + build_from_source_for_arch(args, "arm64", llvm_source) + # for Apple systems also cross-compile for building a universal binary if sys.platform == "darwin": - build_from_source_for_arch(args, "arm64", llvm_source) + if machine_architecture() == "x86_64": + build_from_source_for_arch(args, "arm64", llvm_source) + else: + build_from_source_for_arch(args, "x86_64", llvm_source) # build warp-clang.dll From 4a28d93ffdd190f237c64ac6b9dbc197fb8b2d28 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Tue, 5 Dec 2023 11:04:13 -0500 Subject: [PATCH 15/50] Fix LLVM build of BLAKE3 for non-OSX AArch64 LLVM 15's build files for the BLAKE3 hash functions assume that if `CMAKE_OSX_ARCHITECTURES` is defined we want to compile the x86 SSE/AVX optimized version. This depends on having a suitable cross-architecture assembler, which typically isn't available on Linux AArch64. --- build_llvm.py | 9 ++++++--- 1 file changed, 6 insertions(+), 3 deletions(-) diff --git a/build_llvm.py b/build_llvm.py index f916eae76..7c453cc07 100644 --- a/build_llvm.py +++ b/build_llvm.py @@ -102,14 +102,17 @@ def build_from_source_for_arch(args, arch, llvm_source): if sys.platform == "darwin": host_triple = f"{arch}-apple-macos11" + osx_architectures = arch # build one architecture only elif os.name == "nt": host_triple = f"{arch}-pc-windows" + osx_architectures = "" else: host_triple = f"{arch}-pc-linux" + osx_architectures = "" llvm_path = os.path.join(llvm_source, "llvm") - build_path = os.path.join(llvm_build_path, f"{warp.config.mode}-{ arch}") - install_path = os.path.join(llvm_install_path, f"{warp.config.mode}-{ arch}") + build_path = os.path.join(llvm_build_path, f"{warp.config.mode}-{arch}") + install_path = os.path.join(llvm_install_path, f"{warp.config.mode}-{arch}") # Build LLVM and Clang cmake_gen = [ @@ -143,7 +146,7 @@ def build_from_source_for_arch(args, arch, llvm_source): "-D", "CMAKE_CXX_FLAGS=-D_GLIBCXX_USE_CXX11_ABI=0", # The pre-C++11 ABI is still the default on the CentOS 7 toolchain "-D", f"CMAKE_INSTALL_PREFIX={install_path}", "-D", f"LLVM_HOST_TRIPLE={host_triple}", - "-D", f"CMAKE_OSX_ARCHITECTURES={ arch}", + "-D", f"CMAKE_OSX_ARCHITECTURES={osx_architectures}", # Disable unused tools and features "-D", "CLANG_BUILD_TOOLS=FALSE", From 2156cc2b4551e2eb9ba4dcfdeed2a6be410b1d72 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Tue, 5 Dec 2023 11:39:03 -0500 Subject: [PATCH 16/50] Support building warp-clang.so for AArch64 on non-Darwin platforms --- build_llvm.py | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/build_llvm.py b/build_llvm.py index 7c453cc07..8ca188b2e 100644 --- a/build_llvm.py +++ b/build_llvm.py @@ -380,4 +380,7 @@ def build_warp_clang(args, lib_name): os.remove(f"{dylib_path}-arm64") else: - build_warp_clang_for_arch(args, lib_name, "x86_64") + if machine_architecture() == "x86_64": + build_warp_clang_for_arch(args, lib_name, "x86_64") + else: + build_warp_clang_for_arch(args, lib_name, "arm64") From 04a9332ee14c3155b00df47bb8eb9f7d8be4e6f9 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Tue, 5 Dec 2023 13:42:26 -0500 Subject: [PATCH 17/50] Remove deprecated Packman credentials configuration The referenced repository has been removed. See https://confluence.nvidia.com/pages/viewpage.action?pageId=1822616759 for details. Instead we can now use https://omnipackages.nvidia.com/packages/publish to manually upload packages created by `tools/packman/packman pack `. --- tools/packman/config.packman.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/tools/packman/config.packman.xml b/tools/packman/config.packman.xml index 7402744d3..e72195910 100644 --- a/tools/packman/config.packman.xml +++ b/tools/packman/config.packman.xml @@ -1,7 +1,6 @@ - From df4c9ba7e1b1438919bde20c5d6dce90c31ef23a Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Tue, 5 Dec 2023 13:48:47 -0500 Subject: [PATCH 18/50] Build warp-clang.so for Linux AArch64 from prebuilt LLVM libraries --- build_llvm.py | 5 ++++- .../ci/building/build-linux-aarch64/build.sh | 21 ------------------- 2 files changed, 4 insertions(+), 22 deletions(-) diff --git a/build_llvm.py b/build_llvm.py index 8ca188b2e..975f96e7b 100644 --- a/build_llvm.py +++ b/build_llvm.py @@ -40,7 +40,10 @@ def fetch_prebuilt_libraries(): "x86_64": "15.0.7-darwin-x86_64-macos11", } else: - packages = {"x86_64": "15.0.7-linux-x86_64-ptx-gcc7.5-cxx11abi0"} + packages = { + "arm64": "15.0.7-linux-aarch64-gcc7.5", + "x86_64": "15.0.7-linux-x86_64-ptx-gcc7.5-cxx11abi0", + } for arch in packages: subprocess.check_call( diff --git a/tools/ci/building/build-linux-aarch64/build.sh b/tools/ci/building/build-linux-aarch64/build.sh index 013e990a5..1087cf5dd 100755 --- a/tools/ci/building/build-linux-aarch64/build.sh +++ b/tools/ci/building/build-linux-aarch64/build.sh @@ -1,24 +1,3 @@ -##!/usr/bin/env bash -# -#set -e -# -#SCRIPT_DIR="$(dirname "${BASH_SOURCE}")" -# -## Verify formatting -## "$SCRIPT_DIR/../../../../format_code.sh" --verify -# -## Full rebuild -#"$SCRIPT_DIR/../../../../build.sh" -x --platform-target linux-aarch64 -# -## Package all -#"$SCRIPT_DIR/../../../../tools/package.sh" -a -c release --platform-target linux-aarch64 -# -## Package all -#"$SCRIPT_DIR/../../../../tools/package.sh" -a -c debug --platform-target linux-aarch64 -# -## publish artifacts to teamcity -#echo "##teamcity[publishArtifacts '_build/packages']" - #!/bin/bash set -e From 08f4d6b7fd551abe444c45a4018d35b7043d1372 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Tue, 5 Dec 2023 15:21:58 -0500 Subject: [PATCH 19/50] Copy the Linux x86-64 CI test script for AArch64 --- tools/ci/testing/test-linux-aarch64/step.sh | 8 -------- tools/ci/testing/test-linux-aarch64/test.sh | 19 +++++++++++++++++++ 2 files changed, 19 insertions(+), 8 deletions(-) delete mode 100755 tools/ci/testing/test-linux-aarch64/step.sh create mode 100755 tools/ci/testing/test-linux-aarch64/test.sh diff --git a/tools/ci/testing/test-linux-aarch64/step.sh b/tools/ci/testing/test-linux-aarch64/step.sh deleted file mode 100755 index 8268c323c..000000000 --- a/tools/ci/testing/test-linux-aarch64/step.sh +++ /dev/null @@ -1,8 +0,0 @@ -#!/usr/bin/env bash - -set -e - -SCRIPT_DIR="$(dirname "${BASH_SOURCE}")" - -# tests -"$SCRIPT_DIR/../../../../repo.sh" test --config release --from-package diff --git a/tools/ci/testing/test-linux-aarch64/test.sh b/tools/ci/testing/test-linux-aarch64/test.sh new file mode 100755 index 000000000..44da31bd3 --- /dev/null +++ b/tools/ci/testing/test-linux-aarch64/test.sh @@ -0,0 +1,19 @@ +#!/bin/bash +set -e + +SCRIPT_DIR=$(dirname ${BASH_SOURCE}) +"$SCRIPT_DIR/../../../../repo.sh" build --fetch-only $@ + +PYTHON="$SCRIPT_DIR/../../../../_build/target-deps/python/python" + +echo "Installing test dependencies" +#$PYTHON -m pip install matplotlib +#$PYTHON -m pip install usd-core +#$PYTHON -m pip install torch --extra-index-url https://download.pytorch.org/whl/cu113 +#$PYTHON -m pip install "jax[cuda]" -f https://storage.googleapis.com/jax-releases/jax_cuda_releases.html + +echo "Installing Warp to Python" +$PYTHON -m pip install -e "$SCRIPT_DIR/../../../../." + +echo "Running tests" +$PYTHON "$SCRIPT_DIR/../../../../warp/tests/test_all.py" From 4a5697aaffe66b67b88bd54b37fa412fe8f67239 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Wed, 6 Dec 2023 16:10:36 -0500 Subject: [PATCH 20/50] Fix wp.synchronize() errors if CUDA is unavailable If the Warp DLLs were built with CUDA enabled (i.e. the SDK is present), but there is no runtime CUDA support, the `wp.synchronize()` call previously produced an error: `Warp CUDA error: Function cuCtxGetCurrent_f: a suitable driver entry point was not found` This change properly checks whether the CUDA driver has been successfully initialized. --- warp/native/cuda_util.cpp | 11 ++++++++--- warp/native/cuda_util.h | 1 + warp/native/warp.cu | 7 +------ 3 files changed, 10 insertions(+), 9 deletions(-) diff --git a/warp/native/cuda_util.cpp b/warp/native/cuda_util.cpp index 3b07043dd..1448357af 100644 --- a/warp/native/cuda_util.cpp +++ b/warp/native/cuda_util.cpp @@ -89,6 +89,7 @@ static PFN_cuGraphicsResourceGetMappedPointer_v3020 pfn_cuGraphicsResourceGetMap static PFN_cuGraphicsGLRegisterBuffer_v3000 pfn_cuGraphicsGLRegisterBuffer; static PFN_cuGraphicsUnregisterResource_v3000 pfn_cuGraphicsUnregisterResource; +static bool cuda_driver_initialized = false; bool ContextGuard::always_restore = false; @@ -196,11 +197,15 @@ bool init_cuda_driver() get_driver_entry_point("cuGraphicsUnregisterResource", &(void*&)pfn_cuGraphicsUnregisterResource); if (pfn_cuInit) - return check_cu(pfn_cuInit(0)); - else - return false; + cuda_driver_initialized = check_cu(pfn_cuInit(0)); + + return cuda_driver_initialized; } +bool is_cuda_driver_initialized() +{ + return cuda_driver_initialized; +} bool check_cuda_result(cudaError_t code, const char* file, int line) { diff --git a/warp/native/cuda_util.h b/warp/native/cuda_util.h index 446109554..27acaff5d 100644 --- a/warp/native/cuda_util.h +++ b/warp/native/cuda_util.h @@ -83,6 +83,7 @@ CUresult cuGraphicsUnregisterResource_f(CUgraphicsResource resource); bool init_cuda_driver(); +bool is_cuda_driver_initialized(); bool check_cuda_result(cudaError_t code, const char* file, int line); inline bool check_cuda_result(uint64_t code, const char* file, int line) diff --git a/warp/native/warp.cu b/warp/native/warp.cu index c48ba430b..9ae10de1d 100644 --- a/warp/native/warp.cu +++ b/warp/native/warp.cu @@ -1143,12 +1143,7 @@ int cuda_toolkit_version() bool cuda_driver_is_initialized() { - CUcontext ctx; - - // result can be: CUDA_SUCCESS, CUDA_ERROR_DEINITIALIZED, CUDA_ERROR_NOT_INITIALIZED - CUresult result = cuCtxGetCurrent_f(&ctx); - - return result == CUDA_SUCCESS; + return is_cuda_driver_initialized(); } int nvrtc_supported_arch_count() From 48ad930a8fcbfeb6755378b2618db04d504c75a0 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Wed, 6 Dec 2023 23:12:36 -0500 Subject: [PATCH 21/50] Upgrade to Python 3.9 for testing Linux AArch64 builds PyPI currently only has binary wheels of numpy for Python 3.9+. While there's also a source distribution, it fails to build properly on Linux AArch64 due to dependencies that can't be met. --- deps/target-deps.packman.xml | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/deps/target-deps.packman.xml b/deps/target-deps.packman.xml index 1c2f42321..2620a1ae4 100644 --- a/deps/target-deps.packman.xml +++ b/deps/target-deps.packman.xml @@ -23,10 +23,11 @@ --> - + - - + + + From 79cd8c118786230e8c0cda573ae3f9d1ab0b65f8 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Thu, 7 Dec 2023 00:27:45 -0500 Subject: [PATCH 22/50] Skip testing FEM examples if USD is unavailable The FEM examples depend on the `usd-core` package, which isn't available for AArch64 at this time. --- warp/tests/test_examples.py | 55 ++++++++++++++++++++++--------------- 1 file changed, 33 insertions(+), 22 deletions(-) diff --git a/warp/tests/test_examples.py b/warp/tests/test_examples.py index dd0040edd..a87497841 100644 --- a/warp/tests/test_examples.py +++ b/warp/tests/test_examples.py @@ -82,28 +82,39 @@ class TestExamples(parent): add_example_test(TestExamples, name="example_wave", options={"resx": 256, "resy": 256}) add_example_test(TestExamples, name="fem.example_diffusion_mgpu", options={"quiet": True, "num_frames": 1}) - # The following examples do not need cuda - add_example_test(TestExamples, name="fem.example_apic_fluid", options={"quiet": True, "res": [16, 16, 16]}) - add_example_test( - TestExamples, - name="fem.example_diffusion", - options={"quiet": True, "resolution": 10, "mesh": "tri", "num_frames": 1}, - ) - add_example_test( - TestExamples, name="fem.example_diffusion_3d", options={"quiet": True, "resolution": 10, "num_frames": 1} - ) - add_example_test( - TestExamples, - name="fem.example_deformed_geometry", - options={"quiet": True, "resolution": 10, "num_frames": 1, "mesh": "tri"}, - ) - add_example_test(TestExamples, name="fem.example_convection_diffusion", options={"quiet": True, "resolution": 20}) - add_example_test( - TestExamples, - name="fem.example_mixed_elasticity", - options={"quiet": True, "nonconforming_stresses": True, "mesh": "quad", "num_frames": 1}, - ) - add_example_test(TestExamples, name="fem.example_stokes_transfer", options={"quiet": True, "num_frames": 1}) + # USD import failures should not count as a test failure + try: + from pxr import Usd, UsdGeom + + have_usd = True + except: + have_usd = False + + # The following examples do not need CUDA, but they need USD + if have_usd: + add_example_test(TestExamples, name="fem.example_apic_fluid", options={"quiet": True, "res": [16, 16, 16]}) + add_example_test( + TestExamples, + name="fem.example_diffusion", + options={"quiet": True, "resolution": 10, "mesh": "tri", "num_frames": 1}, + ) + add_example_test( + TestExamples, name="fem.example_diffusion_3d", options={"quiet": True, "resolution": 10, "num_frames": 1} + ) + add_example_test( + TestExamples, + name="fem.example_deformed_geometry", + options={"quiet": True, "resolution": 10, "num_frames": 1, "mesh": "tri"}, + ) + add_example_test( + TestExamples, name="fem.example_convection_diffusion", options={"quiet": True, "resolution": 20} + ) + add_example_test( + TestExamples, + name="fem.example_mixed_elasticity", + options={"quiet": True, "nonconforming_stresses": True, "mesh": "quad", "num_frames": 1}, + ) + add_example_test(TestExamples, name="fem.example_stokes_transfer", options={"quiet": True, "num_frames": 1}) return TestExamples From c46c4c5712416480ddcbd1493ce75abb32b3b671 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Fri, 8 Dec 2023 15:18:16 -0500 Subject: [PATCH 23/50] Fix getting the source segment the AST was constructed from `ast.get_source_segment(source, node)` expects that the `source` is the same as the one the `node` was parsed from. `adj.raw_source` does not include the `dedent()` operation that happens in `Adjoint`'s constructor prior to AST construction. --- warp/codegen.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/warp/codegen.py b/warp/codegen.py index 30ab0fdb4..7cb7ab885 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -2083,7 +2083,7 @@ def set_lineno(adj, lineno): def get_node_source(adj, node): # return the Python code corresponding to the given AST node - return ast.get_source_segment("".join(adj.raw_source), node) + return ast.get_source_segment(adj.source, node) # ---------------- From dd000d7f7e17af453802edd44adf4eee48d53e90 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Fri, 8 Dec 2023 15:56:13 -0500 Subject: [PATCH 24/50] Use only the source code used for AST parsing `adj.raw_source` was only used for annotating the generated code with the original Python code. It is identical to `adj.source` except the latter is dedented and not split into lines yet. The original indentation doesn't matter because it is stripped. Other than eliminating `adj.raw_source` the code was restructured for readability. --- warp/codegen.py | 22 ++++++++++------------ 1 file changed, 10 insertions(+), 12 deletions(-) diff --git a/warp/codegen.py b/warp/codegen.py index 7cb7ab885..d70553458 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -518,21 +518,16 @@ def __init__( # whether the generation of the adjoint code is skipped for this function adj.skip_reverse_codegen = skip_reverse_codegen - # build AST from function object - adj.source = inspect.getsource(func) - - # get source code lines and line number where function starts - adj.raw_source, adj.fun_lineno = inspect.getsourcelines(func) - - # keep track of line number in function code - adj.lineno = None + # extract name of source file + adj.filename = inspect.getsourcefile(func) or "unknown source file" + # get source file line number where function starts + _, adj.fun_lineno = inspect.getsourcelines(func) + # get function source code + adj.source = inspect.getsource(func) # ensures that indented class methods can be parsed as kernels adj.source = textwrap.dedent(adj.source) - # extract name of source file - adj.filename = inspect.getsourcefile(func) or "unknown source file" - # build AST and apply node transformers adj.tree = ast.parse(adj.source) adj.transformers = transformers @@ -541,6 +536,9 @@ def __init__( adj.fun_name = adj.tree.body[0].name + # for keeping track of line number in function code + adj.lineno = None + # whether the forward code shall be used for the reverse pass and a custom # function signature is applied to the reverse version of the function adj.custom_reverse_mode = custom_reverse_mode @@ -2076,7 +2074,7 @@ def resolve_static_expression(adj, root_node, eval_types=True): def set_lineno(adj, lineno): if adj.lineno is None or adj.lineno != lineno: line = lineno + adj.fun_lineno - source = adj.raw_source[lineno].strip().ljust(80 - len(adj.indentation), " ") + source = adj.source.splitlines()[lineno].strip().ljust(80 - len(adj.indentation), " ") adj.add_forward(f"// {source} ") adj.add_reverse(f"// adj: {source} ") adj.lineno = lineno From af651ae72d2a22e1acbf06fc36adae083170e33d Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Fri, 8 Dec 2023 16:01:08 -0500 Subject: [PATCH 25/50] Cache line-splitted source code This is an optimization which eliminates multiple occurrences where the source code was being split into an array of lines. Note this doesn't add new storage overhead because the previous commit removed `adj.raw_source` which was the line-splitted undedented source. --- warp/codegen.py | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/warp/codegen.py b/warp/codegen.py index d70553458..87b9e3316 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -528,6 +528,8 @@ def __init__( # ensures that indented class methods can be parsed as kernels adj.source = textwrap.dedent(adj.source) + adj.source_lines = adj.source.splitlines() + # build AST and apply node transformers adj.tree = ast.parse(adj.source) adj.transformers = transformers @@ -623,7 +625,7 @@ def build(adj, builder): else: msg = "Error" lineno = adj.lineno + adj.fun_lineno - line = adj.source.splitlines()[adj.lineno] + line = adj.source_lines[adj.lineno] msg += f' while parsing function "{adj.fun_name}" at {adj.filename}:{lineno}:\n{line}\n' ex, data, traceback = sys.exc_info() e = ex(";".join([msg] + [str(a) for a in data.args])).with_traceback(traceback) @@ -1415,7 +1417,7 @@ def materialize_redefinitions(adj, symbols): if var1 != var2: if warp.config.verbose and not adj.custom_reverse_mode: lineno = adj.lineno + adj.fun_lineno - line = adj.source.splitlines()[adj.lineno] + line = adj.source_lines[adj.lineno] msg = f'Warning: detected mutated variable {sym} during a dynamic for-loop in function "{adj.fun_name}" at {adj.filename}:{lineno}: this may not be a differentiable operation.\n{line}\n' print(msg) @@ -1598,7 +1600,7 @@ def check_tid_in_func_error(adj, node): if adj.is_user_function: if hasattr(node.func, "attr") and node.func.attr == "tid": lineno = adj.lineno + adj.fun_lineno - line = adj.source.splitlines()[adj.lineno] + line = adj.source_lines[adj.lineno] raise WarpCodegenError( "tid() may only be called from a Warp kernel, not a Warp function. " "Instead, obtain the indices from a @wp.kernel and pass them as " @@ -1820,7 +1822,7 @@ def emit_Assign(adj, node): if warp.config.verbose and not adj.custom_reverse_mode: lineno = adj.lineno + adj.fun_lineno - line = adj.source.splitlines()[adj.lineno] + line = adj.source_lines[adj.lineno] node_source = adj.get_node_source(lhs.value) print( f"Warning: mutating {node_source} in function {adj.fun_name} at {adj.filename}:{lineno}: this is a non-differentiable operation.\n{line}\n" @@ -1877,7 +1879,7 @@ def emit_Assign(adj, node): if warp.config.verbose and not adj.custom_reverse_mode: lineno = adj.lineno + adj.fun_lineno - line = adj.source.splitlines()[adj.lineno] + line = adj.source_lines[adj.lineno] msg = f'Warning: detected mutated struct {attr.label} during function "{adj.fun_name}" at {adj.filename}:{lineno}: this is a non-differentiable operation.\n{line}\n' print(msg) @@ -2074,7 +2076,7 @@ def resolve_static_expression(adj, root_node, eval_types=True): def set_lineno(adj, lineno): if adj.lineno is None or adj.lineno != lineno: line = lineno + adj.fun_lineno - source = adj.source.splitlines()[lineno].strip().ljust(80 - len(adj.indentation), " ") + source = adj.source_lines[lineno].strip().ljust(80 - len(adj.indentation), " ") adj.add_forward(f"// {source} ") adj.add_reverse(f"// adj: {source} ") adj.lineno = lineno From f1128b89a0c015899fca0ecac92b76822449ab4a Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Wed, 13 Dec 2023 07:17:27 +1300 Subject: [PATCH 26/50] Bump omni.warp.core to version 1.0.0-beta.5 --- exts/omni.warp.core/config/extension.toml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/exts/omni.warp.core/config/extension.toml b/exts/omni.warp.core/config/extension.toml index 0a287a390..ec8d094d4 100644 --- a/exts/omni.warp.core/config/extension.toml +++ b/exts/omni.warp.core/config/extension.toml @@ -1,6 +1,6 @@ [package] # Semantic Versioning is used: https://semver.org/ -version = "1.0.0-beta.4" +version = "1.0.0-beta.5" authors = ["NVIDIA"] title = "Warp Core" description="The core Warp Python module" From ebee05d0d7b3a4e865ddf0ff2685e3f11784c1c2 Mon Sep 17 00:00:00 2001 From: Gilles Daviet Date: Tue, 12 Dec 2023 16:33:14 -0800 Subject: [PATCH 27/50] Address multiple differentiability issues --- warp/codegen.py | 26 ++++- warp/fem/cache.py | 3 +- warp/fem/field/nodal_field.py | 35 +++--- warp/fem/integrate.py | 72 ++++++++++-- warp/fem/space/shape/cube_shape_function.py | 42 ++++--- warp/fem/space/shape/square_shape_function.py | 47 +++++--- warp/tests/test_fem.py | 106 ++++++++++++++++++ warp/tests/test_grad.py | 51 +++++++++ 8 files changed, 317 insertions(+), 65 deletions(-) diff --git a/warp/codegen.py b/warp/codegen.py index 30ab0fdb4..f852f0b00 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -1295,6 +1295,12 @@ def vector_component_index(adj, component, vector_type): index = adj.add_constant(index) return index + @staticmethod + def is_differentiable_value_type(var_type): + # checks that the argument type is a value type (i.e, not an array) + # possibly holding differentiable values (for which gradients must be accumulated) + return type_scalar_type(var_type) in float_types or isinstance(var_type, Struct) + def emit_Attribute(adj, node): if hasattr(node, "is_adjoint"): node.value.is_adjoint = True @@ -1331,9 +1337,12 @@ def emit_Attribute(adj, node): if is_reference(aggregate.type): adj.add_forward(f"{attr.emit()} = &({aggregate.emit()}->{node.attr});") - adj.add_reverse(f"{aggregate.emit_adj()}.{node.attr} = {attr.emit_adj()};") else: adj.add_forward(f"{attr.emit()} = &({aggregate.emit()}.{node.attr});") + + if adj.is_differentiable_value_type(strip_reference(attr_type)): + adj.add_reverse(f"{aggregate.emit_adj()}.{node.attr} += {attr.emit_adj()};") + else: adj.add_reverse(f"{aggregate.emit_adj()}.{node.attr} = {attr.emit_adj()};") return attr @@ -1455,6 +1464,10 @@ def eval_num(adj, a): # try and resolve the expression to an object # e.g.: wp.constant in the globals scope obj, path = adj.resolve_static_expression(a) + + if isinstance(obj, Var) and obj.constant is not None: + obj = obj.constant + return warp.types.is_int(obj), obj # detects whether a loop contains a break (or continue) statement @@ -2135,7 +2148,9 @@ def get_node_source(adj, node): {{ }} - CUDA_CALLABLE {name}& operator += (const {name}&) {{ return *this; }} + CUDA_CALLABLE {name}& operator += (const {name}& rhs) + {{{prefix_add_body} + return *this;}} }}; @@ -2362,6 +2377,7 @@ def codegen_struct(struct, device="cpu", indent_size=4): forward_initializers = [] reverse_body = [] atomic_add_body = [] + prefix_add_body = [] # forward args for label, var in struct.vars.items(): @@ -2375,6 +2391,11 @@ def codegen_struct(struct, device="cpu", indent_size=4): prefix = f"{indent_block}," if forward_initializers else ":" forward_initializers.append(f"{indent_block}{prefix} {label}{{{label}}}\n") + # prefix-add operator + for label, var in struct.vars.items(): + if not is_array(var.type): + prefix_add_body.append(f"{indent_block}{label} += rhs.{label};\n") + # reverse args for label, var in struct.vars.items(): reverse_args.append(var.ctype() + " & adj_" + label) @@ -2392,6 +2413,7 @@ def codegen_struct(struct, device="cpu", indent_size=4): forward_initializers="".join(forward_initializers), reverse_args=indent(reverse_args), reverse_body="".join(reverse_body), + prefix_add_body="".join(prefix_add_body), atomic_add_body="".join(atomic_add_body), ) diff --git a/warp/fem/cache.py b/warp/fem/cache.py index 93faab52e..5345fc4dd 100644 --- a/warp/fem/cache.py +++ b/warp/fem/cache.py @@ -95,6 +95,7 @@ def wrap_struct(struct: type): def get_integrand_function( integrand: "warp.fem.operator.Integrand", suffix: str, + func=None, annotations=None, code_transformers=[], ): @@ -102,7 +103,7 @@ def get_integrand_function( if key not in _func_cache: _func_cache[key] = wp.Function( - func=integrand.func, + func=integrand.func if func is None else func, key=key, namespace="", module=integrand.module, diff --git a/warp/fem/field/nodal_field.py b/warp/fem/field/nodal_field.py index 2f657a2c1..ccec0da63 100644 --- a/warp/fem/field/nodal_field.py +++ b/warp/fem/field/nodal_field.py @@ -84,15 +84,14 @@ def _make_eval_grad_inner(self, world_space: bool): if not self.gradient_valid(): return None - @cache.dynamic_func(suffix=self.name + ("W" if world_space else "R")) - def eval_grad_inner(args: self.ElementEvalArg, s: Sample): + @cache.dynamic_func(suffix=self.name) + def eval_grad_inner_ref_space(args: self.ElementEvalArg, s: Sample): res = utils.generalized_outer( self._read_node_value(args, s.element_index, 0), self.space.element_inner_weight_gradient( args.elt_arg, args.eval_arg.space_arg, s.element_index, s.element_coords, 0 ), ) - for k in range(1, NODES_PER_ELEMENT): res += utils.generalized_outer( self._read_node_value(args, s.element_index, k), @@ -100,14 +99,15 @@ def eval_grad_inner(args: self.ElementEvalArg, s: Sample): args.elt_arg, args.eval_arg.space_arg, s.element_index, s.element_coords, k ), ) - - if world_space: - grad_transform = self.space.element_inner_reference_gradient_transform(args.elt_arg, s) - return utils.apply_right(res, grad_transform) - return res - return eval_grad_inner + @cache.dynamic_func(suffix=self.name) + def eval_grad_inner_world_space(args: self.ElementEvalArg, s: Sample): + grad_transform = self.space.element_inner_reference_gradient_transform(args.elt_arg, s) + res = eval_grad_inner_ref_space(args, s) + return utils.apply_right(res, grad_transform) + + return eval_grad_inner_world_space if world_space else eval_grad_inner_ref_space def _make_eval_div_inner(self): NODES_PER_ELEMENT = self.space.topology.NODES_PER_ELEMENT @@ -173,8 +173,8 @@ def _make_eval_grad_outer(self, world_space: bool): if not self.gradient_valid(): return None - @cache.dynamic_func(suffix=self.name + ("W" if world_space else "R")) - def eval_grad_outer(args: self.ElementEvalArg, s: Sample): + @cache.dynamic_func(suffix=self.name) + def eval_grad_outer_ref_space(args: self.ElementEvalArg, s: Sample): res = utils.generalized_outer( self._read_node_value(args, s.element_index, 0), self.space.element_outer_weight_gradient( @@ -188,14 +188,15 @@ def eval_grad_outer(args: self.ElementEvalArg, s: Sample): args.elt_arg, args.eval_arg.space_arg, s.element_index, s.element_coords, k ), ) - - if world_space: - grad_transform = self.space.element_outer_reference_gradient_transform(args.elt_arg, s) - return utils.apply_right(res, grad_transform) - return res - return eval_grad_outer + @cache.dynamic_func(suffix=self.name) + def eval_grad_outer_world_space(args: self.ElementEvalArg, s: Sample): + grad_transform = self.space.element_outer_reference_gradient_transform(args.elt_arg, s) + res = eval_grad_outer_ref_space(args, s) + return utils.apply_right(res, grad_transform) + + return eval_grad_outer_world_space if world_space else eval_grad_outer_ref_space def _make_eval_div_outer(self): NODES_PER_ELEMENT = self.space.topology.NODES_PER_ELEMENT diff --git a/warp/fem/integrate.py b/warp/fem/integrate.py index 0230aa663..ebee7db93 100644 --- a/warp/fem/integrate.py +++ b/warp/fem/integrate.py @@ -619,7 +619,7 @@ def integrate_kernel_fn( test_element_index.node_index_in_element, test_dof, ) - + val_sum = accumulate_dtype(0.0) for k in range(qp_point_count): @@ -1012,7 +1012,7 @@ def as_2d_array(array): ) if output_temporary is not None: - return output_temporary.detach() + return output_temporary.detach() return output @@ -1108,7 +1108,7 @@ def as_2d_array(array): block_type=block_type, device=device, ) - + bsr_set_from_triplets(output, triplet_rows, triplet_cols, triplet_values) # Do not wait for garbage collection @@ -1230,7 +1230,7 @@ def integrate( ) -def get_interpolate_to_field_kernel( +def get_interpolate_to_field_function( integrand_func: wp.Function, domain: GeometryDomain, FieldStruct: wp.codegen.Struct, @@ -1239,7 +1239,8 @@ def get_interpolate_to_field_kernel( ): value_type = dest.space.dtype - def interpolate_to_field_kernel_fn( + def interpolate_to_field_fn( + local_node_index: int, domain_arg: domain.ElementArg, domain_index_arg: domain.ElementIndexArg, dest_node_arg: dest.space_restriction.NodeArg, @@ -1247,19 +1248,15 @@ def interpolate_to_field_kernel_fn( fields: FieldStruct, values: ValueStruct, ): - local_node_index = wp.tid() node_index = dest.space_restriction.node_partition_index(dest_node_arg, local_node_index) - element_count = dest.space_restriction.node_element_count(dest_node_arg, local_node_index) - if element_count == 0: - return test_dof_index = NULL_DOF_INDEX trial_dof_index = NULL_DOF_INDEX node_weight = 1.0 - # Volume-weighted average accross elements - # Superfluous if the function is continuous, but we might as well + # Volume-weighted average across elements + # Superfluous if the interpolated function is continuous, but helpful for visualizing discontinuous spaces val_sum = value_type(0.0) vol_sum = float(0.0) @@ -1290,7 +1287,34 @@ def interpolate_to_field_kernel_fn( vol_sum += vol val_sum += vol * val + return val_sum, vol_sum + + return interpolate_to_field_fn + + +def get_interpolate_to_field_kernel( + interpolate_to_field_fn: wp.Function, + domain: GeometryDomain, + FieldStruct: wp.codegen.Struct, + ValueStruct: wp.codegen.Struct, + dest: FieldRestriction, +): + def interpolate_to_field_kernel_fn( + domain_arg: domain.ElementArg, + domain_index_arg: domain.ElementIndexArg, + dest_node_arg: dest.space_restriction.NodeArg, + dest_eval_arg: dest.field.EvalArg, + fields: FieldStruct, + values: ValueStruct, + ): + local_node_index = wp.tid() + + val_sum, vol_sum = interpolate_to_field_fn( + local_node_index, domain_arg, domain_index_arg, dest_node_arg, dest_eval_arg, fields, values + ) + if vol_sum > 0.0: + node_index = dest.space_restriction.node_partition_index(dest_node_arg, local_node_index) dest.field.set_node_value(dest_eval_arg, node_index, val_sum / vol_sum) return interpolate_to_field_kernel_fn @@ -1404,13 +1428,37 @@ def _generate_interpolate_kernel( # Generate interpolation kernel if isinstance(dest, FieldRestriction): - interpolate_kernel_fn = get_interpolate_to_field_kernel( + # need to split into kernel + function for diffferentiability + interpolate_fn = get_interpolate_to_field_function( integrand_func, domain, dest=dest, FieldStruct=FieldStruct, ValueStruct=ValueStruct, ) + + interpolate_fn = cache.get_integrand_function( + integrand=integrand, + func=interpolate_fn, + suffix=kernel_suffix, + code_transformers=[ + PassFieldArgsToIntegrand( + arg_names=integrand.argspec.args, + field_args=field_args.keys(), + value_args=value_args.keys(), + sample_name=sample_name, + domain_name=domain_name, + ) + ], + ) + + interpolate_kernel_fn = get_interpolate_to_field_kernel( + interpolate_fn, + domain, + dest=dest, + FieldStruct=FieldStruct, + ValueStruct=ValueStruct, + ) elif wp.types.is_array(dest): interpolate_kernel_fn = get_interpolate_to_array_kernel( integrand_func, diff --git a/warp/fem/space/shape/cube_shape_function.py b/warp/fem/space/shape/cube_shape_function.py index bc16edcbe..91e7b6f62 100644 --- a/warp/fem/space/shape/cube_shape_function.py +++ b/warp/fem/space/shape/cube_shape_function.py @@ -41,6 +41,7 @@ def __init__(self, degree: int, family: Polynomial): self.LOBATTO_COORDS = wp.constant(NodeVec(lobatto_coords)) self.LOBATTO_WEIGHT = wp.constant(NodeVec(lobatto_weight)) self.LAGRANGE_SCALE = wp.constant(NodeVec(lagrange_scale)) + self.ORDER_PLUS_ONE = wp.constant(self.ORDER + 1) self._node_ijk = self._make_node_ijk() self.node_type_and_type_index = self._make_node_type_and_type_index() @@ -57,21 +58,21 @@ def _vertex_coords_f(vidx_in_cell: int): return wp.vec3(float(x), float(y), float(z)) def _make_node_ijk(self): - ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE def node_ijk( node_index_in_elt: int, ): - node_i = node_index_in_elt // ((ORDER + 1) * (ORDER + 1)) - node_jk = node_index_in_elt - (ORDER + 1) * (ORDER + 1) * node_i - node_j = node_jk // (ORDER + 1) - node_k = node_jk - (ORDER + 1) * node_j + node_i = node_index_in_elt // (ORDER_PLUS_ONE * ORDER_PLUS_ONE) + node_jk = node_index_in_elt - ORDER_PLUS_ONE * ORDER_PLUS_ONE * node_i + node_j = node_jk // ORDER_PLUS_ONE + node_k = node_jk - ORDER_PLUS_ONE * node_j return node_i, node_j, node_k return cache.get_func(node_ijk, self.name) def _make_node_type_and_type_index(self): - ORDER = wp.constant(self.ORDER) + ORDER = self.ORDER @cache.dynamic_func(suffix=self.name) def node_type_and_type_index( @@ -190,13 +191,21 @@ def trace_node_quadrature_weight_linear( ): return 0.25 + def trace_node_quadrature_weight_open( + node_index_in_elt: int, + ): + return 0.0 + + if not is_closed(self.family): + return cache.get_func(trace_node_quadrature_weight_open, self.name) + if ORDER == 1: return cache.get_func(trace_node_quadrature_weight_linear, self.name) return cache.get_func(trace_node_quadrature_weight, self.name) def make_element_inner_weight(self): - ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -207,7 +216,7 @@ def element_inner_weight( node_i, node_j, node_k = self._node_ijk(node_index_in_elt) w = float(1.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: w *= coords[0] - LOBATTO_COORDS[k] if k != node_j: @@ -230,13 +239,13 @@ def element_inner_weight_linear( wz = (1.0 - coords[2]) * (1.0 - v[2]) + v[2] * coords[2] return wx * wy * wz - if ORDER == 1: + if self.ORDER == 1 and is_closed(self.family): return cache.get_func(element_inner_weight_linear, self.name) return cache.get_func(element_inner_weight, self.name) def make_element_inner_weight_gradient(self): - ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -249,7 +258,7 @@ def element_inner_weight_gradient( prefix_xy = float(1.0) prefix_yz = float(1.0) prefix_zx = float(1.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: prefix_yz *= coords[0] - LOBATTO_COORDS[k] if k != node_j: @@ -265,7 +274,7 @@ def element_inner_weight_gradient( grad_y = float(0.0) grad_z = float(0.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: delta_x = coords[0] - LOBATTO_COORDS[k] grad_x = grad_x * delta_x + prefix_x @@ -308,7 +317,7 @@ def element_inner_weight_gradient_linear( return wp.vec3(dx * wy * wz, dy * wz * wx, dz * wx * wy) - if ORDER == 1: + if self.ORDER == 1 and is_closed(self.family): return cache.get_func(element_inner_weight_gradient_linear, self.name) return cache.get_func(element_inner_weight_gradient, self.name) @@ -356,6 +365,7 @@ def __init__(self, degree: int, family: Polynomial): self.LOBATTO_COORDS = wp.constant(NodeVec(lobatto_coords)) self.LOBATTO_WEIGHT = wp.constant(NodeVec(lobatto_weight)) self.LAGRANGE_SCALE = wp.constant(NodeVec(lagrange_scale)) + self.ORDER_PLUS_ONE = wp.constant(self.ORDER + 1) self.node_type_and_type_index = self._get_node_type_and_type_index() self._node_lobatto_indices = self._get_node_lobatto_indices() @@ -466,6 +476,7 @@ def trace_node_quadrature_weight( def make_element_inner_weight(self): ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -511,7 +522,7 @@ def element_inner_weight( w *= wp.select(node_all[1] == 0, local_coords[1], 1.0 - local_coords[1]) w *= wp.select(node_all[2] == 0, local_coords[2], 1.0 - local_coords[2]) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_all[0]: w *= local_coords[0] - LOBATTO_COORDS[k] w *= LAGRANGE_SCALE[node_all[0]] @@ -522,6 +533,7 @@ def element_inner_weight( def make_element_inner_weight_gradient(self): ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -585,7 +597,7 @@ def element_inner_weight_gradient( w_alt = LAGRANGE_SCALE[node_all[0]] g_alt = float(0.0) prefix_alt = LAGRANGE_SCALE[node_all[0]] - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_all[0]: delta_alt = local_coords[0] - LOBATTO_COORDS[k] w_alt *= delta_alt diff --git a/warp/fem/space/shape/square_shape_function.py b/warp/fem/space/shape/square_shape_function.py index ba205ceb7..0cf680f0c 100644 --- a/warp/fem/space/shape/square_shape_function.py +++ b/warp/fem/space/shape/square_shape_function.py @@ -25,6 +25,7 @@ def __init__(self, degree: int, family: Polynomial): self.LOBATTO_COORDS = wp.constant(NodeVec(lobatto_coords)) self.LOBATTO_WEIGHT = wp.constant(NodeVec(lobatto_weight)) self.LAGRANGE_SCALE = wp.constant(NodeVec(lagrange_scale)) + self.ORDER_PLUS_ONE = wp.constant(self.ORDER + 1) @property def name(self) -> str: @@ -93,13 +94,21 @@ def trace_node_quadrature_weight_linear( ): return 0.5 + def trace_node_quadrature_weight_open( + node_index_in_elt: int, + ): + return 0.0 + + if not is_closed(self.family): + return cache.get_func(trace_node_quadrature_weight_open, self.name) + if ORDER == 1: return cache.get_func(trace_node_quadrature_weight_linear, self.name) return cache.get_func(trace_node_quadrature_weight, self.name) def make_element_inner_weight(self): - ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -107,11 +116,11 @@ def element_inner_weight( coords: Coords, node_index_in_elt: int, ): - node_i = node_index_in_elt // (ORDER + 1) - node_j = node_index_in_elt - (ORDER + 1) * node_i + node_i = node_index_in_elt // ORDER_PLUS_ONE + node_j = node_index_in_elt - ORDER_PLUS_ONE * node_i w = float(1.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: w *= coords[0] - LOBATTO_COORDS[k] if k != node_j: @@ -131,13 +140,13 @@ def element_inner_weight_linear( wy = (1.0 - coords[1]) * (1.0 - v[1]) + v[1] * coords[1] return wx * wy - if ORDER == 1: + if self.ORDER == 1 and is_closed(self.family): return cache.get_func(element_inner_weight_linear, self.name) return cache.get_func(element_inner_weight, self.name) def make_element_inner_weight_gradient(self): - ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -145,12 +154,12 @@ def element_inner_weight_gradient( coords: Coords, node_index_in_elt: int, ): - node_i = node_index_in_elt // (ORDER + 1) - node_j = node_index_in_elt - (ORDER + 1) * node_i + node_i = node_index_in_elt // ORDER_PLUS_ONE + node_j = node_index_in_elt - ORDER_PLUS_ONE * node_i prefix_x = float(1.0) prefix_y = float(1.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: prefix_y *= coords[0] - LOBATTO_COORDS[k] if k != node_j: @@ -159,7 +168,7 @@ def element_inner_weight_gradient( grad_x = float(0.0) grad_y = float(0.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: delta_x = coords[0] - LOBATTO_COORDS[k] grad_x = grad_x * delta_x + prefix_x @@ -187,7 +196,7 @@ def element_inner_weight_gradient_linear( return wp.vec2(dx * wy, dy * wx) - if ORDER == 1: + if self.ORDER == 1 and is_closed(self.family): return cache.get_func(element_inner_weight_gradient_linear, self.name) return cache.get_func(element_inner_weight_gradient, self.name) @@ -230,6 +239,7 @@ def __init__(self, degree: int, family: Polynomial): self.LOBATTO_COORDS = wp.constant(NodeVec(lobatto_coords)) self.LOBATTO_WEIGHT = wp.constant(NodeVec(lobatto_weight)) self.LAGRANGE_SCALE = wp.constant(NodeVec(lagrange_scale)) + self.ORDER_PLUS_ONE = wp.constant(self.ORDER + 1) self.node_type_and_type_index = self._get_node_type_and_type_index() self._node_lobatto_indices = self._get_node_lobatto_indices() @@ -328,6 +338,7 @@ def trace_node_quadrature_weight( def make_element_inner_weight(self): ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -361,7 +372,7 @@ def element_inner_weight( if node_type == SquareSerendipityShapeFunctions.EDGE_Y: w *= wp.select(node_i == 0, coords[0], 1.0 - coords[0]) else: - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: w *= coords[0] - LOBATTO_COORDS[k] @@ -370,7 +381,7 @@ def element_inner_weight( if node_type == SquareSerendipityShapeFunctions.EDGE_X: w *= wp.select(node_j == 0, coords[1], 1.0 - coords[1]) else: - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_j: w *= coords[1] - LOBATTO_COORDS[k] w *= LAGRANGE_SCALE[node_j] @@ -381,6 +392,7 @@ def element_inner_weight( def make_element_inner_weight_gradient(self): ORDER = self.ORDER + ORDER_PLUS_ONE = self.ORDER_PLUS_ONE LOBATTO_COORDS = self.LOBATTO_COORDS LAGRANGE_SCALE = self.LAGRANGE_SCALE @@ -424,7 +436,7 @@ def element_inner_weight_gradient( prefix_x = wp.select(node_j == 0, coords[1], 1.0 - coords[1]) else: prefix_x = LAGRANGE_SCALE[node_j] - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_j: prefix_x *= coords[1] - LOBATTO_COORDS[k] @@ -432,7 +444,7 @@ def element_inner_weight_gradient( prefix_y = wp.select(node_i == 0, coords[0], 1.0 - coords[0]) else: prefix_y = LAGRANGE_SCALE[node_i] - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: prefix_y *= coords[0] - LOBATTO_COORDS[k] @@ -441,7 +453,7 @@ def element_inner_weight_gradient( else: prefix_y *= LAGRANGE_SCALE[node_j] grad_y = float(0.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_j: delta_y = coords[1] - LOBATTO_COORDS[k] grad_y = grad_y * delta_y + prefix_y @@ -452,7 +464,7 @@ def element_inner_weight_gradient( else: prefix_x *= LAGRANGE_SCALE[node_i] grad_x = float(0.0) - for k in range(ORDER + 1): + for k in range(ORDER_PLUS_ONE): if k != node_i: delta_x = coords[0] - LOBATTO_COORDS[k] grad_x = grad_x * delta_x + prefix_x @@ -530,7 +542,6 @@ def make_node_quadrature_weight(self): NODES_PER_ELEMENT = self.NODES_PER_ELEMENT if self.ORDER == 2: - # Intrinsic quadrature (order 2) @cache.dynamic_func(suffix=self.name) def node_quadrature_weight_quadratic( diff --git a/warp/tests/test_fem.py b/warp/tests/test_fem.py index 70a6da628..36f5fb110 100644 --- a/warp/tests/test_fem.py +++ b/warp/tests/test_fem.py @@ -63,6 +63,89 @@ def test_integrate_gradient(test_case, device): test_case.assertLess(err, 1.0e-8) +@fem.integrand +def bilinear_field(s: fem.Sample, domain: fem.Domain): + x = domain(s) + return x[0] * x[1] + + +@fem.integrand +def grad_field(s: fem.Sample, p: fem.Field): + return fem.grad(p, s) + + +def test_interpolate_gradient(test_case, device): + with wp.ScopedDevice(device): + # Quad mesh with single element + # so we can test gradient with respect to vertex positions + positions = wp.array([[0.0, 0.0], [0.0, 2.0], [2.0, 0.0], [2.0, 2.0]], dtype=wp.vec2, requires_grad=True) + quads = wp.array([[0, 2, 3, 1]], dtype=int) + geo = fem.Quadmesh2D(quads, positions) + + # Quadratic scalar space + scalar_space = fem.make_polynomial_space(geo, degree=2) + + # Point-based vector space + # So we can test gradient with respect to inteprolation point position + point_coords = wp.array([[[0.5, 0.5, 0.0]]], dtype=fem.Coords, requires_grad=True) + interpolation_nodes = fem.PointBasisSpace( + fem.ExplicitQuadrature(domain=fem.Cells(geo), points=point_coords, weights=wp.array([[1.0]], dtype=float)) + ) + vector_space = fem.make_collocated_function_space(interpolation_nodes, dtype=wp.vec2) + + # Initialize scalar field with known function + scalar_field = scalar_space.make_field() + scalar_field.dof_values.requires_grad = True + fem.interpolate(bilinear_field, dest=scalar_field) + + # Interpolate gradient at center point + vector_field = vector_space.make_field() + vector_field.dof_values.requires_grad = True + tape = wp.Tape() + with tape: + fem.interpolate(grad_field, dest=vector_field, fields={"p": scalar_field}) + + assert_np_equal(vector_field.dof_values.numpy(), np.array([[1.0, 1.0]])) + + vector_field.dof_values.grad.assign([1.0, 0.0]) + tape.backward() + + assert_np_equal(scalar_field.dof_values.grad.numpy(), np.array([0.0, 0.0, 0.0, 0.0, 0.0, -0.5, 0.0, 0.5, 0.0])) + assert_np_equal( + geo.positions.grad.numpy(), + np.array( + [ + [0.25, 0.25], + [0.25, 0.25], + [-0.25, -0.25], + [-0.25, -0.25], + ] + ), + ) + assert_np_equal(point_coords.grad.numpy(), np.array([[[0.0, 2.0, 0.0]]])) + + tape.zero() + scalar_field.dof_values.grad.zero_() + geo.positions.grad.zero_() + point_coords.grad.zero_() + + vector_field.dof_values.grad.assign([0.0, 1.0]) + tape.backward() + + assert_np_equal(scalar_field.dof_values.grad.numpy(), np.array([0.0, 0.0, 0.0, 0.0, -0.5, 0.0, 0.5, 0.0, 0.0])) + assert_np_equal( + geo.positions.grad.numpy(), + np.array( + [ + [0.25, 0.25], + [-0.25, -0.25], + [0.25, 0.25], + [-0.25, -0.25], + ] + ), + ) + assert_np_equal(point_coords.grad.numpy(), np.array([[[2.0, 0.0, 0.0]]])) + @integrand def vector_divergence_form(s: Sample, u: Field, q: Field): return div(u, s) * q(s) @@ -889,6 +972,17 @@ def square_coord_delta_sampler(epsilon: float, state: wp.uint32): test_shape_function_gradient(test_case, Q_2, square_coord_sampler, square_coord_delta_sampler) test_shape_function_gradient(test_case, Q_3, square_coord_sampler, square_coord_delta_sampler) + Q_1 = shape.SquareBipolynomialShapeFunctions(degree=1, family=fem.Polynomial.GAUSS_LEGENDRE) + Q_2 = shape.SquareBipolynomialShapeFunctions(degree=2, family=fem.Polynomial.GAUSS_LEGENDRE) + Q_3 = shape.SquareBipolynomialShapeFunctions(degree=3, family=fem.Polynomial.GAUSS_LEGENDRE) + + test_shape_function_weight(test_case, Q_1, square_coord_sampler, SQUARE_CENTER_COORDS) + test_shape_function_weight(test_case, Q_2, square_coord_sampler, SQUARE_CENTER_COORDS) + test_shape_function_weight(test_case, Q_3, square_coord_sampler, SQUARE_CENTER_COORDS) + test_shape_function_gradient(test_case, Q_1, square_coord_sampler, square_coord_delta_sampler) + test_shape_function_gradient(test_case, Q_2, square_coord_sampler, square_coord_delta_sampler) + test_shape_function_gradient(test_case, Q_3, square_coord_sampler, square_coord_delta_sampler) + S_2 = shape.SquareSerendipityShapeFunctions(degree=2, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) S_3 = shape.SquareSerendipityShapeFunctions(degree=3, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) @@ -940,6 +1034,17 @@ def cube_coord_delta_sampler(epsilon: float, state: wp.uint32): test_shape_function_gradient(test_case, Q_2, cube_coord_sampler, cube_coord_delta_sampler) test_shape_function_gradient(test_case, Q_3, cube_coord_sampler, cube_coord_delta_sampler) + Q_1 = shape.CubeTripolynomialShapeFunctions(degree=1, family=fem.Polynomial.GAUSS_LEGENDRE) + Q_2 = shape.CubeTripolynomialShapeFunctions(degree=2, family=fem.Polynomial.GAUSS_LEGENDRE) + Q_3 = shape.CubeTripolynomialShapeFunctions(degree=3, family=fem.Polynomial.GAUSS_LEGENDRE) + + test_shape_function_weight(test_case, Q_1, cube_coord_sampler, CUBE_CENTER_COORDS) + test_shape_function_weight(test_case, Q_2, cube_coord_sampler, CUBE_CENTER_COORDS) + test_shape_function_weight(test_case, Q_3, cube_coord_sampler, CUBE_CENTER_COORDS) + test_shape_function_gradient(test_case, Q_1, cube_coord_sampler, cube_coord_delta_sampler) + test_shape_function_gradient(test_case, Q_2, cube_coord_sampler, cube_coord_delta_sampler) + test_shape_function_gradient(test_case, Q_3, cube_coord_sampler, cube_coord_delta_sampler) + S_2 = shape.CubeSerendipityShapeFunctions(degree=2, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) S_3 = shape.CubeSerendipityShapeFunctions(degree=3, family=fem.Polynomial.LOBATTO_GAUSS_LEGENDRE) @@ -1135,6 +1240,7 @@ class TestFem(parent): add_function_test(TestFem, "test_closest_point_queries", test_closest_point_queries) add_function_test(TestFem, "test_grad_decomposition", test_grad_decomposition, devices=devices) add_function_test(TestFem, "test_integrate_gradient", test_integrate_gradient, devices=devices) + add_function_test(TestFem, "test_interpolate_gradient", test_interpolate_gradient, devices=devices) add_function_test(TestFem, "test_vector_divergence_theorem", test_vector_divergence_theorem, devices=devices) add_function_test(TestFem, "test_tensor_divergence_theorem", test_tensor_divergence_theorem, devices=devices) add_function_test(TestFem, "test_grid_2d", test_grid_2d, devices=devices) diff --git a/warp/tests/test_grad.py b/warp/tests/test_grad.py index 6e15c748f..d8ed5d062 100644 --- a/warp/tests/test_grad.py +++ b/warp/tests/test_grad.py @@ -6,6 +6,7 @@ # license agreement from NVIDIA CORPORATION is strictly prohibited. import unittest +from typing import Any import numpy as np @@ -560,6 +561,55 @@ def test_name_clash(test, device): assert_np_equal(input_b.grad.numpy(), np.array([1.0, 1.0, 0.0])) +@wp.struct +class NestedStruct: + v: wp.vec2 + + +@wp.struct +class ParentStruct: + a: float + n: NestedStruct + + +@wp.func +def noop(a: Any): + pass + + +@wp.func +def sum2(v: wp.vec2): + return v[0] + v[1] + + +@wp.kernel +def test_struct_attribute_gradient_kernel(src: wp.array(dtype=float), res: wp.array(dtype=float)): + tid = wp.tid() + + p = ParentStruct(src[tid], NestedStruct(wp.vec2(2.0 * src[tid]))) + + # test that we are not losing gradients when accessing attributes + noop(p.a) + noop(p.n) + noop(p.n.v) + + res[tid] = p.a + sum2(p.n.v) + + +def test_struct_attribute_gradient(test_case, device): + src = wp.array([1], dtype=float, requires_grad=True) + res = wp.empty_like(src) + + tape = wp.Tape() + with tape: + wp.launch(test_struct_attribute_gradient_kernel, dim=1, inputs=[src, res]) + + res.grad.fill_(1.0) + tape.backward() + + test_case.assertEqual(src.grad.numpy()[0], 5.0) + + def register(parent): devices = get_test_devices() @@ -579,6 +629,7 @@ class TestGrad(parent): add_function_test(TestGrad, "test_multi_valued_function_grad", test_multi_valued_function_grad, devices=devices) add_function_test(TestGrad, "test_mesh_grad", test_mesh_grad, devices=devices) add_function_test(TestGrad, "test_name_clash", test_name_clash, devices=devices) + add_function_test(TestGrad, "test_struct_attribute_gradient", test_struct_attribute_gradient, devices=devices) return TestGrad From f6fb39684d0176b910315e27044ffde49fc6a2c8 Mon Sep 17 00:00:00 2001 From: Eric Shi Date: Tue, 12 Dec 2023 16:42:38 -0800 Subject: [PATCH 28/50] Add github-linguist exclusions for accurate language breakdown --- .gitattributes | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/.gitattributes b/.gitattributes index b495b445b..c3c477560 100644 --- a/.gitattributes +++ b/.gitattributes @@ -13,3 +13,7 @@ *.grid filter=lfs diff=lfs merge=lfs -text *.nvdb filter=lfs diff=lfs merge=lfs -text *.gif filter=lfs diff=lfs merge=lfs -text + +# Exclude vendored code from project language stats +warp/native/cutlass/** linguist-vendored +tools/** linguist-vendored From 0a5c46a48b65bf71d3c53ce2409d0a5d3fd88c0a Mon Sep 17 00:00:00 2001 From: Eric Shi Date: Tue, 12 Dec 2023 16:43:02 -0800 Subject: [PATCH 29/50] Make clear when tid() breaking change happened in CHANGELOG --- CHANGELOG.md | 42 +++++++++++++++++------------------------- 1 file changed, 17 insertions(+), 25 deletions(-) diff --git a/CHANGELOG.md b/CHANGELOG.md index c452e8f7f..d98de5de3 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -5,15 +5,15 @@ - Fix for kernel caching when function argument types change - Fix code-gen ordering of dependent structs - Fix for `wp.Mesh` build on MGPU systems -- Fix for name clash bug with adjoint code: https://github.com/NVIDIA/warp/issues/154 +- Fix for name clash bug with adjoint code: https://github.com/NVIDIA/warp/issues/154 - Add `wp.frac()` for returning the fractional part of a floating point value - Add support for custom native CUDA snippets using `@wp.func_native` decorator - Add support for batched matmul with batch size > 2^16-1 -- Add support for tranposed CUTLASS `wp.matmul()` and additional error checking +- Add support for transposed CUTLASS `wp.matmul()` and additional error checking - Add support for quad and hex meshes in `wp.fem` -- Detect and warn when C++ runtime doesn't match compiler during build, e.g.: libstdc++.so.6: version `GLIBCXX_3.4.30' not found +- Detect and warn when C++ runtime doesn't match compiler during build, e.g.: ``libstdc++.so.6: version `GLIBCXX_3.4.30' not found`` - Documentation update for `wp.BVH` -- Documentaiton and simplified API for runtime kernel specialization `wp.Kernel` +- Documentation and simplified API for runtime kernel specialization `wp.Kernel` ## [1.0.0-beta.4] - 2023-11-01 @@ -43,7 +43,11 @@ - Fix for `wp.func` to return a default value if function does not return on all control paths - Refactor `wp.fem` support for new basis functions, decoupled function spaces - Optimizations for `wp.noise` functions, up to 10x faster in most cases -- Optimizations for `type_size_in_bytes()` used in array construction +- Optimizations for `type_size_in_bytes()` used in array construction' + +### Breaking Changes + +- To support grid-stride kernels, `wp.tid()` can no longer be called inside `wp.func` functions. ## [1.0.0-beta.2] - 2023-09-01 @@ -181,7 +185,7 @@ ## [0.8.1] - 2023-04-13 - Fix for regression when passing flattened numeric lists as matrix arguments to kernels -- Fix for regressions when passing wp.struct types with uninitialized (None) member attributes +- Fix for regressions when passing `wp.struct` types with uninitialized (`None`) member attributes ## [0.8.0] - 2023-04-05 @@ -215,20 +219,18 @@ - Optimizations for `wp.launch()`, up to 3x faster launches in common cases - Fix `wp.randf()` conversion to float to reduce bias for uniform sampling - Fix capture of `wp.func` and `wp.constant` types from inside Python closures -- Fix for CUDA on WSL +- Fix for CUDA on WSL - Fix for matrices in structs - Fix for transpose indexing for some non-square matrices - Enable Python faulthandler by default - Update to VS2019 -Breaking Changes ----------------- +### Breaking Changes - `wp.constant` variables can now be treated as their true type, accessing the underlying value through `constant.val` is no longer supported - `wp.sim.model.ground_plane` is now a `wp.array` to support gradient, users should call `builder.set_ground_plane()` to create the ground - `wp.sim` capsule, cones, and cylinders are now aligned with the default USD up-axis - ## [0.7.2] - 2023-02-15 - Reduce test time for vec/math types @@ -248,9 +250,9 @@ Breaking Changes - Add support for slicing `wp.array` types in Python - Add `wp.from_ptr()` helper to construct arrays from an existing allocation - Add support for `break` statements in ranged-for and while loops (backward pass support currently not implemented) -- Add built-in mathematic constants, see `wp.pi`, `wp.e`, `wp.log2e`, etc +- Add built-in mathematic constants, see `wp.pi`, `wp.e`, `wp.log2e`, etc. - Add built-in conversion between degrees and radians, see `wp.degrees()`, `wp.radians()` -- Add security pop-up for Kernel Node +- Add security pop-up for Kernel Node - Improve error handling for kernel return values ## [0.6.3] - 2023-01-31 @@ -336,7 +338,7 @@ Breaking Changes - Fix for hashing of `wp.constants()` not invalidating kernels - Fix for reload when multiple `.ptx` versions are present - Improved error reporting during code-gen - + ## [0.4.3] - 2022-09-20 - Update all samples to use GPU interop path by default @@ -360,7 +362,6 @@ Breaking Changes - Fix for debug flags not being set correctly on CUDA when `wp.config.mode == "debug"`, this enables bounds checking on CUDA kernels in debug mode - Fix for code gen of functions that do not return a value - ## [0.4.0] - 2022-08-09 - Fix for FP16 conversions on GPUs without hardware support @@ -373,18 +374,15 @@ Breaking Changes - Add support for cross-module `@wp.struct` references - Support running even if CUDA initialization failed, use `wp.is_cuda_available()` to check availability - Statically linking with the CUDA runtime library to avoid deployment issues - ### Breaking Changes - Removed `wp.runtime` reference from the top-level module, as it should be considered private - ## [0.3.2] - 2022-07-19 - Remove Torch import from `__init__.py`, defer import to `wp.from_torch()`, `wp.to_torch()` - ## [0.3.1] - 2022-07-12 - Fix for marching cubes reallocation after initialization @@ -396,7 +394,6 @@ Breaking Changes - Add support for using arbitrary external CUDA contexts, see `wp.map_cuda_device()`, `wp.unmap_cuda_device()` - Add PyTorch device aliasing functions, see `wp.device_from_torch()`, `wp.device_to_torch()` - ### Breaking Changes - A CUDA device is used by default, if available (aligned with `wp.get_preferred_device()`) @@ -404,7 +401,6 @@ Breaking Changes - `wp.synchronize()` now synchronizes all devices; for finer-grained control, use `wp.synchronize_device()` - Device alias `"cuda"` now refers to the current CUDA context, rather than a specific device like `"cuda:0"` or `"cuda:1"` - ## [0.3.0] - 2022-07-08 - Add support for FP16 storage type, see `wp.float16` @@ -429,7 +425,6 @@ Breaking Changes - Fix for reload of generated CPU kernel code on Linux - Fix for example scripts to output USD at 60 timecodes per-second (better Kit compatibility) - ## [0.2.3] - 2022-06-13 - Fix for incorrect 4d array bounds checking @@ -438,7 +433,6 @@ Breaking Changes - Array gradients are now allocated along with the arrays and accessible as `wp.array.grad`, users should take care to always call `wp.Tape.zero()` to clear gradients between different invocations of `wp.Tape.backward()` - Added `wp.array.fill_()` to set all entries to a scalar value (4-byte values only currently) - ### Breaking Changes - Tape `capture` option has been removed, users can now capture tapes inside existing CUDA graphs (e.g.: inside Torch) @@ -471,7 +465,7 @@ Breaking Changes ## [0.2.1] - 2022-05-11 - Fix for unit tests in Kit -- + ## [0.2.0] - 2022-05-02 ### Warp Core @@ -509,7 +503,7 @@ Breaking Changes - Fix for URDF importer and floating base support - Add examples showing how to use differentiable forward kinematics to solve inverse kinematics - Add examples for URDF cartpole and quadruped simulation - + ### Breaking Changes - `wp.volume_sample_world()` is now replaced by `wp.volume_sample_f/i/vec()` which operate in index (local) space. Users should use `wp.volume_world_to_index()` to transform points from world space to index space before sampling. @@ -517,7 +511,6 @@ Breaking Changes - `wp.array.length` member has been removed, please use `wp.array.shape` to access array dimensions, or use `wp.array.size` to get total element count - Marking `dense_gemm()`, `dense_chol()`, etc methods as experimental until we revisit them - ## [0.1.25] - 2022-03-20 - Add support for class methods to be Warp kernels @@ -528,7 +521,6 @@ Breaking Changes - Add support for floored division on integer types - Move tests into core library so they can be run in Kit environment - ## [0.1.24] - 2022-03-03 ### Warp Core From 5e305f837348034df2c1a7fb1959644da3d26d86 Mon Sep 17 00:00:00 2001 From: Eric Heiden Date: Tue, 12 Dec 2023 16:47:42 -0800 Subject: [PATCH 30/50] Make atomic_min, atomic_max differentiable --- warp/native/array.h | 57 +++++++++++++++++++++++++++++++++------ warp/native/builtin.h | 19 +++++++++++++ warp/native/mat.h | 12 +++++++++ warp/native/vec.h | 23 +++++++++++----- warp/stubs.py | 16 +++++++++++ warp/tests/test_atomic.py | 54 ++++++++++++++++++++++++++++++++----- 6 files changed, 160 insertions(+), 21 deletions(-) diff --git a/warp/native/array.h b/warp/native/array.h index 86ac4d98d..8c6ea2b98 100644 --- a/warp/native/array.h +++ b/warp/native/array.h @@ -951,23 +951,64 @@ inline CUDA_CALLABLE void adj_atomic_sub(const A1& buf, int i, int j, int k, template class A1, template class A2, typename T> inline CUDA_CALLABLE void adj_atomic_sub(const A1& buf, int i, int j, int k, int l, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, int& adj_l, T& adj_value, const T& adj_ret) {} +// generic handler for scalar values template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, T value, const A2& adj_buf, int& adj_i, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, T value, const A2& adj_buf, int& adj_i, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i), &index_grad(buf, i), value, adj_value); + + FP_VERIFY_ADJ_1(value, adj_value) +} template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, int j, T value, const A2& adj_buf, int& adj_i, int& adj_j, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, int j, T value, const A2& adj_buf, int& adj_i, int& adj_j, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i, j), &index_grad(buf, i, j), value, adj_value); + + FP_VERIFY_ADJ_2(value, adj_value) +} template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, int j, int k, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, int j, int k, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i, j, k), &index_grad(buf, i, j, k), value, adj_value); + + FP_VERIFY_ADJ_3(value, adj_value) +} template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, int j, int k, int l, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, int& adj_l, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_min(const A1& buf, int i, int j, int k, int l, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, int& adj_l, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i, j, k, l), &index_grad(buf, i, j, k, l), value, adj_value); + + FP_VERIFY_ADJ_4(value, adj_value) +} template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, T value, const A2& adj_buf, int& adj_i, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, T value, const A2& adj_buf, int& adj_i, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i), &index_grad(buf, i), value, adj_value); + + FP_VERIFY_ADJ_1(value, adj_value) +} template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, int j, T value, const A2& adj_buf, int& adj_i, int& adj_j, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, int j, T value, const A2& adj_buf, int& adj_i, int& adj_j, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i, j), &index_grad(buf, i, j), value, adj_value); + + FP_VERIFY_ADJ_2(value, adj_value) +} template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, int j, int k, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, int j, int k, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i, j, k), &index_grad(buf, i, j, k), value, adj_value); + + FP_VERIFY_ADJ_3(value, adj_value) +} template class A1, template class A2, typename T> -inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, int j, int k, int l, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, int& adj_l, T& adj_value, const T& adj_ret) {} +inline CUDA_CALLABLE void adj_atomic_max(const A1& buf, int i, int j, int k, int l, T value, const A2& adj_buf, int& adj_i, int& adj_j, int& adj_k, int& adj_l, T& adj_value, const T& adj_ret) { + if (buf.grad) + adj_atomic_minmax(&index(buf, i, j, k, l), &index_grad(buf, i, j, k, l), value, adj_value); + + FP_VERIFY_ADJ_4(value, adj_value) +} } // namespace wp diff --git a/warp/native/builtin.h b/warp/native/builtin.h index ad33cf575..d5b7c8b2d 100644 --- a/warp/native/builtin.h +++ b/warp/native/builtin.h @@ -1271,6 +1271,25 @@ inline CUDA_CALLABLE int atomic_min(int* address, int val) #endif } +// default behavior for adjoint of atomic min/max operation that accumulates gradients for all elements matching the min/max value +template +CUDA_CALLABLE inline void adj_atomic_minmax(T *addr, T *adj_addr, const T &value, T &adj_value) +{ + if (value == *addr) + adj_value += *adj_addr; +} + +// for integral types we do not accumulate gradients +CUDA_CALLABLE inline void adj_atomic_minmax(int8* buf, int8* adj_buf, const int8 &value, int8 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(uint8* buf, uint8* adj_buf, const uint8 &value, uint8 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(int16* buf, int16* adj_buf, const int16 &value, int16 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(uint16* buf, uint16* adj_buf, const uint16 &value, uint16 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(int32* buf, int32* adj_buf, const int32 &value, int32 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(uint32* buf, uint32* adj_buf, const uint32 &value, uint32 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(int64* buf, int64* adj_buf, const int64 &value, int64 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(uint64* buf, uint64* adj_buf, const uint64 &value, uint64 &adj_value) { } +CUDA_CALLABLE inline void adj_atomic_minmax(bool* buf, bool* adj_buf, const bool &value, bool &adj_value) { } + } // namespace wp diff --git a/warp/native/mat.h b/warp/native/mat.h index d3853f689..40dfbdcc7 100644 --- a/warp/native/mat.h +++ b/warp/native/mat.h @@ -297,6 +297,18 @@ inline CUDA_CALLABLE mat_t atomic_max(mat_t * ad return m; } +template +inline CUDA_CALLABLE void adj_atomic_minmax( + mat_t *addr, + mat_t *adj_addr, + const mat_t &value, + mat_t &adj_value) +{ + for (unsigned i=0; i < Rows; ++i) + for (unsigned j=0; j < Cols; ++j) + adj_atomic_minmax(&addr->data[i][j], &adj_addr->data[i][j], value.data[i][j], adj_value.data[i][j]); +} + template inline CUDA_CALLABLE vec_t extract(const mat_t& m, int row) { diff --git a/warp/native/vec.h b/warp/native/vec.h index 9c70864cb..e5abeca9b 100644 --- a/warp/native/vec.h +++ b/warp/native/vec.h @@ -952,8 +952,8 @@ inline CUDA_CALLABLE void adj_max(const vec_t &v, vec_t -inline CUDA_CALLABLE vec_t atomic_add(vec_t * addr, vec_t value) { - +inline CUDA_CALLABLE vec_t atomic_add(vec_t * addr, vec_t value) +{ vec_t ret; for( unsigned i=0; i < Length; ++i ) { @@ -964,8 +964,8 @@ inline CUDA_CALLABLE vec_t atomic_add(vec_t * addr, } template -inline CUDA_CALLABLE vec_t atomic_min(vec_t * addr, vec_t value) { - +inline CUDA_CALLABLE vec_t atomic_min(vec_t * addr, vec_t value) +{ vec_t ret; for( unsigned i=0; i < Length; ++i ) { @@ -976,8 +976,8 @@ inline CUDA_CALLABLE vec_t atomic_min(vec_t * addr, } template -inline CUDA_CALLABLE vec_t atomic_max(vec_t * addr, vec_t value) { - +inline CUDA_CALLABLE vec_t atomic_max(vec_t * addr, vec_t value) +{ vec_t ret; for( unsigned i=0; i < Length; ++i ) { @@ -987,6 +987,17 @@ inline CUDA_CALLABLE vec_t atomic_max(vec_t * addr, return ret; } +template +inline CUDA_CALLABLE void adj_atomic_minmax( + vec_t *addr, + vec_t *adj_addr, + const vec_t &value, + vec_t &adj_value) +{ + for (unsigned i=0; i < Length; ++i) + adj_atomic_minmax(&(addr->c[i]), &(adj_addr->c[i]), value[i], adj_value[i]); +} + // ok, the original implementation of this didn't take the absolute values. // I wouldn't consider this expected behavior. It looks like it's only // being used for bounding boxes at the moment, where this doesn't matter, diff --git a/warp/stubs.py b/warp/stubs.py index 9d5afa21f..a3856efdd 100644 --- a/warp/stubs.py +++ b/warp/stubs.py @@ -1863,6 +1863,8 @@ def atomic_min(a: Array[Any], i: int32, value: Any): Compute the minimum of ``value`` and ``a[i]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the minimum of ``a``. """ ... @@ -1873,6 +1875,8 @@ def atomic_min(a: Array[Any], i: int32, j: int32, value: Any): Compute the minimum of ``value`` and ``a[i,j]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the minimum of ``a``. """ ... @@ -1883,6 +1887,8 @@ def atomic_min(a: Array[Any], i: int32, j: int32, k: int32, value: Any): Compute the minimum of ``value`` and ``a[i,j,k]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the minimum of ``a``. """ ... @@ -1893,6 +1899,8 @@ def atomic_min(a: Array[Any], i: int32, j: int32, k: int32, l: int32, value: Any Compute the minimum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the minimum of ``a``. """ ... @@ -1983,6 +1991,8 @@ def atomic_max(a: Array[Any], i: int32, value: Any): Compute the maximum of ``value`` and ``a[i]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the maximum of ``a``. """ ... @@ -1993,6 +2003,8 @@ def atomic_max(a: Array[Any], i: int32, j: int32, value: Any): Compute the maximum of ``value`` and ``a[i,j]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the maximum of ``a``. """ ... @@ -2003,6 +2015,8 @@ def atomic_max(a: Array[Any], i: int32, j: int32, k: int32, value: Any): Compute the maximum of ``value`` and ``a[i,j,k]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the maximum of ``a``. """ ... @@ -2013,6 +2027,8 @@ def atomic_max(a: Array[Any], i: int32, j: int32, k: int32, l: int32, value: Any Compute the maximum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. Note that for vectors and matrices the operation is only atomic on a per-component basis. + + The gradient through this operation is accumulated for every element (or its component, in the case of vectors and matrices) of ``a`` that is equal to the maximum of ``a``. """ ... diff --git a/warp/tests/test_atomic.py b/warp/tests/test_atomic.py index 6dc0d4ea2..5cba5f746 100644 --- a/warp/tests/test_atomic.py +++ b/warp/tests/test_atomic.py @@ -53,20 +53,60 @@ def test_atomic(test, device): base = rng.random(size=(1, *type._shape_), dtype=float) val = rng.random(size=(n, *type._shape_), dtype=float) - add_array = wp.array(base, dtype=type, device=device) - min_array = wp.array(base, dtype=type, device=device) - max_array = wp.array(base, dtype=type, device=device) + add_array = wp.array(base, dtype=type, device=device, requires_grad=True) + min_array = wp.array(base, dtype=type, device=device, requires_grad=True) + max_array = wp.array(base, dtype=type, device=device, requires_grad=True) + add_array.zero_() + min_array.fill_(10000) + max_array.fill_(-10000) - val_array = wp.array(val, dtype=type, device=device) + val_array = wp.array(val, dtype=type, device=device, requires_grad=True) - wp.launch(kernel, n, inputs=[add_array, min_array, max_array, val_array], device=device) - - val = np.append(val, [base[0]], axis=0) + tape = wp.Tape() + with tape: + wp.launch(kernel, n, inputs=[add_array, min_array, max_array, val_array], device=device) assert_np_equal(add_array.numpy(), np.sum(val, axis=0), tol=1.0e-2) assert_np_equal(min_array.numpy(), np.min(val, axis=0), tol=1.0e-2) assert_np_equal(max_array.numpy(), np.max(val, axis=0), tol=1.0e-2) + if type != wp.int32: + add_array.grad.fill_(1) + tape.backward() + assert_np_equal(val_array.grad.numpy(), np.ones_like(val)) + tape.zero() + + min_array.grad.fill_(1) + tape.backward() + min_grad_array = np.zeros_like(val) + argmin = val.argmin(axis=0) + if val.ndim == 1: + min_grad_array[argmin] = 1 + elif val.ndim == 2: + for i in range(val.shape[1]): + min_grad_array[argmin[i], i] = 1 + elif val.ndim == 3: + for i in range(val.shape[1]): + for j in range(val.shape[2]): + min_grad_array[argmin[i, j], i, j] = 1 + assert_np_equal(val_array.grad.numpy(), min_grad_array) + tape.zero() + + max_array.grad.fill_(1) + tape.backward() + max_grad_array = np.zeros_like(val) + argmax = val.argmax(axis=0) + if val.ndim == 1: + max_grad_array[argmax] = 1 + elif val.ndim == 2: + for i in range(val.shape[1]): + max_grad_array[argmax[i], i] = 1 + elif val.ndim == 3: + for i in range(val.shape[1]): + for j in range(val.shape[2]): + max_grad_array[argmax[i, j], i, j] = 1 + assert_np_equal(val_array.grad.numpy(), max_grad_array) + return test_atomic From ebaf4adb18bc89c47bfcec85e7a17ba9716501f1 Mon Sep 17 00:00:00 2001 From: Eric Heiden Date: Tue, 12 Dec 2023 16:48:34 -0800 Subject: [PATCH 31/50] Add depth rendering to OpenGLRenderer, document warp.render --- docs/index.rst | 1 + docs/modules/render.rst | 38 +++ examples/example_render_opengl.py | 25 +- warp/render/render_opengl.py | 370 +++++++++++++++++++++--------- 4 files changed, 317 insertions(+), 117 deletions(-) create mode 100644 docs/modules/render.rst diff --git a/docs/index.rst b/docs/index.rst index 1c7c8f690..383df0f66 100644 --- a/docs/index.rst +++ b/docs/index.rst @@ -180,6 +180,7 @@ Full Table of Contents modules/sim modules/sparse modules/fem + modules/render .. toctree:: :hidden: diff --git a/docs/modules/render.rst b/docs/modules/render.rst new file mode 100644 index 000000000..4988c8757 --- /dev/null +++ b/docs/modules/render.rst @@ -0,0 +1,38 @@ +warp.render +=============================== + +.. currentmodule:: warp.render + +The ``warp.render`` module provides a set of renderers that can be used for visualizing scenes involving shapes of various types. + +Built on top of these stand-alone renderers, the ``warp.sim.render`` module provides renderers that can be used to visualize scenes directly from ``warp.sim.ModelBuilder`` objects and update them from ``warp.sim.State`` objects. + +.. + .. toctree:: + :maxdepth: 2 + +Stand-alone renderers +--------------------- + +The ``OpenGLRenderer`` provides an interactive renderer to play back animations in real time, the ``UsdRenderer`` provides a renderer that exports the scene to a USD file that can be rendered in a renderer of your choice. + +.. autoclass:: UsdRenderer + :members: + + +.. autoclass:: OpenGLRenderer + :members: + +Simulation renderers +-------------------- + +Based on these renderers from ``warp.render``, the ``SimRendererUsd`` (which equals ``SimRenderer``) and ``SimRendererOpenGL`` classes from ``warp.sim.render`` are derived to populate the renderers directly from ``warp.sim.ModelBuilder`` scenes and update them from ``warp.sim.State`` objects. + +.. currentmodule:: warp.sim.render + +.. autoclass:: SimRendererUsd + :members: + +.. autoclass:: SimRendererOpenGL + :members: + diff --git a/examples/example_render_opengl.py b/examples/example_render_opengl.py index 759db719c..8bf2ffa38 100644 --- a/examples/example_render_opengl.py +++ b/examples/example_render_opengl.py @@ -27,6 +27,8 @@ custom_tile_arrangement = False # whether to display the pixels in a matplotlib figure show_plot = True +# whether to render depth image to a Warp array +render_mode = "depth" renderer = wp.render.OpenGLRenderer(vsync=False) instance_ids = [] @@ -51,11 +53,12 @@ renderer.render_ground() +channels = 1 if render_mode == "depth" else 3 if show_plot: import matplotlib.pyplot as plt if split_up_tiles: - pixels = wp.zeros((num_tiles, renderer.tile_height, renderer.tile_width, 3), dtype=wp.float32) + pixels = wp.zeros((num_tiles, renderer.tile_height, renderer.tile_width, channels), dtype=wp.float32) ncols = int(np.ceil(np.sqrt(num_tiles))) nrows = int(np.ceil(num_tiles / float(ncols))) img_plots = [] @@ -70,17 +73,23 @@ sharey=True, num=1, ) - tile_temp = np.zeros((renderer.tile_height, renderer.tile_width, 3), dtype=np.float32) + tile_temp = np.zeros((renderer.tile_height, renderer.tile_width, channels), dtype=np.float32) for dim in range(ncols * nrows): ax = axes[dim // ncols, dim % ncols] if dim >= num_tiles: ax.axis("off") continue - img_plots.append(ax.imshow(tile_temp)) + if render_mode == "depth": + img_plots.append(ax.imshow(tile_temp, vmin=renderer.camera_near_plane, vmax=renderer.camera_far_plane)) + else: + img_plots.append(ax.imshow(tile_temp)) else: fig = plt.figure(1) - pixels = wp.zeros((renderer.screen_height, renderer.screen_width, 3), dtype=wp.float32) - img_plot = plt.imshow(pixels.numpy()) + pixels = wp.zeros((renderer.screen_height, renderer.screen_width, channels), dtype=wp.float32) + if render_mode == "depth": + img_plot = plt.imshow(pixels.numpy(), vmin=renderer.camera_near_plane, vmax=renderer.camera_far_plane) + else: + img_plot = plt.imshow(pixels.numpy()) plt.ion() plt.show() @@ -110,15 +119,15 @@ if show_plot and plt.fignum_exists(1): if split_up_tiles: - pixel_shape = (num_tiles, renderer.tile_height, renderer.tile_width, 3) + pixel_shape = (num_tiles, renderer.tile_height, renderer.tile_width, channels) else: - pixel_shape = (renderer.screen_height, renderer.screen_width, 3) + pixel_shape = (renderer.screen_height, renderer.screen_width, channels) if pixel_shape != pixels.shape: # make sure we resize the pixels array to the right dimensions if the user resizes the window pixels = wp.zeros(pixel_shape, dtype=wp.float32) - renderer.get_pixels(pixels, split_up_tiles=split_up_tiles) + renderer.get_pixels(pixels, split_up_tiles=split_up_tiles, mode=render_mode) if split_up_tiles: pixels_np = pixels.numpy() diff --git a/warp/render/render_opengl.py b/warp/render/render_opengl.py index 0efc77805..6cff3a98d 100644 --- a/warp/render/render_opengl.py +++ b/warp/render/render_opengl.py @@ -13,12 +13,14 @@ from collections import defaultdict from typing import List, Tuple, Union, Optional +from enum import Enum import numpy as np import ctypes Mat44 = Union[List[float], List[List[float]], np.ndarray] + wp.set_module_options({"enable_backward": False}) shape_vertex_shader = """ @@ -175,12 +177,13 @@ uniform vec3 color1; uniform vec3 color2; +uniform float farPlane; uniform vec3 sunDirection; void main() { - float y = tanh(FragPos.y*0.01)*0.5+0.5; + float y = tanh(FragPos.y/farPlane*10.0)*0.5+0.5; float height = sqrt(1.0-y); float s = pow(0.5, 1.0 / 10.0); @@ -222,6 +225,42 @@ } """ +frame_depth_fragment_shader = """ +#version 330 core +in vec2 TexCoord; + +out vec4 FragColor; + +uniform sampler2D textureSampler; + +vec3 bourkeColorMap(float v) { + vec3 c = vec3(1.0, 1.0, 1.0); + + v = clamp(v, 0.0, 1.0); // Ensures v is between 0 and 1 + + if (v < 0.25) { + c.r = 0.0; + c.g = 4.0 * v; + } else if (v < 0.5) { + c.r = 0.0; + c.b = 1.0 + 4.0 * (0.25 - v); + } else if (v < 0.75) { + c.r = 4.0 * (v - 0.5); + c.b = 0.0; + } else { + c.g = 1.0 + 4.0 * (0.75 - v); + c.b = 0.0; + } + + return c; +} + +void main() { + float depth = texture(textureSampler, TexCoord).r; + FragColor = vec4(bourkeColorMap(sqrt(1.0 - depth)), 1.0); +} +""" + @wp.kernel def update_vbo_transforms( @@ -411,7 +450,7 @@ def assemble_gfx_vertices( @wp.kernel -def copy_frame( +def copy_rgb_frame( input_img: wp.array(dtype=wp.uint8), width: int, height: int, @@ -432,7 +471,26 @@ def copy_frame( @wp.kernel -def copy_frame_tiles( +def copy_depth_frame( + input_img: wp.array(dtype=wp.float32), + width: int, + height: int, + near: float, + far: float, + # outputs + output_img: wp.array(dtype=wp.float32, ndim=3), +): + w, v = wp.tid() + pixel = v * width + w + # flip vertically (OpenGL coordinates start at bottom) + v = height - v - 1 + d = 2.0 * input_img[pixel] - 1.0 + d = 2.0 * near * far / ((far - near) * d - near - far) + output_img[v, w, 0] = -d + + +@wp.kernel +def copy_rgb_frame_tiles( input_img: wp.array(dtype=wp.uint8), positions: wp.array(dtype=int, ndim=2), screen_width: int, @@ -463,7 +521,34 @@ def copy_frame_tiles( @wp.kernel -def copy_frame_tile( +def copy_depth_frame_tiles( + input_img: wp.array(dtype=wp.float32), + positions: wp.array(dtype=int, ndim=2), + screen_width: int, + screen_height: int, + tile_height: int, + near: float, + far: float, + # outputs + output_img: wp.array(dtype=wp.float32, ndim=4), +): + tile, x, y = wp.tid() + p = positions[tile] + qx = x + p[0] + qy = y + p[1] + pixel = qy * screen_width + qx + # flip vertically (OpenGL coordinates start at bottom) + y = tile_height - y - 1 + if qx >= screen_width or qy >= screen_height: + output_img[tile, y, x, 0] = far + return # prevent out-of-bounds access + d = 2.0 * input_img[pixel] - 1.0 + d = 2.0 * near * far / ((far - near) * d - near - far) + output_img[tile, y, x, 0] = -d + + +@wp.kernel +def copy_rgb_frame_tile( input_img: wp.array(dtype=wp.uint8), offset_x: int, offset_y: int, @@ -768,15 +853,19 @@ def __init__( up_axis="Y", screen_width=1024, screen_height=768, - near_plane=0.01, - far_plane=1000.0, + near_plane=1.0, + far_plane=100.0, camera_fov=45.0, + camera_pos=(0.0, 2.0, 10.0), + camera_front=(0.0, 0.0, -1.0), + camera_up=(0.0, 1.0, 0.0), background_color=(0.53, 0.8, 0.92), draw_grid=True, draw_sky=True, draw_axis=True, show_info=True, render_wireframe=False, + render_depth=False, axis_scale=1.0, vsync=False, headless=False, @@ -804,6 +893,7 @@ def __init__( self.draw_axis = draw_axis self.show_info = show_info self.render_wireframe = render_wireframe + self.render_depth = render_depth self.enable_backface_culling = enable_backface_culling self._device = wp.get_cuda_device() @@ -819,9 +909,9 @@ def __init__( self.screen_width, self.screen_height = self.window.get_framebuffer_size() - self._camera_pos = PyVec3(0.0, 2.0, 10.0) - self._camera_front = PyVec3(0.0, 0.0, -1.0) - self._camera_up = PyVec3(0.0, 1.0, 0.0) + self._camera_pos = PyVec3(*camera_pos) + self._camera_front = PyVec3(*camera_front) + self._camera_up = PyVec3(*camera_up) self._camera_speed = 0.04 if isinstance(up_axis, int): self._camera_axis = up_axis @@ -832,6 +922,7 @@ def __init__( self._first_mouse = True self._left_mouse_pressed = False self._keys_pressed = defaultdict(bool) + self._key_callbacks = [] self.update_view_matrix() self.update_projection_matrix() @@ -888,6 +979,7 @@ def __init__( self._tile_projection_matrices = None self._frame_texture = None + self._frame_depth_texture = None self._frame_fbo = None self._frame_pbo = None @@ -903,6 +995,8 @@ def __init__( gl.glClearColor(*self.background_color, 1) gl.glEnable(gl.GL_DEPTH_TEST) + gl.glDepthMask(True) + gl.glDepthRange(0.0, 1.0) self._shape_shader = ShaderProgram( Shader(shape_vertex_shader, "vertex"), Shader(shape_fragment_shader, "fragment") @@ -969,15 +1063,17 @@ def __init__( self._loc_sky_color1 = gl.glGetUniformLocation(self._sky_shader.id, str_buffer("color1")) self._loc_sky_color2 = gl.glGetUniformLocation(self._sky_shader.id, str_buffer("color2")) + self._loc_sky_far_plane = gl.glGetUniformLocation(self._sky_shader.id, str_buffer("farPlane")) gl.glUniform3f(self._loc_sky_color1, *background_color) # glUniform3f(self._loc_sky_color2, *np.clip(np.array(background_color)+0.5, 0.0, 1.0)) gl.glUniform3f(self._loc_sky_color2, 0.8, 0.4, 0.05) + gl.glUniform1f(self._loc_sky_far_plane, self.camera_far_plane) self._loc_sky_view_pos = gl.glGetUniformLocation(self._sky_shader.id, str_buffer("viewPos")) gl.glUniform3f( gl.glGetUniformLocation(self._sky_shader.id, str_buffer("sunDirection")), *self._sun_direction ) - # Create VAO, VBO, and EBO + # create VAO, VBO, and EBO self._sky_vao = gl.GLuint() gl.glGenVertexArrays(1, self._sky_vao) gl.glBindVertexArray(self._sky_vao) @@ -995,7 +1091,7 @@ def __init__( gl.glBindBuffer(gl.GL_ELEMENT_ARRAY_BUFFER, self._sky_ebo) gl.glBufferData(gl.GL_ELEMENT_ARRAY_BUFFER, indices.nbytes, indices.ctypes.data, gl.GL_STATIC_DRAW) - # Set up vertex attributes + # set up vertex attributes vertex_stride = vertices.shape[1] * vertices.itemsize # positions gl.glVertexAttribPointer(0, 3, gl.GL_FLOAT, gl.GL_FALSE, vertex_stride, ctypes.c_void_p(0)) @@ -1029,6 +1125,7 @@ def __init__( # create frame buffer for rendering to a texture self._frame_texture = None + self._frame_depth_texture = None self._frame_fbo = None self._setup_framebuffer() @@ -1076,7 +1173,15 @@ def __init__( gl.glUseProgram(self._frame_shader.id) self._frame_loc_texture = gl.glGetUniformLocation(self._frame_shader.id, str_buffer("textureSampler")) - # Unbind the VBO and VAO + self._frame_depth_shader = ShaderProgram( + Shader(frame_vertex_shader, "vertex"), Shader(frame_depth_fragment_shader, "fragment") + ) + gl.glUseProgram(self._frame_depth_shader.id) + self._frame_loc_depth_texture = gl.glGetUniformLocation( + self._frame_depth_shader.id, str_buffer("textureSampler") + ) + + # unbind the VBO and VAO gl.glBindBuffer(gl.GL_ARRAY_BUFFER, 0) gl.glBindVertexArray(0) @@ -1322,7 +1427,11 @@ def _setup_framebuffer(self): if self._frame_texture is None: self._frame_texture = gl.GLuint() gl.glGenTextures(1, self._frame_texture) + if self._frame_depth_texture is None: + self._frame_depth_texture = gl.GLuint() + gl.glGenTextures(1, self._frame_depth_texture) + # set up RGB texture gl.glBindFramebuffer(gl.GL_FRAMEBUFFER, 0) gl.glBindBuffer(gl.GL_PIXEL_UNPACK_BUFFER, 0) gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_texture) @@ -1339,6 +1448,22 @@ def _setup_framebuffer(self): ) gl.glTexParameteri(gl.GL_TEXTURE_2D, gl.GL_TEXTURE_MIN_FILTER, gl.GL_LINEAR) gl.glTexParameteri(gl.GL_TEXTURE_2D, gl.GL_TEXTURE_MAG_FILTER, gl.GL_LINEAR) + + # set up depth texture + gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_depth_texture) + gl.glTexImage2D( + gl.GL_TEXTURE_2D, + 0, + gl.GL_DEPTH_COMPONENT32, + self.screen_width, + self.screen_height, + 0, + gl.GL_DEPTH_COMPONENT, + gl.GL_FLOAT, + None, + ) + gl.glTexParameteri(gl.GL_TEXTURE_2D, gl.GL_TEXTURE_MIN_FILTER, gl.GL_LINEAR) + gl.glTexParameteri(gl.GL_TEXTURE_2D, gl.GL_TEXTURE_MAG_FILTER, gl.GL_LINEAR) gl.glBindTexture(gl.GL_TEXTURE_2D, 0) # create a framebuffer object (FBO) @@ -1351,15 +1476,9 @@ def _setup_framebuffer(self): gl.glFramebufferTexture2D( gl.GL_FRAMEBUFFER, gl.GL_COLOR_ATTACHMENT0, gl.GL_TEXTURE_2D, self._frame_texture, 0 ) - - self._frame_depth_renderbuffer = gl.GLuint() - gl.glGenRenderbuffers(1, self._frame_depth_renderbuffer) - gl.glBindRenderbuffer(gl.GL_RENDERBUFFER, self._frame_depth_renderbuffer) - gl.glRenderbufferStorage(gl.GL_RENDERBUFFER, gl.GL_DEPTH_COMPONENT, self.screen_width, self.screen_height) - - # attach the depth renderbuffer to the FBO - gl.glFramebufferRenderbuffer( - gl.GL_FRAMEBUFFER, gl.GL_DEPTH_ATTACHMENT, gl.GL_RENDERBUFFER, self._frame_depth_renderbuffer + # attach the depth texture to the FBO as its depth attachment + gl.glFramebufferTexture2D( + gl.GL_FRAMEBUFFER, gl.GL_DEPTH_ATTACHMENT, gl.GL_TEXTURE_2D, self._frame_depth_texture, 0 ) if gl.glCheckFramebufferStatus(gl.GL_FRAMEBUFFER) != gl.GL_FRAMEBUFFER_COMPLETE: @@ -1367,13 +1486,6 @@ def _setup_framebuffer(self): gl.glBindFramebuffer(gl.GL_FRAMEBUFFER, 0) sys.exit(1) - gl.glBindRenderbuffer(gl.GL_RENDERBUFFER, 0) - else: - # rescale framebuffer - gl.glBindRenderbuffer(gl.GL_RENDERBUFFER, self._frame_depth_renderbuffer) - gl.glRenderbufferStorage(gl.GL_RENDERBUFFER, gl.GL_DEPTH_COMPONENT, self.screen_width, self.screen_height) - gl.glBindRenderbuffer(gl.GL_RENDERBUFFER, 0) - # unbind the FBO (switch back to the default framebuffer) gl.glBindFramebuffer(gl.GL_FRAMEBUFFER, 0) @@ -1383,7 +1495,11 @@ def _setup_framebuffer(self): gl.glBindBuffer(gl.GL_PIXEL_PACK_BUFFER, self._frame_pbo) # binding to this buffer # allocate memory for PBO - pixels = np.zeros((self.screen_height, self.screen_width, 3), dtype=np.uint8) + rgb_bytes_per_pixel = 3 + depth_bytes_per_pixel = 4 + pixels = np.zeros( + (self.screen_height, self.screen_width, rgb_bytes_per_pixel + depth_bytes_per_pixel), dtype=np.uint8 + ) gl.glBufferData(gl.GL_PIXEL_PACK_BUFFER, pixels.nbytes, pixels.ctypes.data, gl.GL_DYNAMIC_DRAW) gl.glBindBuffer(gl.GL_PIXEL_PACK_BUFFER, 0) @@ -1542,7 +1658,6 @@ def _draw(self): if self._frame_fbo is not None: gl.glBindFramebuffer(gl.GL_FRAMEBUFFER, self._frame_fbo) - gl.glBindBuffer(gl.GL_PIXEL_UNPACK_BUFFER, self._frame_fbo) gl.glClearColor(*self.background_color, 1) gl.glClear(gl.GL_COLOR_BUFFER_BIT | gl.GL_DEPTH_BUFFER_BIT) @@ -1580,15 +1695,26 @@ def _draw(self): # render frame buffer texture to screen if self._frame_fbo is not None: - with self._frame_shader: - gl.glActiveTexture(gl.GL_TEXTURE0) - gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_texture) - gl.glUniform1i(self._frame_loc_texture, 0) + if self.render_depth: + with self._frame_depth_shader: + gl.glActiveTexture(gl.GL_TEXTURE0) + gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_depth_texture) + gl.glUniform1i(self._frame_loc_depth_texture, 0) + + gl.glBindVertexArray(self._frame_vao) + gl.glDrawElements(gl.GL_TRIANGLES, len(self._frame_indices), gl.GL_UNSIGNED_INT, None) + gl.glBindVertexArray(0) + gl.glBindTexture(gl.GL_TEXTURE_2D, 0) + else: + with self._frame_shader: + gl.glActiveTexture(gl.GL_TEXTURE0) + gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_texture) + gl.glUniform1i(self._frame_loc_texture, 0) - gl.glBindVertexArray(self._frame_vao) - gl.glDrawElements(gl.GL_TRIANGLES, len(self._frame_indices), gl.GL_UNSIGNED_INT, None) - gl.glBindVertexArray(0) - gl.glBindTexture(gl.GL_TEXTURE_2D, 0) + gl.glBindVertexArray(self._frame_vao) + gl.glDrawElements(gl.GL_TRIANGLES, len(self._frame_indices), gl.GL_UNSIGNED_INT, None) + gl.glBindVertexArray(0) + gl.glBindTexture(gl.GL_TEXTURE_2D, 0) # check for OpenGL errors # check_gl_error() @@ -1767,9 +1893,17 @@ def _key_press_callback(self, symbol, modifiers): self.show_info = not self.show_info if symbol == pyglet.window.key.X: self.render_wireframe = not self.render_wireframe + if symbol == pyglet.window.key.T: + self.render_depth = not self.render_depth if symbol == pyglet.window.key.B: self.enable_backface_culling = not self.enable_backface_culling + for cb in self._key_callbacks: + cb(symbol, modifiers) + + def register_key_press_callback(self, callback): + self._key_callbacks.append(callback) + def _window_resize_callback(self, width, height): self._first_mouse = True self.screen_width, self.screen_height = self.window.get_framebuffer_size() @@ -1861,7 +1995,7 @@ def allocate_shape_instances(self): gl.glDeleteBuffers(1, self._instance_color1_buffer) gl.glDeleteBuffers(1, self._instance_color2_buffer) - # Create instance buffer and bind it as an instanced array + # create instance buffer and bind it as an instanced array self._instance_transform_gl_buffer = gl.GLuint() gl.glGenBuffers(1, self._instance_transform_gl_buffer) gl.glBindBuffer(gl.GL_ARRAY_BUFFER, self._instance_transform_gl_buffer) @@ -1869,7 +2003,7 @@ def allocate_shape_instances(self): transforms = np.tile(np.diag(np.ones(4, dtype=np.float32)), (len(self._instances), 1, 1)) gl.glBufferData(gl.GL_ARRAY_BUFFER, transforms.nbytes, transforms.ctypes.data, gl.GL_DYNAMIC_DRAW) - # Create CUDA buffer for instance transforms + # create CUDA buffer for instance transforms self._instance_transform_cuda_buffer = wp.RegisteredGLBuffer( int(self._instance_transform_gl_buffer.value), self._device ) @@ -1897,7 +2031,7 @@ def allocate_shape_instances(self): gl.glBindBuffer(gl.GL_ARRAY_BUFFER, self._instance_color2_buffer) gl.glBufferData(gl.GL_ARRAY_BUFFER, colors2.nbytes, colors2.ctypes.data, gl.GL_STATIC_DRAW) - # Set up instance attribute pointers + # set up instance attribute pointers matrix_size = transforms[0].nbytes instance_ids = [] @@ -2018,9 +2152,27 @@ def save(self): self.clear() self.app.event_loop.exit() - def get_pixels(self, target_image: wp.array, split_up_tiles=True): + def get_pixels(self, target_image: wp.array, split_up_tiles=True, mode="rgb"): + """ + Read the pixels from the frame buffer (RGB or depth are supported) into the given array. + + If `split_up_tiles` is False, array must be of shape (screen_height, screen_width, 3) for RGB mode or + (screen_height, screen_width, 1) for depth mode. + If `split_up_tiles` is True, the pixels will be split up into tiles (see :attr:`tile_width` and :attr:`tile_height` for dimensions): + array must be of shape (num_tiles, tile_height, tile_width, 3) for RGB mode or (num_tiles, tile_height, tile_width, 1) for depth mode. + + Args: + target_image (array): The array to read the pixels into. Must have float32 as dtype and be on a CUDA device. + split_up_tiles (bool): Whether to split up the viewport into tiles, see :meth:`setup_tiled_rendering`. + mode (str): can be either "rgb" or "depth" + + Returns: + bool: Whether the pixels were successfully read. + """ from pyglet import gl + channels = 3 if mode == "rgb" else 1 + if split_up_tiles: assert ( self._tile_width is not None and self._tile_height is not None @@ -2035,20 +2187,26 @@ def get_pixels(self, target_image: wp.array, split_up_tiles=True): self.num_tiles, self._tile_height, self._tile_width, - 3, - ), f"Shape of `target_image` array does not match {self.num_tiles} x {self.screen_height} x {self.screen_width} x 3" + channels, + ), f"Shape of `target_image` array does not match {self.num_tiles} x {self.screen_height} x {self.screen_width} x {channels}" else: assert target_image.shape == ( self.screen_height, self.screen_width, - 3, - ), f"Shape of `target_image` array does not match {self.screen_height} x {self.screen_width} x 3" + channels, + ), f"Shape of `target_image` array does not match {self.screen_height} x {self.screen_width} x {channels}" gl.glBindBuffer(gl.GL_PIXEL_PACK_BUFFER, self._frame_pbo) - gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_texture) + if mode == "rgb": + gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_texture) + if mode == "depth": + gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_depth_texture) try: # read screen texture into PBO - gl.glGetTexImage(gl.GL_TEXTURE_2D, 0, gl.GL_RGB, gl.GL_UNSIGNED_BYTE, ctypes.c_void_p(0)) + if mode == "rgb": + gl.glGetTexImage(gl.GL_TEXTURE_2D, 0, gl.GL_RGB, gl.GL_UNSIGNED_BYTE, ctypes.c_void_p(0)) + elif mode == "depth": + gl.glGetTexImage(gl.GL_TEXTURE_2D, 0, gl.GL_DEPTH_COMPONENT, gl.GL_FLOAT, ctypes.c_void_p(0)) except gl.GLException: # this can happen if the window is closed/being moved to a different display gl.glBindTexture(gl.GL_TEXTURE_2D, 0) @@ -2061,63 +2219,54 @@ def get_pixels(self, target_image: wp.array, split_up_tiles=True): int(self._frame_pbo.value), self._device, wp.RegisteredGLBuffer.WRITE_DISCARD ) screen_size = self.screen_height * self.screen_width - img = pbo_buffer.map(dtype=wp.uint8, shape=(screen_size * 3)) + if mode == "rgb": + img = pbo_buffer.map(dtype=wp.uint8, shape=(screen_size * channels)) + elif mode == "depth": + img = pbo_buffer.map(dtype=wp.float32, shape=(screen_size * channels)) img = img.to(target_image.device) if split_up_tiles: positions = wp.array(self._tile_viewports, ndim=2, dtype=wp.int32, device=target_image.device) - wp.launch( - copy_frame_tiles, - dim=(self.num_tiles, self._tile_width, self._tile_height), - inputs=[img, positions, self.screen_width, self.screen_height, self._tile_height], - outputs=[target_image], - device=target_image.device, - ) + if mode == "rgb": + wp.launch( + copy_rgb_frame_tiles, + dim=(self.num_tiles, self._tile_width, self._tile_height), + inputs=[img, positions, self.screen_width, self.screen_height, self._tile_height], + outputs=[target_image], + device=target_image.device, + ) + elif mode == "depth": + wp.launch( + copy_depth_frame_tiles, + dim=(self.num_tiles, self._tile_width, self._tile_height), + inputs=[ + img, + positions, + self.screen_width, + self.screen_height, + self._tile_height, + self.camera_near_plane, + self.camera_far_plane, + ], + outputs=[target_image], + device=target_image.device, + ) else: - wp.launch( - copy_frame, - dim=(self.screen_width, self.screen_height), - inputs=[img, self.screen_width, self.screen_height], - outputs=[target_image], - device=target_image.device, - ) - pbo_buffer.unmap() - return True - - def get_tile_pixels(self, tile_id: int, target_image: wp.array): - from pyglet import gl - - viewport = self._tile_viewports[tile_id] - assert target_image.shape == ( - viewport[3], - viewport[2], - 3, - ), f"Shape of `target_image` array does not match {viewport[3]} x {viewport[2]} x 3" - gl.glBindBuffer(gl.GL_PIXEL_PACK_BUFFER, self._frame_pbo) - gl.glBindTexture(gl.GL_TEXTURE_2D, self._frame_texture) - try: - # read screen texture into PBO - gl.glGetTexImage(gl.GL_TEXTURE_2D, 0, gl.GL_RGB, gl.GL_UNSIGNED_BYTE, ctypes.c_void_p(0)) - except gl.GLException: - # this can happen if the window is closed/being moved to a different display - gl.glBindTexture(gl.GL_TEXTURE_2D, 0) - gl.glBindBuffer(gl.GL_PIXEL_PACK_BUFFER, 0) - return False - gl.glBindTexture(gl.GL_TEXTURE_2D, 0) - gl.glBindBuffer(gl.GL_PIXEL_PACK_BUFFER, 0) - - pbo_buffer = wp.RegisteredGLBuffer( - int(self._frame_pbo.value), self._device, wp.RegisteredGLBuffer.WRITE_DISCARD - ) - screen_size = self.screen_height * self.screen_width - img = pbo_buffer.map(dtype=wp.uint8, shape=(screen_size * 3)) - img = img.to(target_image.device) - wp.launch( - copy_frame_tiles, - dim=(self.num_tiles, self._tile_width, self._tile_height), - inputs=[img, viewport[0], viewport[1], self.screen_width, self.screen_height, self._tile_height], - outputs=[target_image], - device=target_image.device, - ) + if mode == "rgb": + wp.launch( + copy_rgb_frame, + dim=(self.screen_width, self.screen_height), + inputs=[img, self.screen_width, self.screen_height], + outputs=[target_image], + device=target_image.device, + ) + elif mode == "depth": + wp.launch( + copy_depth_frame, + dim=(self.screen_width, self.screen_height), + inputs=[img, self.screen_width, self.screen_height, self.camera_near_plane, self.camera_far_plane], + outputs=[target_image], + device=target_image.device, + ) pbo_buffer.unmap() return True @@ -2570,7 +2719,7 @@ def _render_lines(self, name: str, lines, color: tuple, radius: float = 0.01): if name not in self._shape_instancers: instancer = ShapeInstancer(self._shape_shader, self._device) vertices, indices = self._create_capsule_mesh(radius, 0.5) - if color is None or isinstance(color, list): + if color is None or isinstance(color, list) and len(color) > 0 and isinstance(color[0], list): color = tab10_color_map(len(self._shape_geo_hash)) instancer.register_shape(vertices, indices, color, color) instancer.allocate_instances(np.zeros((len(lines), 3))) @@ -2640,7 +2789,12 @@ def update_shape_vertices(self, shape, points): cuda_buffer.unmap() @staticmethod - def _create_sphere_mesh(radius=1.0, num_latitudes=default_num_segments, num_longitudes=default_num_segments, reverse_winding=False): + def _create_sphere_mesh( + radius=1.0, + num_latitudes=default_num_segments, + num_longitudes=default_num_segments, + reverse_winding=False, + ): vertices = [] indices = [] @@ -2754,7 +2908,7 @@ def _create_cylinder_mesh(radius, half_height, up_axis=1, segments=default_num_s top_radius = radius side_slope = -np.arctan2(top_radius - radius, 2 * half_height) - # Create the cylinder base and top vertices + # create the cylinder base and top vertices for j in (-1, 1): center_index = max(j, 0) if j == 1: @@ -2782,12 +2936,10 @@ def _create_cylinder_mesh(radius, half_height, up_axis=1, segments=default_num_s vertex = np.hstack([position[[x_dir, y_dir, z_dir]], normal[[x_dir, y_dir, z_dir]], uv]) cap_vertices.append(vertex) - indices.extend( - [center_index, i + center_index * segments + 2, - (i + 1) % segments + center_index * segments + 2][::-j] - ) + cs = center_index * segments + indices.extend([center_index, i + cs + 2, (i + 1) % segments + cs + 2][::-j]) - # Create the cylinder side indices + # create the cylinder side indices for i in range(segments): index1 = len(cap_vertices) + i + segments index2 = len(cap_vertices) + ((i + 1) % segments) + segments From 276ce36a61715d0a99ce8b2d7e8c77c76b05fb98 Mon Sep 17 00:00:00 2001 From: Eric Shi Date: Tue, 12 Dec 2023 16:49:24 -0800 Subject: [PATCH 32/50] Fix multi-gpu synchronization issue in sparse.py --- warp/sparse.py | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/warp/sparse.py b/warp/sparse.py index 70d831596..148064f28 100644 --- a/warp/sparse.py +++ b/warp/sparse.py @@ -1,9 +1,9 @@ -from typing import Tuple, Any, Optional, Union, TypeVar, Generic +from typing import Any, Generic, Optional, Tuple, TypeVar, Union import warp as wp import warp.types -from warp.types import Matrix, Vector, Rows, Cols, Scalar, Array import warp.utils +from warp.types import Array, Cols, Matrix, Rows, Scalar, Vector # typing hints @@ -54,7 +54,7 @@ def block_size(self) -> int: @property def shape(self) -> Tuple[int, int]: - """Shape of the matrix, i.e. number of rows/columns of blocks times number of rows/columsn per block""" + """Shape of the matrix, i.e. number of rows/columns of blocks times number of rows/columns per block""" block_shape = self.block_shape return (self.nrow * block_shape[0], self.ncol * block_shape[1]) @@ -193,7 +193,7 @@ def bsr_set_from_triplets( elif values.ndim == 3: if values.shape[1:] != dest.block_shape: raise ValueError( - f"Last two dimensions in values array ({values.shape[1:]}) shoudl correspond to matrix block shape {(dest.block_shape)})" + f"Last two dimensions in values array ({values.shape[1:]}) should correspond to matrix block shape {(dest.block_shape)})" ) if warp.types.type_scalar_type(values.dtype) != dest.scalar_type: @@ -266,7 +266,7 @@ def bsr_assign(dest: BsrMatrix[BlockType[Rows, Cols, Scalar]], src: BsrMatrix[Bl def bsr_copy(A: BsrMatrix, scalar_type: Optional[Scalar] = None): - """Returns a copy of matrix ``A``, possibly chaning its scalar type. + """Returns a copy of matrix ``A``, possibly changing its scalar type. Args: scalar_type: If provided, the returned matrix will use this scalar type instead of the one from `A`. @@ -992,7 +992,7 @@ def bsr_mm( # Get back total counts on host if device.is_cuda: wp.copy(dest=work_arrays._pinned_count_buffer, src=work_arrays._mm_row_counts, src_offset=z.nrow, count=1) - wp.synchronize_stream(wp.get_stream()) + wp.synchronize_stream(wp.get_stream(device)) mm_nnz = int(work_arrays._pinned_count_buffer.numpy()[0]) else: mm_nnz = int(work_arrays._mm_row_counts.numpy()[z.nrow]) From c19a704864e269f4d1244032e5e9e4d89e311844 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Thu, 26 Oct 2023 15:23:00 +1300 Subject: [PATCH 33/50] Add operators with scalar as the dividend --- warp/builtins.py | 21 +++++++++++++++++ warp/native/exports.h | 51 +++++++++++++++++++++++++++++++++++++++++ warp/native/mat.h | 33 ++++++++++++++++++++++++-- warp/native/quat.h | 19 +++++++++++++++ warp/native/vec.h | 50 ++++++++++++++++++++++++++++++++++++++++ warp/tests/test_mat.py | 28 ++++++++++++++++++++++ warp/tests/test_quat.py | 28 ++++++++++++++++++++++ warp/tests/test_vec.py | 28 ++++++++++++++++++++++ warp/types.py | 16 ++----------- 9 files changed, 258 insertions(+), 16 deletions(-) diff --git a/warp/builtins.py b/warp/builtins.py index c7eb52014..0e72173a7 100644 --- a/warp/builtins.py +++ b/warp/builtins.py @@ -3228,6 +3228,13 @@ def mul_matmat_value_func(arg_types, kwds, _): doc="", group="Operators", ) +add_builtin( + "div", + input_types={"x": Scalar, "y": vector(length=Any, dtype=Scalar)}, + value_func=scalar_mul_value_func(vector(length=Any, dtype=Scalar)), + doc="", + group="Operators", +) add_builtin( "div", input_types={"x": matrix(shape=(Any, Any), dtype=Scalar), "y": Scalar}, @@ -3235,6 +3242,13 @@ def mul_matmat_value_func(arg_types, kwds, _): doc="", group="Operators", ) +add_builtin( + "div", + input_types={"x": Scalar, "y": matrix(shape=(Any, Any), dtype=Scalar)}, + value_func=scalar_mul_value_func(matrix(shape=(Any, Any), dtype=Scalar)), + doc="", + group="Operators", +) add_builtin( "div", input_types={"x": quaternion(dtype=Scalar), "y": Scalar}, @@ -3242,6 +3256,13 @@ def mul_matmat_value_func(arg_types, kwds, _): doc="", group="Operators", ) +add_builtin( + "div", + input_types={"x": Scalar, "y": quaternion(dtype=Scalar)}, + value_func=scalar_mul_value_func(quaternion(dtype=Scalar)), + doc="", + group="Operators", +) add_builtin( "floordiv", diff --git a/warp/native/exports.h b/warp/native/exports.h index 78b2f14d2..931680e4c 100644 --- a/warp/native/exports.h +++ b/warp/native/exports.h @@ -1302,6 +1302,42 @@ WP_API void builtin_div_vec4ul_uint64(vec4ul x, uint64 y, vec4ul* ret) { *ret = WP_API void builtin_div_vec2ub_uint8(vec2ub x, uint8 y, vec2ub* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_vec3ub_uint8(vec3ub x, uint8 y, vec3ub* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_vec4ub_uint8(vec4ub x, uint8 y, vec4ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_vec2h(float16 x, vec2h y, vec2h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_vec3h(float16 x, vec3h y, vec3h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_vec4h(float16 x, vec4h y, vec4h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_spatial_vectorh(float16 x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_vec2f(float32 x, vec2f y, vec2f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_vec3f(float32 x, vec3f y, vec3f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_vec4f(float32 x, vec4f y, vec4f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_spatial_vectorf(float32 x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_vec2d(float64 x, vec2d y, vec2d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_vec3d(float64 x, vec3d y, vec3d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_vec4d(float64 x, vec4d y, vec4d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_spatial_vectord(float64 x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int16_vec2s(int16 x, vec2s y, vec2s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int16_vec3s(int16 x, vec3s y, vec3s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int16_vec4s(int16 x, vec4s y, vec4s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int32_vec2i(int32 x, vec2i y, vec2i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int32_vec3i(int32 x, vec3i y, vec3i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int32_vec4i(int32 x, vec4i y, vec4i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int64_vec2l(int64 x, vec2l y, vec2l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int64_vec3l(int64 x, vec3l y, vec3l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int64_vec4l(int64 x, vec4l y, vec4l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int8_vec2b(int8 x, vec2b y, vec2b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int8_vec3b(int8 x, vec3b y, vec3b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int8_vec4b(int8 x, vec4b y, vec4b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint16_vec2us(uint16 x, vec2us y, vec2us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint16_vec3us(uint16 x, vec3us y, vec3us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint16_vec4us(uint16 x, vec4us y, vec4us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint32_vec2ui(uint32 x, vec2ui y, vec2ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint32_vec3ui(uint32 x, vec3ui y, vec3ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint32_vec4ui(uint32 x, vec4ui y, vec4ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint64_vec2ul(uint64 x, vec2ul y, vec2ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint64_vec3ul(uint64 x, vec3ul y, vec3ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint64_vec4ul(uint64 x, vec4ul y, vec4ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint8_vec2ub(uint8 x, vec2ub y, vec2ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint8_vec3ub(uint8 x, vec3ub y, vec3ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint8_vec4ub(uint8 x, vec4ub y, vec4ub* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_mat22h_float16(mat22h x, float16 y, mat22h* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_mat33h_float16(mat33h x, float16 y, mat33h* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_mat44h_float16(mat44h x, float16 y, mat44h* ret) { *ret = wp::div(x, y); } @@ -1314,9 +1350,24 @@ WP_API void builtin_div_mat22d_float64(mat22d x, float64 y, mat22d* ret) { *ret WP_API void builtin_div_mat33d_float64(mat33d x, float64 y, mat33d* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_mat44d_float64(mat44d x, float64 y, mat44d* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_spatial_matrixd_float64(spatial_matrixd x, float64 y, spatial_matrixd* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_mat22h(float16 x, mat22h y, mat22h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_mat33h(float16 x, mat33h y, mat33h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_mat44h(float16 x, mat44h y, mat44h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_spatial_matrixh(float16 x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_mat22f(float32 x, mat22f y, mat22f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_mat33f(float32 x, mat33f y, mat33f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_mat44f(float32 x, mat44f y, mat44f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_spatial_matrixf(float32 x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_mat22d(float64 x, mat22d y, mat22d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_mat33d(float64 x, mat33d y, mat33d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_mat44d(float64 x, mat44d y, mat44d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_spatial_matrixd(float64 x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_quath_float16(quath x, float16 y, quath* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_quatf_float32(quatf x, float32 y, quatf* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_quatd_float64(quatd x, float64 y, quatd* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_quath(float16 x, quath y, quath* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_quatf(float32 x, quatf y, quatf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_quatd(float64 x, quatd y, quatd* ret) { *ret = wp::div(x, y); } WP_API void builtin_floordiv_float16_float16(float16 x, float16 y, float16* ret) { *ret = wp::floordiv(x, y); } WP_API void builtin_floordiv_float32_float32(float32 x, float32 y, float32* ret) { *ret = wp::floordiv(x, y); } WP_API void builtin_floordiv_float64_float64(float64 x, float64 y, float64* ret) { *ret = wp::floordiv(x, y); } diff --git a/warp/native/mat.h b/warp/native/mat.h index 40dfbdcc7..da3b9c9df 100644 --- a/warp/native/mat.h +++ b/warp/native/mat.h @@ -437,7 +437,22 @@ inline CUDA_CALLABLE mat_t div(const mat_t& a, T } } - return t; + return t; +} + +template +inline CUDA_CALLABLE mat_t div(Type b, const mat_t& a) +{ + mat_t t; + for (unsigned i=0; i < Rows; ++i) + { + for (unsigned j=0; j < Cols; ++j) + { + t.data[i][j] = b / a.data[i][j]; + } + } + + return t; } template @@ -452,7 +467,7 @@ inline CUDA_CALLABLE mat_t mul(const mat_t& a, T } } - return t; + return t; } template @@ -944,6 +959,20 @@ inline CUDA_CALLABLE void adj_div(const mat_t& a, Type s, mat_t< } } +template +inline CUDA_CALLABLE void adj_div(Type s, const mat_t& a, Type& adj_s, mat_t& adj_a, const mat_t& adj_ret) +{ + adj_s -= tensordot(a , adj_ret)/ (s * s); // - a / s^2 + + for (unsigned i=0; i < Rows; ++i) + { + for (unsigned j=0; j < Cols; ++j) + { + adj_a.data[i][j] += s / adj_ret.data[i][j]; + } + } +} + template inline CUDA_CALLABLE void adj_mul(const mat_t& a, Type b, mat_t& adj_a, Type& adj_b, const mat_t& adj_ret) { diff --git a/warp/native/quat.h b/warp/native/quat.h index c554e243c..dc55b0f1b 100644 --- a/warp/native/quat.h +++ b/warp/native/quat.h @@ -225,12 +225,24 @@ inline CUDA_CALLABLE quat_t div(quat_t q, Type s) return quat_t(q.x/s, q.y/s, q.z/s, q.w/s); } +template +inline CUDA_CALLABLE quat_t div(Type s, quat_t q) +{ + return quat_t(s/q.x, s/q.y, s/q.z, s/q.w); +} + template inline CUDA_CALLABLE quat_t operator / (quat_t a, Type s) { return div(a,s); } +template +inline CUDA_CALLABLE quat_t operator / (Type s, quat_t a) +{ + return div(s,a); +} + template inline CUDA_CALLABLE quat_t operator*(Type s, const quat_t& a) { @@ -613,6 +625,13 @@ inline CUDA_CALLABLE void adj_div(quat_t a, Type s, quat_t& adj_a, T adj_a += adj_ret / s; } +template +inline CUDA_CALLABLE void adj_div(Type s, quat_t a, Type& adj_s, quat_t& adj_a, const quat_t& adj_ret) +{ + adj_s -= dot(a, adj_ret)/ (s * s); // - a / s^2 + adj_a += s / adj_ret; +} + template inline CUDA_CALLABLE void adj_quat_rotate(const quat_t& q, const vec_t<3,Type>& p, quat_t& adj_q, vec_t<3,Type>& adj_p, const vec_t<3,Type>& adj_ret) { diff --git a/warp/native/vec.h b/warp/native/vec.h index e5abeca9b..52840f71c 100644 --- a/warp/native/vec.h +++ b/warp/native/vec.h @@ -284,12 +284,41 @@ inline CUDA_CALLABLE vec_t<2, Type> div(vec_t<2, Type> a, Type s) return vec_t<2, Type>(a.c[0]/s,a.c[1]/s); } +template +inline CUDA_CALLABLE vec_t div(Type s, vec_t a) +{ + vec_t ret; + for (unsigned i=0; i < Length; ++i) + { + ret[i] = s / a[i]; + } + return ret; +} + +template +inline CUDA_CALLABLE vec_t<3, Type> div(Type s, vec_t<3, Type> a) +{ + return vec_t<3, Type>(s/a.c[0],s/a.c[1],s/a.c[2]); +} + +template +inline CUDA_CALLABLE vec_t<2, Type> div(Type s, vec_t<2, Type> a) +{ + return vec_t<2, Type>(s/a.c[0],s/a.c[1]); +} + template inline CUDA_CALLABLE vec_t operator / (vec_t a, Type s) { return div(a,s); } +template +inline CUDA_CALLABLE vec_t operator / (Type s, vec_t a) +{ + return div(s, a); +} + // component wise division template inline CUDA_CALLABLE vec_t cw_div(vec_t a, vec_t b) @@ -734,6 +763,27 @@ inline CUDA_CALLABLE void adj_div(vec_t a, Type s, vec_t +inline CUDA_CALLABLE void adj_div(Type s, vec_t a, Type& adj_s, vec_t& adj_a, const vec_t& adj_ret) +{ + + adj_s -= dot(a , adj_ret)/ (s * s); // - a / s^2 + + for( unsigned i=0; i < Length; ++i ) + { + adj_a[i] += s / adj_ret[i]; + } + +#if FP_CHECK + if (!isfinite(a) || !isfinite(s) || !isfinite(adj_a) || !isfinite(adj_s) || !isfinite(adj_ret)) + { + // \TODO: How shall we implement this error message? + // printf("adj_div((%f %f %f %f), %f, (%f %f %f %f), %f, (%f %f %f %f)\n", a.x, a.y, a.z, a.w, s, adj_a.x, adj_a.y, adj_a.z, adj_a.w, adj_s, adj_ret.x, adj_ret.y, adj_ret.z, adj_ret.w); + assert(0); + } +#endif +} + template inline CUDA_CALLABLE void adj_cw_div(vec_t a, vec_t b, vec_t& ret, vec_t& adj_a, vec_t& adj_b, const vec_t& adj_ret) { adj_a += cw_div(adj_ret, b); diff --git a/warp/tests/test_mat.py b/warp/tests/test_mat.py index 10d3b0dea..e74748fbc 100644 --- a/warp/tests/test_mat.py +++ b/warp/tests/test_mat.py @@ -159,6 +159,31 @@ def test_components(test, device, dtype): test.assertEqual(m[1, 2], 18) +def test_py_arithmetic_ops(test, device, dtype): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def make_mat(*args): + if wptype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(tuple(wptype._type_(x).value for x in row) for row in args) + + return args + + mat_cls = wp.mat((3, 3), wptype) + + m = mat_cls(((-1, 2, 3), (4, -5, 6), (7, 8, -9))) + test.assertSequenceEqual(+m, make_mat((-1, 2, 3), (4, -5, 6), (7, 8, -9))) + test.assertSequenceEqual(-m, make_mat((1, -2, -3), (-4, 5, -6), (-7, -8, 9))) + test.assertSequenceEqual(m + mat_cls((5, 5, 5) * 3), make_mat((4, 7, 8), (9, 0, 11), (12, 13, -4))) + test.assertSequenceEqual(m - mat_cls((5, 5, 5) * 3), make_mat((-6, -3, -2), (-1, -10, 1), (2, 3, -14))) + + m = mat_cls(((2, 4, 6), (8, 10, 12), (14, 16, 18))) + test.assertSequenceEqual(m * wptype(2), make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) + test.assertSequenceEqual(wptype(2) * m, make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) + test.assertSequenceEqual(m / wptype(2), make_mat((1, 2, 3), (4, 5, 6), (7, 8, 9))) + test.assertSequenceEqual(wptype(5040) / m, make_mat((2520, 1260, 840), (630, 504, 420), (360, 315, 280))) + + def test_constants(test, device, dtype, register_kernels=False): wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) @@ -4412,6 +4437,9 @@ class TestMat(parent): ) for dtype in np_float_types: + add_function_test( + TestMat, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype + ) add_function_test_register_kernel( TestMat, f"test_quat_constructor_{dtype.__name__}", test_quat_constructor, devices=devices, dtype=dtype ) diff --git a/warp/tests/test_quat.py b/warp/tests/test_quat.py index ef415ebe6..b7828ece7 100644 --- a/warp/tests/test_quat.py +++ b/warp/tests/test_quat.py @@ -1932,6 +1932,31 @@ def test_constructor_default(): wp.expect_eq(qeye[3], 1.0) +def test_py_arithmetic_ops(test, device, dtype): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def make_quat(*args): + if wptype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(wptype._type_(x).value for x in args) + + return args + + quat_cls = wp.types.quaternion(wptype) + + v = quat_cls(1, -2, 3, -4) + test.assertSequenceEqual(+v, make_quat(1, -2, 3, -4)) + test.assertSequenceEqual(-v, make_quat(-1, 2, -3, 4)) + test.assertSequenceEqual(v + quat_cls(5, 5, 5, 5), make_quat(6, 3, 8, 1)) + test.assertSequenceEqual(v - quat_cls(5, 5, 5, 5), make_quat(-4, -7, -2, -9)) + + v = quat_cls(2, 4, 6, 8) + test.assertSequenceEqual(v * wptype(2), make_quat(4, 8, 12, 16)) + test.assertSequenceEqual(wptype(2) * v, make_quat(4, 8, 12, 16)) + test.assertSequenceEqual(v / wptype(2), make_quat(1, 2, 3, 4)) + test.assertSequenceEqual(wptype(24) / v, make_quat(12, 6, 4, 3)) + + def register(parent): devices = get_test_devices() @@ -2020,6 +2045,9 @@ class TestQuat(parent): add_function_test_register_kernel( TestQuat, f"test_quat_to_matrix_{dtype.__name__}", test_quat_to_matrix, devices=devices, dtype=dtype ) + add_function_test( + TestQuat, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype + ) return TestQuat diff --git a/warp/tests/test_vec.py b/warp/tests/test_vec.py index 362e0ead7..88f5d9d2d 100644 --- a/warp/tests/test_vec.py +++ b/warp/tests/test_vec.py @@ -176,6 +176,31 @@ def test_components(test, device, dtype): test.assertEqual(v[2], 15) +def test_py_arithmetic_ops(test, device, dtype): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def make_vec(*args): + if wptype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(wptype._type_(x).value for x in args) + + return args + + vec_cls = wp.vec(3, wptype) + + v = vec_cls(1, -2, 3) + test.assertSequenceEqual(+v, make_vec(1, -2, 3)) + test.assertSequenceEqual(-v, make_vec(-1, 2, -3)) + test.assertSequenceEqual(v + vec_cls(5, 5, 5), make_vec(6, 3, 8)) + test.assertSequenceEqual(v - vec_cls(5, 5, 5), make_vec(-4, -7, -2)) + + v = vec_cls(2, 4, 6) + test.assertSequenceEqual(v * wptype(2), make_vec(4, 8, 12)) + test.assertSequenceEqual(wptype(2) * v, make_vec(4, 8, 12)) + test.assertSequenceEqual(v / wptype(2), make_vec(1, 2, 3)) + test.assertSequenceEqual(wptype(24) / v, make_vec(12, 6, 4)) + + def test_anon_type_instance(test, device, dtype, register_kernels=False): rng = np.random.default_rng(123) @@ -3205,6 +3230,9 @@ class TestVec(parent): for dtype in np_scalar_types: add_function_test(TestVec, f"test_arrays_{dtype.__name__}", test_arrays, devices=devices, dtype=dtype) add_function_test(TestVec, f"test_components_{dtype.__name__}", test_components, devices=None, dtype=dtype) + add_function_test( + TestVec, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype + ) add_function_test_register_kernel( TestVec, f"test_constructors_{dtype.__name__}", test_constructors, devices=devices, dtype=dtype ) diff --git a/warp/types.py b/warp/types.py index 3e056174b..148109422 100644 --- a/warp/types.py +++ b/warp/types.py @@ -177,15 +177,9 @@ def __setattr__(self, name, value): def __add__(self, y): return warp.add(self, y) - def __radd__(self, y): - return warp.add(self, y) - def __sub__(self, y): return warp.sub(self, y) - def __rsub__(self, x): - return warp.sub(x, self) - def __mul__(self, y): return warp.mul(self, y) @@ -195,7 +189,7 @@ def __rmul__(self, x): def __truediv__(self, y): return warp.div(self, y) - def __rdiv__(self, x): + def __rtruediv__(self, x): return warp.div(x, self) def __pos__(self): @@ -293,15 +287,9 @@ def __init__(self, *args): def __add__(self, y): return warp.add(self, y) - def __radd__(self, y): - return warp.add(self, y) - def __sub__(self, y): return warp.sub(self, y) - def __rsub__(self, x): - return warp.sub(x, self) - def __mul__(self, y): return warp.mul(self, y) @@ -317,7 +305,7 @@ def __rmatmul__(self, x): def __truediv__(self, y): return warp.div(self, y) - def __rdiv__(self, x): + def __rtruediv__(self, x): return warp.div(x, self) def __pos__(self): From 579683b236da2f29b7c88371f2c0f5514ffbed41 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Tue, 31 Oct 2023 14:31:19 +1300 Subject: [PATCH 34/50] Implement the vector @ matrix operator --- warp/builtins.py | 24 ++++++ warp/native/exports.h | 12 +++ warp/native/mat.h | 18 ++++ warp/tests/test_ctypes.py | 28 ++++--- warp/tests/test_mat.py | 171 ++++++++++++++++++++++++++++++++++++++ 5 files changed, 241 insertions(+), 12 deletions(-) diff --git a/warp/builtins.py b/warp/builtins.py index 0e72173a7..b1072779e 100644 --- a/warp/builtins.py +++ b/warp/builtins.py @@ -3106,6 +3106,23 @@ def mul_matvec_value_func(arg_types, kwds, _): return vector(length=arg_types[0]._shape_[0], dtype=arg_types[0]._wp_scalar_type_) +def mul_vecmat_value_func(arg_types, kwds, _): + if arg_types is None: + return vector(length=Any, dtype=Scalar) + + if arg_types[1]._wp_scalar_type_ != arg_types[0]._wp_scalar_type_: + raise RuntimeError( + f"Can't multiply vector and matrix with different types {arg_types[1]._wp_scalar_type_}, {arg_types[0]._wp_scalar_type_}" + ) + + if arg_types[1]._shape_[0] != arg_types[0]._length_: + raise RuntimeError( + f"Can't multiply vector with length {arg_types[0]._length_} and matrix of shape {arg_types[1]._shape_}" + ) + + return vector(length=arg_types[1]._shape_[1], dtype=arg_types[1]._wp_scalar_type_) + + def mul_matmat_value_func(arg_types, kwds, _): if arg_types is None: return matrix(length=Any, dtype=Scalar) @@ -3180,6 +3197,13 @@ def mul_matmat_value_func(arg_types, kwds, _): doc="", group="Operators", ) +add_builtin( + "mul", + input_types={"x": vector(length=Any, dtype=Scalar), "y": matrix(shape=(Any, Any), dtype=Scalar)}, + value_func=mul_vecmat_value_func, + doc="", + group="Operators", +) add_builtin( "mul", input_types={"x": matrix(shape=(Any, Any), dtype=Scalar), "y": matrix(shape=(Any, Any), dtype=Scalar)}, diff --git a/warp/native/exports.h b/warp/native/exports.h index 931680e4c..fa35feff6 100644 --- a/warp/native/exports.h +++ b/warp/native/exports.h @@ -1223,6 +1223,18 @@ WP_API void builtin_mul_mat22d_vec2d(mat22d x, vec2d y, vec2d* ret) { *ret = wp: WP_API void builtin_mul_mat33d_vec3d(mat33d x, vec3d y, vec3d* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mul_mat44d_vec4d(mat44d x, vec4d y, vec4d* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mul_spatial_matrixd_spatial_vectord(spatial_matrixd x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2h_mat22h(vec2h x, mat22h y, vec2h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3h_mat33h(vec3h x, mat33h y, vec3h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4h_mat44h(vec4h x, mat44h y, vec4h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectorh_spatial_matrixh(spatial_vectorh x, spatial_matrixh y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2f_mat22f(vec2f x, mat22f y, vec2f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3f_mat33f(vec3f x, mat33f y, vec3f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4f_mat44f(vec4f x, mat44f y, vec4f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectorf_spatial_matrixf(spatial_vectorf x, spatial_matrixf y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2d_mat22d(vec2d x, mat22d y, vec2d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3d_mat33d(vec3d x, mat33d y, vec3d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4d_mat44d(vec4d x, mat44d y, vec4d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectord_spatial_matrixd(spatial_vectord x, spatial_matrixd y, spatial_vectord* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mul_mat22h_mat22h(mat22h x, mat22h y, mat22h* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mul_mat33h_mat33h(mat33h x, mat33h y, mat33h* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mul_mat44h_mat44h(mat44h x, mat44h y, mat44h* ret) { *ret = wp::mul(x, y); } diff --git a/warp/native/mat.h b/warp/native/mat.h index da3b9c9df..42cf586f6 100644 --- a/warp/native/mat.h +++ b/warp/native/mat.h @@ -500,6 +500,17 @@ inline CUDA_CALLABLE vec_t mul(const mat_t& a, const return r; } +template +inline CUDA_CALLABLE vec_t mul(const vec_t& b, const mat_t& a) +{ + vec_t r = a.get_row(0)*b[0]; + for( unsigned i=1; i < Rows; ++i ) + { + r += a.get_row(i)*b[i]; + } + return r; +} + template inline CUDA_CALLABLE mat_t mul(const mat_t& a, const mat_t& b) { @@ -1006,6 +1017,13 @@ inline CUDA_CALLABLE void adj_mul(const mat_t& a, const vec_t +inline CUDA_CALLABLE void adj_mul(const vec_t& b, const mat_t& a, vec_t& adj_b, mat_t& adj_a, const vec_t& adj_ret) +{ + adj_a += outer(b, adj_ret); + adj_b += mul(adj_ret, transpose(a)); +} + template inline CUDA_CALLABLE void adj_mul(const mat_t& a, const mat_t& b, mat_t& adj_a, mat_t& adj_b, const mat_t& adj_ret) { diff --git a/warp/tests/test_ctypes.py b/warp/tests/test_ctypes.py index 63e6e92ca..9717f3496 100644 --- a/warp/tests/test_ctypes.py +++ b/warp/tests/test_ctypes.py @@ -24,11 +24,11 @@ def add_vec2(dest: wp.array(dtype=wp.vec2), c: wp.vec2): @wp.kernel -def transform_vec2(dest: wp.array(dtype=wp.vec2), m: wp.mat22, v: wp.vec2): +def transform_vec2(dest_right: wp.array(dtype=wp.vec2), dest_left: wp.array(dtype=wp.vec2), m: wp.mat22, v: wp.vec2): tid = wp.tid() - p = wp.mul(m, v) - dest[tid] = p + dest_right[tid] = wp.mul(m, v) + dest_left[tid] = wp.mul(v, m) @wp.kernel @@ -38,11 +38,11 @@ def add_vec3(dest: wp.array(dtype=wp.vec3), c: wp.vec3): @wp.kernel -def transform_vec3(dest: wp.array(dtype=wp.vec3), m: wp.mat33, v: wp.vec3): +def transform_vec3(dest_right: wp.array(dtype=wp.vec3), dest_left: wp.array(dtype=wp.vec3), m: wp.mat33, v: wp.vec3): tid = wp.tid() - p = wp.mul(m, v) - dest[tid] = p + dest_right[tid] = wp.mul(m, v) + dest_left[tid] = wp.mul(v, m) @wp.kernel @@ -63,12 +63,14 @@ def test_vec2_arg(test, device, n): def test_vec2_transform(test, device, n): - dest = wp.zeros(n=n, dtype=wp.vec2, device=device) + dest_right = wp.zeros(n=n, dtype=wp.vec2, device=device) + dest_left = wp.zeros(n=n, dtype=wp.vec2, device=device) c = np.array((1.0, 2.0)) m = np.array(((3.0, -1.0), (2.5, 4.0))) - wp.launch(transform_vec2, dim=n, inputs=[dest, m, c], device=device) - test.assertTrue(np.array_equal(dest.numpy(), np.tile(m @ c, (n, 1)))) + wp.launch(transform_vec2, dim=n, inputs=[dest_right, dest_left, m, c], device=device) + test.assertTrue(np.array_equal(dest_right.numpy(), np.tile(m @ c, (n, 1)))) + test.assertTrue(np.array_equal(dest_left.numpy(), np.tile(c @ m, (n, 1)))) def test_vec3_arg(test, device, n): @@ -80,12 +82,14 @@ def test_vec3_arg(test, device, n): def test_vec3_transform(test, device, n): - dest = wp.zeros(n=n, dtype=wp.vec3, device=device) + dest_right = wp.zeros(n=n, dtype=wp.vec3, device=device) + dest_left = wp.zeros(n=n, dtype=wp.vec3, device=device) c = np.array((1.0, 2.0, 3.0)) m = np.array(((1.0, 2.0, 3.0), (4.0, 5.0, 6.0), (7.0, 8.0, 9.0))) - wp.launch(transform_vec3, dim=n, inputs=[dest, m, c], device=device) - test.assertTrue(np.array_equal(dest.numpy(), np.tile(m @ c, (n, 1)))) + wp.launch(transform_vec3, dim=n, inputs=[dest_right, dest_left, m, c], device=device) + test.assertTrue(np.array_equal(dest_right.numpy(), np.tile(m @ c, (n, 1)))) + test.assertTrue(np.array_equal(dest_left.numpy(), np.tile(c @ m, (n, 1)))) def test_transform_multiply(test, device, n): diff --git a/warp/tests/test_mat.py b/warp/tests/test_mat.py index e74748fbc..321bc1cf9 100644 --- a/warp/tests/test_mat.py +++ b/warp/tests/test_mat.py @@ -169,19 +169,35 @@ def make_mat(*args): return args + def make_vec(*args): + if wptype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(wptype._type_(x).value for x in args) + + return args + mat_cls = wp.mat((3, 3), wptype) + vec_cls = wp.vec(3, wptype) m = mat_cls(((-1, 2, 3), (4, -5, 6), (7, 8, -9))) test.assertSequenceEqual(+m, make_mat((-1, 2, 3), (4, -5, 6), (7, 8, -9))) test.assertSequenceEqual(-m, make_mat((1, -2, -3), (-4, 5, -6), (-7, -8, 9))) test.assertSequenceEqual(m + mat_cls((5, 5, 5) * 3), make_mat((4, 7, 8), (9, 0, 11), (12, 13, -4))) test.assertSequenceEqual(m - mat_cls((5, 5, 5) * 3), make_mat((-6, -3, -2), (-1, -10, 1), (2, 3, -14))) + test.assertSequenceEqual(m * vec_cls(5, 5, 5), make_vec(20, 25, 30)) + test.assertSequenceEqual(m @ vec_cls(5, 5, 5), make_vec(20, 25, 30)) + test.assertSequenceEqual(vec_cls(5, 5, 5) * m, make_vec(50, 25, 0)) + test.assertSequenceEqual(vec_cls(5, 5, 5) @ m, make_vec(50, 25, 0)) m = mat_cls(((2, 4, 6), (8, 10, 12), (14, 16, 18))) test.assertSequenceEqual(m * wptype(2), make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) test.assertSequenceEqual(wptype(2) * m, make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) test.assertSequenceEqual(m / wptype(2), make_mat((1, 2, 3), (4, 5, 6), (7, 8, 9))) test.assertSequenceEqual(wptype(5040) / m, make_mat((2520, 1260, 840), (630, 504, 420), (360, 315, 280))) + test.assertSequenceEqual(m * vec_cls(5, 5, 5), make_vec(60, 150, 240)) + test.assertSequenceEqual(m @ vec_cls(5, 5, 5), make_vec(60, 150, 240)) + test.assertSequenceEqual(vec_cls(5, 5, 5) * m, make_vec(120, 150, 180)) + test.assertSequenceEqual(vec_cls(5, 5, 5) @ m, make_vec(120, 150, 180)) def test_constants(test, device, dtype, register_kernels=False): @@ -1600,6 +1616,153 @@ def check_mat_vec_mul( idx = idx + 1 +def test_vecmat_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 2.0e-2, + np.float32: 5.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat23 = wp.types.matrix(shape=(2, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_vec_mat_mul( + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v32: wp.array(dtype=vec2), + m2: wp.array(dtype=mat22), + m3: wp.array(dtype=mat33), + m4: wp.array(dtype=mat44), + m5: wp.array(dtype=mat55), + m23: wp.array(dtype=mat23), + outcomponents: wp.array(dtype=wptype), + ): + v2result = v2[0] * m2[0] + v3result = v3[0] * m3[0] + v4result = v4[0] * m4[0] + v5result = v5[0] * m5[0] + v32result = v32[0] * m23[0] + v2result_2 = v2[0] @ m2[0] + v3result_2 = v3[0] @ m3[0] + v4result_2 = v4[0] @ m4[0] + v5result_2 = v5[0] @ m5[0] + v32result_2 = v32[0] @ m23[0] + + idx = 0 + + # multiply outputs by 2 so we've got something to backpropagate: + for i in range(2): + outcomponents[idx] = wptype(2) * v2result[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v3result[i] + idx = idx + 1 + + for i in range(4): + outcomponents[idx] = wptype(2) * v4result[i] + idx = idx + 1 + + for i in range(5): + outcomponents[idx] = wptype(2) * v5result[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v32result[i] + idx = idx + 1 + + for i in range(2): + outcomponents[idx] = wptype(2) * v2result_2[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v3result_2[i] + idx = idx + 1 + + for i in range(4): + outcomponents[idx] = wptype(2) * v4result_2[i] + idx = idx + 1 + + for i in range(5): + outcomponents[idx] = wptype(2) * v5result_2[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v32result_2[i] + idx = idx + 1 + + kernel = getkernel(check_vec_mat_mul, suffix=dtype.__name__) + + if register_kernels: + return + + v2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) + v32 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + m23 = wp.array(randvals(rng, [1, 2, 3], dtype), dtype=mat23, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * (2 + 3 + 4 + 5 + 3), dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m23], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:2], 2 * np.matmul(v2.numpy()[0], m2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[2:5], 2 * np.matmul(v3.numpy()[0], m3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[5:9], 2 * np.matmul(v4.numpy()[0], m4.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[9:14], 2 * np.matmul(v5.numpy()[0], m5.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[14:17], 2 * np.matmul(v32.numpy()[0], m23.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[17:19], 2 * np.matmul(v2.numpy()[0], m2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[19:22], 2 * np.matmul(v3.numpy()[0], m3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[22:26], 2 * np.matmul(v4.numpy()[0], m4.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[26:31], 2 * np.matmul(v5.numpy()[0], m5.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[31:34], 2 * np.matmul(v32.numpy()[0], m23.numpy()[0]), tol=5 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, inmat, invec in [(2, m2, v2), (3, m3, v3), (4, m4, v4), (5, m5, v5), (3, m23, v32)]: + for i in range(dim): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m23], + outputs=[outcomponents], + device=device, + ) + wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) + tape.backward(loss=out) + + assert_np_equal(tape.gradients[invec].numpy()[0], 2 * inmat.numpy()[0, :, i], tol=2 * tol) + expectedresult = np.zeros(inmat.dtype._shape_, dtype=dtype) + expectedresult[:, i] = 2 * invec.numpy()[0] + assert_np_equal(tape.gradients[inmat].numpy()[0], expectedresult, tol=2 * tol) + + tape.zero() + + idx = idx + 1 + + def test_matmat_multiplication(test, device, dtype, register_kernels=False): rng = np.random.default_rng(123) @@ -4165,6 +4328,7 @@ def test_constructors_explicit_precision(): mat32d = wp.mat(shape=(3, 2), dtype=wp.float64) + @wp.kernel def test_matrix_constructor_value_func(): a = wp.mat22() @@ -4389,6 +4553,13 @@ class TestMat(parent): devices=devices, dtype=dtype, ) + add_function_test_register_kernel( + TestMat, + f"test_vecmat_multiplication_{dtype.__name__}", + test_vecmat_multiplication, + devices=devices, + dtype=dtype, + ) add_function_test_register_kernel( TestMat, f"test_matmat_multiplication_{dtype.__name__}", From d7ec437bb5833b15a0b1f55fab79f49c36d6de60 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Wed, 1 Nov 2023 15:31:14 +1300 Subject: [PATCH 35/50] Fix `float16` types being interpreted as `ushort` --- warp/context.py | 14 ++++++++++---- 1 file changed, 10 insertions(+), 4 deletions(-) diff --git a/warp/context.py b/warp/context.py index c1ccc20ee..514302485 100644 --- a/warp/context.py +++ b/warp/context.py @@ -244,7 +244,10 @@ class ValueArg(ctypes.Structure): else: try: # try to pack as a scalar type - params.append(arg_type._type_(a)) + if arg_type == warp.types.float16: + params.append(arg_type._type_(warp.types.float_to_half_bits(a))) + else: + params.append(arg_type._type_(a)) except Exception: raise RuntimeError( f"Error calling function {f.key}, unable to pack function parameter type {type(a)} for param {arg_name}, expected {arg_type}" @@ -264,10 +267,11 @@ def type_ctype(dtype): # scalar type return dtype._type_ - value_type = type_ctype(f.value_func(None, None, None)) + value_type = f.value_func(None, None, None) + value_ctype = type_ctype(value_type) # construct return value (passed by address) - ret = value_type() + ret = value_ctype() ret_addr = ctypes.c_void_p(ctypes.addressof(ret)) params.append(ret_addr) @@ -275,9 +279,11 @@ def type_ctype(dtype): c_func = getattr(warp.context.runtime.core, f.mangled_name) c_func(*params) - if issubclass(value_type, ctypes.Array) or issubclass(value_type, ctypes.Structure): + if issubclass(value_ctype, ctypes.Array) or issubclass(value_ctype, ctypes.Structure): # return vector types as ctypes return ret + elif value_type == warp.types.float16: + return warp.types.half_bits_to_float(ret.value) # return scalar types as int/float return ret.value From 9c8bc86fac9a53bc2c99e6a720d1213528b3a687 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Wed, 6 Dec 2023 16:34:55 -0500 Subject: [PATCH 36/50] Fix support for function calls in range() Support for the `type()` operator in kernels introduced a regression for `range()` expressions that contain function calls. In the case of e.g. `wp.min()` the full function name is not an `ast.Name` but rather an `ast.Attribute`, and in the case of just `min()` we should not immediately treat it as an invalid operator but continue parsing it as a potential builtin function call. --- warp/codegen.py | 15 ++++----------- warp/tests/test_codegen.py | 34 ++++++++++++++++++++++++++++++++++ warp/tests/test_generics.py | 2 +- 3 files changed, 39 insertions(+), 12 deletions(-) diff --git a/warp/codegen.py b/warp/codegen.py index b04f74e46..4dd04fec7 100644 --- a/warp/codegen.py +++ b/warp/codegen.py @@ -1463,7 +1463,7 @@ def eval_num(adj, a): # try and resolve the expression to an object # e.g.: wp.constant in the globals scope - obj, path = adj.resolve_static_expression(a) + obj, _ = adj.resolve_static_expression(a) if isinstance(obj, Var) and obj.constant is not None: obj = obj.constant @@ -1630,7 +1630,7 @@ def emit_Call(adj, node): if not isinstance(func, warp.context.Function): if len(path) == 0: - raise WarpCodegenError(f"Unrecognized syntax for function call, path not valid: '{node.func}'") + raise WarpCodegenError(f"Unknown function or operator: '{node.func.func.id}'") attr = path[-1] caller = func @@ -2027,16 +2027,11 @@ def resolve_static_expression(adj, root_node, eval_types=True): attributes.append(node.attr) node = node.value - if eval_types and isinstance(node, ast.Call): + if eval_types and isinstance(node, ast.Call) and isinstance(node.func, ast.Name): # support for operators returning modules # i.e. operator_name(*operator_args).x.y.z operator_args = node.args - operator_name = getattr(node.func, "id", None) - - if operator_name is None: - raise WarpCodegenError( - f"Invalid operator call syntax, expected a plain name, got {ast.dump(node.func, annotate_fields=False)}" - ) + operator_name = node.func.id if operator_name == "type": if len(operator_args) != 1: @@ -2061,8 +2056,6 @@ def resolve_static_expression(adj, root_node, eval_types=True): else: raise WarpCodegenError(f"Cannot deduce the type of {var}") - raise WarpCodegenError(f"Unknown operator '{operator_name}'") - # reverse list since ast presents it backward order path = [*reversed(attributes)] if isinstance(node, ast.Name): diff --git a/warp/tests/test_codegen.py b/warp/tests/test_codegen.py index 5c0d0deef..a078e5e76 100644 --- a/warp/tests/test_codegen.py +++ b/warp/tests/test_codegen.py @@ -317,6 +317,33 @@ def test_range_constant_dynamic_nested(m: int): wp.expect_eq(s, N * m * N) +@wp.kernel +def test_range_expression(): + idx = 1 + batch_size = 100 + + a = wp.float(0.0) + c = wp.float(1.0) + + # constant expression with a function + for i in range(4 * idx, wp.min(4 * idx + 4, batch_size)): + a += c + + for i in range(4 * idx, min(4 * idx + 4, batch_size)): + a += c + + tid = wp.tid() + + # dynamic expression with a function + for i in range(4 * idx, wp.min(4 * idx, tid + 1000)): + a += c + + for i in range(4 * idx, min(4 * idx, tid + 1000)): + a += c + + wp.expect_eq(a, 8.0) + + def test_unresolved_func(test, device): # kernel with unresolved function must be in a separate module, otherwise the current module would fail to load from warp.tests.test_unresolved_func import unresolved_func_kernel @@ -450,6 +477,13 @@ class TestCodeGen(parent): inputs=[4], devices=devices, ) + add_kernel_test( + TestCodeGen, + name="test_range_expression", + kernel=test_range_expression, + dim=1, + devices=devices, + ) add_kernel_test(TestCodeGen, name="test_while_zero", kernel=test_while, dim=1, inputs=[0], devices=devices) add_kernel_test(TestCodeGen, name="test_while_positive", kernel=test_while, dim=1, inputs=[16], devices=devices) diff --git a/warp/tests/test_generics.py b/warp/tests/test_generics.py index 33d58029e..dcddea20c 100644 --- a/warp/tests/test_generics.py +++ b/warp/tests/test_generics.py @@ -463,7 +463,7 @@ def kernel(): i = wp.tid() _ = typez(i)(0) - with test.assertRaisesRegex(RuntimeError, r"Unknown operator 'typez'$"): + with test.assertRaisesRegex(RuntimeError, r"Unknown function or operator: 'typez'$"): wp.launch( kernel, dim=1, From d9d9670e6692b94c0790492178cc58378deac969 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Wed, 8 Nov 2023 11:25:31 +1300 Subject: [PATCH 37/50] Improve native built-ins overload resolution Python types such as `int` and `float` are strictly resolving to `wp.int32` and `wp.float32`, which might require users to be more explicit in some code paths that were working until now. For example, calls like `wp.mul(np.array((1.0, 2.0, 3.0)), 1.23)` won't work anymore since the default float type of NumPy is `np.float64`, which isn't compatibles with `1.23`'s `wp.float32`. As a result, users are now required to either call something like `wp.mul(np.array((1.0, 2.0, 3.0), dtype=np.float32), 1.23)` or `wp.mul(np.array((1.0, 2.0, 3.0)), wp.float64(1.23))`. Additionally, array types such as lists, tuples, NumPy arrays, and others, are now matched by correctly preserving the precision of their element type. However, using Warp types such as `wp.vec`, `wp.mat`, `wp.quat`, or `wp.transform`, is preferred, so support for non-Warp array types is now marked as deprecated and will be dropped in the future. --- warp/context.py | 323 +++--- warp/tests/test_all.py | 2 + warp/tests/test_builtins_resolution.py | 1374 ++++++++++++++++++++++++ warp/tests/test_types.py | 221 +++- warp/types.py | 12 + 5 files changed, 1784 insertions(+), 148 deletions(-) create mode 100644 warp/tests/test_builtins_resolution.py diff --git a/warp/context.py b/warp/context.py index 514302485..1b788d79a 100644 --- a/warp/context.py +++ b/warp/context.py @@ -178,118 +178,16 @@ def __call__(self, *args, **kwargs): # from within a kernel (experimental). if self.is_builtin() and self.mangled_name: - for f in self.overloads: - if f.generic: + # For each of this function's existing overloads, we attempt to pack + # the given arguments into the C types expected by the corresponding + # parameters, and we rinse and repeat until we get a match. + for overload in self.overloads: + if overload.generic: continue - # try and find builtin in the warp.dll - if not hasattr(warp.context.runtime.core, f.mangled_name): - raise RuntimeError( - f"Couldn't find function {self.key} with mangled name {f.mangled_name} in the Warp native library" - ) - - try: - # try and pack args into what the function expects - params = [] - for i, (arg_name, arg_type) in enumerate(f.input_types.items()): - a = args[i] - - # try to convert to a value type (vec3, mat33, etc) - if issubclass(arg_type, ctypes.Array): - # wrap the arg_type (which is an ctypes.Array) in a structure - # to ensure parameter is passed to the .dll by value rather than reference - class ValueArg(ctypes.Structure): - _fields_ = [("value", arg_type)] - - x = ValueArg() - - # force conversion to ndarray first (handles tuple / list, Gf.Vec3 case) - if isinstance(a, ctypes.Array) is False: - # assume you want the float32 version of the function so it doesn't just - # grab an override for a random data type: - if arg_type._type_ != ctypes.c_float: - raise RuntimeError( - f"Error calling function '{f.key}', parameter for argument '{arg_name}' does not have c_float type." - ) - - a = np.array(a) - - # flatten to 1D array - v = a.flatten() - if len(v) != arg_type._length_: - raise RuntimeError( - f"Error calling function '{f.key}', parameter for argument '{arg_name}' has length {len(v)}, but expected {arg_type._length_}. Could not convert parameter to {arg_type}." - ) - - for i in range(arg_type._length_): - x.value[i] = v[i] - - else: - # already a built-in type, check it matches - if not warp.types.types_equal(type(a), arg_type): - raise RuntimeError( - f"Error calling function '{f.key}', parameter for argument '{arg_name}' has type '{type(a)}' but expected '{arg_type}'" - ) - - if isinstance(a, arg_type): - x.value = a - else: - # Cast the value to its argument type to make sure that it can be assigned to the field of the `ValueArg` struct. - # This could error otherwise when, for example, the field type is set to `vec3i` while the value is of type - # `vector(length=3, dtype=int)`, even though both types are semantically identical. - x.value = arg_type(a) - - params.append(x) - - else: - try: - # try to pack as a scalar type - if arg_type == warp.types.float16: - params.append(arg_type._type_(warp.types.float_to_half_bits(a))) - else: - params.append(arg_type._type_(a)) - except Exception: - raise RuntimeError( - f"Error calling function {f.key}, unable to pack function parameter type {type(a)} for param {arg_name}, expected {arg_type}" - ) - - # returns the corresponding ctype for a scalar or vector warp type - def type_ctype(dtype): - if dtype == float: - return ctypes.c_float - elif dtype == int: - return ctypes.c_int32 - elif issubclass(dtype, ctypes.Array): - return dtype - elif issubclass(dtype, ctypes.Structure): - return dtype - else: - # scalar type - return dtype._type_ - - value_type = f.value_func(None, None, None) - value_ctype = type_ctype(value_type) - - # construct return value (passed by address) - ret = value_ctype() - ret_addr = ctypes.c_void_p(ctypes.addressof(ret)) - - params.append(ret_addr) - - c_func = getattr(warp.context.runtime.core, f.mangled_name) - c_func(*params) - - if issubclass(value_ctype, ctypes.Array) or issubclass(value_ctype, ctypes.Structure): - # return vector types as ctypes - return ret - elif value_type == warp.types.float16: - return warp.types.half_bits_to_float(ret.value) - - # return scalar types as int/float - return ret.value - except Exception: - # couldn't pack values to match this overload - continue + success, return_value = call_builtin(overload, *args) + if success: + return return_value # overload resolution or call failed raise RuntimeError( @@ -297,7 +195,7 @@ def type_ctype(dtype): f"the arguments '{', '.join(type(x).__name__ for x in args)}'" ) - elif hasattr(self, "user_overloads") and len(self.user_overloads): + if hasattr(self, "user_overloads") and len(self.user_overloads): # user-defined function with overloads if len(kwargs): @@ -306,28 +204,26 @@ def type_ctype(dtype): ) # try and find a matching overload - for f in self.user_overloads.values(): - if len(f.input_types) != len(args): + for overload in self.user_overloads.values(): + if len(overload.input_types) != len(args): continue - template_types = list(f.input_types.values()) - arg_names = list(f.input_types.keys()) + template_types = list(overload.input_types.values()) + arg_names = list(overload.input_types.keys()) try: # attempt to unify argument types with function template types warp.types.infer_argument_types(args, template_types, arg_names) - return f.func(*args) + return overload.func(*args) except Exception: continue raise RuntimeError(f"Error calling function '{self.key}', no overload found for arguments {args}") - else: - # user-defined function with no overloads + # user-defined function with no overloads + if self.func is None: + raise RuntimeError(f"Error calling function '{self.key}', function is undefined") - if self.func is None: - raise RuntimeError(f"Error calling function '{self.key}', function is undefined") - - # this function has no overloads, call it like a plain Python function - return self.func(*args, **kwargs) + # this function has no overloads, call it like a plain Python function + return self.func(*args, **kwargs) def is_builtin(self): return self.func is None @@ -444,6 +340,187 @@ def __repr__(self): return f"" +def call_builtin(func: Function, *params) -> Tuple[bool, Any]: + uses_non_warp_array_type = False + + # Retrieve the built-in function from Warp's dll. + c_func = getattr(warp.context.runtime.core, func.mangled_name) + + # Try gathering the parameters that the function expects and pack them + # into their corresponding C types. + c_params = [] + for i, (_, arg_type) in enumerate(func.input_types.items()): + param = params[i] + + try: + iter(param) + except TypeError: + is_array = False + else: + is_array = True + + if is_array: + if not issubclass(arg_type, ctypes.Array): + return (False, None) + + # The argument expects a built-in Warp type like a vector or a matrix. + # We need to wrap the given argument into a ctypes' structure + # to ensure that it's passed by value to the dll rather than by reference. + class Param(ctypes.Structure): + _fields_ = [("value", arg_type)] + + c_param = Param() + + if isinstance(param, ctypes.Array): + # The given parameter is also a built-in Warp type, so we only need + # to make sure that it matches with the argument. + if not warp.types.types_equal(type(param), arg_type): + return (False, None) + + if isinstance(param, arg_type): + c_param.value = param + else: + # Cast the value to its argument type to make sure that it + # can be assigned to the field of the `Param` struct. + # This could error otherwise when, for example, the field type + # is set to `vec3i` while the value is of type `vector(length=3, dtype=int)`, + # even though both types are semantically identical. + c_param.value = arg_type(param) + else: + # Flatten the parameter values into a flat 1-D array. + arr = [] + ndim = 1 + stack = [(0, param)] + while stack: + depth, elem = stack.pop(0) + try: + # If `elem` is a sequence, then it should be possible + # to add its elements to the stack for later processing. + stack.extend((depth + 1, x) for x in elem) + except TypeError: + # Since `elem` doesn't seem to be a sequence, + # we must have a leaf value that we need to add to our + # resulting array. + arr.append(elem) + ndim = max(depth, ndim) + + assert ndim > 0 + + # Ensure that if the given parameter value is, say, a 2-D array, + # then we try to resolve it against a matrix argument rather than + # a vector. + if ndim > len(arg_type._shape_): + return (False, None) + + elem_count = len(arr) + if elem_count != arg_type._length_: + return (False, None) + + # Retrieve the element type of the sequence while ensuring + # that it's homogeneous. + elem_type = type(arr[0]) + for i in range(1, elem_count): + if type(arr[i]) is not elem_type: + raise ValueError("All array elements must share the same type.") + + expected_elem_type = arg_type._wp_scalar_type_ + if not ( + elem_type is expected_elem_type + or (elem_type is float and expected_elem_type is warp.types.float32) + or (elem_type is int and expected_elem_type is warp.types.int32) + or ( + issubclass(elem_type, np.number) + and warp.types.np_dtype_to_warp_type[np.dtype(elem_type)] is expected_elem_type + ) + ): + # The parameter value has a type not matching the type defined + # for the corresponding argument. + return (False, None) + + if elem_type in warp.types.int_types: + # Pass the value through the expected integer type + # in order to evaluate any integer wrapping. + # For example `uint8(-1)` should result in the value `-255`. + arr = tuple(elem_type._type_(x.value).value for x in arr) + elif elem_type in warp.types.float_types: + # Extract the floating-point values. + arr = tuple(x.value for x in arr) + + if warp.types.type_is_matrix(arg_type): + rows, cols = arg_type._shape_ + for i in range(rows): + idx_start = i * cols + idx_end = idx_start + cols + c_param.value[i] = arr[idx_start:idx_end] + else: + c_param.value[:] = arr + + uses_non_warp_array_type = True + + c_params.append(c_param) + else: + if issubclass(arg_type, ctypes.Array): + return (False, None) + + if not ( + isinstance(param, arg_type) + or (type(param) is float and arg_type is warp.types.float32) + or (type(param) is int and arg_type is warp.types.int32) + or warp.types.np_dtype_to_warp_type.get(getattr(param, "dtype", None)) is arg_type + ): + return (False, None) + + if type(param) in warp.types.scalar_types: + param = param.value + + # try to pack as a scalar type + if arg_type == warp.types.float16: + c_params.append(arg_type._type_(warp.types.float_to_half_bits(param))) + else: + c_params.append(arg_type._type_(param)) + + # returns the corresponding ctype for a scalar or vector warp type + value_type = func.value_func(None, None, None) + if value_type == float: + value_ctype = ctypes.c_float + elif value_type == int: + value_ctype = ctypes.c_int32 + elif issubclass(value_type, (ctypes.Array, ctypes.Structure)): + value_ctype = value_type + else: + # scalar type + value_ctype = value_type._type_ + + # construct return value (passed by address) + ret = value_ctype() + ret_addr = ctypes.c_void_p(ctypes.addressof(ret)) + c_params.append(ret_addr) + + # Call the built-in function from Warp's dll. + c_func(*c_params) + + # TODO: uncomment when we have a way to print warning messages only once. + # if uses_non_warp_array_type: + # warp.utils.warn( + # "Support for built-in functions called with non-Warp array types, " + # "such as lists, tuples, NumPy arrays, and others, will be dropped " + # "in the future. Use a Warp type such as `wp.vec`, `wp.mat`, " + # "`wp.quat`, or `wp.transform`.", + # DeprecationWarning, + # stacklevel=3 + # ) + + if issubclass(value_ctype, ctypes.Array) or issubclass(value_ctype, ctypes.Structure): + # return vector types as ctypes + return (True, ret) + + if value_type == warp.types.float16: + return (True, warp.types.half_bits_to_float(ret.value)) + + # return scalar types as int/float + return (True, ret.value) + + class KernelHooks: def __init__(self, forward, backward): self.forward = forward diff --git a/warp/tests/test_all.py b/warp/tests/test_all.py index bbd014dff..812aef902 100644 --- a/warp/tests/test_all.py +++ b/warp/tests/test_all.py @@ -14,6 +14,7 @@ import warp.tests.test_array import warp.tests.test_atomic import warp.tests.test_bool +import warp.tests.test_builtins_resolution import warp.tests.test_bvh import warp.tests.test_closest_point_edge_edge import warp.tests.test_codegen @@ -85,6 +86,7 @@ def register_tests(parent): tests.append(warp.tests.test_mesh_query_aabb.register(parent)) tests.append(warp.tests.test_mesh_query_point.register(parent)) tests.append(warp.tests.test_mesh_query_ray.register(parent)) + tests.append(warp.tests.test_builtins_resolution.register(parent)) tests.append(warp.tests.test_bvh.register(parent)) tests.append(warp.tests.test_conditional.register(parent)) tests.append(warp.tests.test_operators.register(parent)) diff --git a/warp/tests/test_builtins_resolution.py b/warp/tests/test_builtins_resolution.py new file mode 100644 index 000000000..bfeb6fa2c --- /dev/null +++ b/warp/tests/test_builtins_resolution.py @@ -0,0 +1,1374 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +import contextlib +import unittest + +import numpy as np + +from warp.tests.test_base import * + + +wp.init() + + +def nps(dtype, value): + """Creates a NumPy scalar value based on the given data type.""" + # Workaround to avoid deprecation warning messages for integer overflows. + return np.array((value,)).astype(dtype)[0] + + +def npv(dtype, values): + """Creates a vector of NumPy scalar values based on the given data type.""" + return tuple(nps(dtype, x) for x in values) + + +def npm(dtype, dim, values): + """Creates a matrix of NumPy scalar values based on the given data type.""" + return tuple(npv(dtype, values[i * dim : (i + 1) * dim]) for i in range(dim)) + + +def wpv(dtype, values): + """Creates a vector of Warp scalar values based on the given data type.""" + return tuple(dtype(x) for x in values) + + +def wpm(dtype, dim, values): + """Creates a matrix of Warp scalar values based on the given data type.""" + return tuple(wpv(dtype, values[i * dim : (i + 1) * dim]) for i in range(dim)) + + +def test_int_arg_overflow(test, device): + value = -1234567890123456789 + + test.assertEqual(wp.invert(wp.int8(value)), 20) + test.assertEqual(wp.invert(wp.int16(value)), -32492) + test.assertEqual(wp.invert(wp.int32(value)), 2112454932) + test.assertEqual(wp.invert(wp.int64(value)), 1234567890123456788) + + test.assertEqual(wp.invert(wp.uint8(value)), 20) + test.assertEqual(wp.invert(wp.uint16(value)), 33044) + test.assertEqual(wp.invert(wp.uint32(value)), 2112454932) + test.assertEqual(wp.invert(wp.uint64(value)), 1234567890123456788) + + test.assertEqual(wp.invert(value), wp.invert(wp.int32(value))) + + +def test_float_arg_precision(test, device): + value = 1.23 + expected = 0.94248880193169748409 + + result = wp.sin(wp.float64(value)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.sin(wp.float32(value)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.sin(wp.float16(value)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + test.assertEqual(wp.sin(value), wp.sin(wp.float32(value))) + + +def test_int_int_args_overflow(test, device): + value = -1234567890 + + test.assertEqual(wp.mul(wp.int8(value), wp.int8(value)), 68) + test.assertEqual(wp.mul(wp.int16(value), wp.int16(value)), -3004) + test.assertEqual(wp.mul(wp.int32(value), wp.int32(value)), 304084036) + test.assertEqual(wp.mul(wp.int64(value), wp.int64(value)), 1524157875019052100) + + test.assertEqual(wp.mul(wp.uint8(value), wp.uint8(value)), 68) + test.assertEqual(wp.mul(wp.uint16(value), wp.uint16(value)), 62532) + test.assertEqual(wp.mul(wp.uint32(value), wp.uint32(value)), 304084036) + test.assertEqual(wp.mul(wp.uint64(value), wp.uint64(value)), 1524157875019052100) + + test.assertEqual(wp.mul(value, value), wp.mul(wp.int32(value), wp.int32(value))) + + +def test_mat22_arg_precision(test, device): + values = (1.23, 2.34, 3.45, 4.56) + values_2d = (values[0:2], values[2:4]) + expected = 5.78999999999999914735 + + result = wp.trace(wp.mat22d(*values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.trace(wp.mat22f(*values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.trace(wp.mat22h(*values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.trace(values), wp.trace(wp.mat22f(*values))) + test.assertEqual(wp.trace(values_2d), wp.trace(wp.mat22f(*values))) + + +def test_mat33_arg_precision(test, device): + values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) + values_2d = (values[0:3], values[3:6], values[6:9]) + expected = 15.91000000000000014211 + + result = wp.trace(wp.mat33d(*values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.trace(wp.mat33f(*values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.trace(wp.mat33h(*values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.trace(values), wp.trace(wp.mat33f(*values))) + test.assertEqual(wp.trace(values_2d), wp.trace(wp.mat33f(*values))) + + +def test_mat44_arg_precision(test, device): + values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01, 10.12, 11.23, 12.34, 13.45, 14.56, 15.67, 16.78) + values_2d = (values[0:4], values[4:8], values[8:12], values[12:16]) + expected = 36.02000000000000312639 + + result = wp.trace(wp.mat44d(*values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.trace(wp.mat44f(*values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.trace(wp.mat44h(*values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.trace(values), wp.trace(wp.mat44f(*values))) + test.assertEqual(wp.trace(values_2d), wp.trace(wp.mat44f(*values))) + + +def test_mat22_mat22_args_precision(test, device): + a_values = (0.12, 1.23, 0.12, 1.23) + a_values_2d = (a_values[0:2], a_values[2:4]) + b_values = (1.23, 0.12, 1.23, 0.12) + b_values_2d = (b_values[0:2], b_values[2:4]) + expected = 0.59039999999999992486 + + result = wp.ddot(wp.mat22d(*a_values), wp.mat22d(*b_values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.ddot(wp.mat22h(*a_values), wp.mat22h(*b_values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + test.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + test.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + test.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + + +def test_mat33_mat33_args_precision(test, device): + a_values = (0.12, 1.23, 2.34, 0.12, 1.23, 2.34, 0.12, 1.23, 2.34) + a_values_2d = (a_values[0:3], a_values[3:6], a_values[6:9]) + b_values = (2.34, 1.23, 0.12, 2.34, 1.23, 0.12, 2.34, 1.23, 0.12) + b_values_2d = (b_values[0:3], b_values[3:6], b_values[6:9]) + expected = 6.22350000000000047606 + + result = wp.ddot(wp.mat33d(*a_values), wp.mat33d(*b_values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.ddot(wp.mat33h(*a_values), wp.mat33h(*b_values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + test.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + test.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + test.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + + +def test_mat44_mat44_args(test, device): + a_values = (0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45) + a_values_2d = (a_values[0:4], a_values[4:8], a_values[8:12], a_values[12:16]) + b_values = (3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12) + b_values_2d = (b_values[0:4], b_values[4:8], b_values[8:12], b_values[12:16]) + expected = 26.33760000000000189857 + + result = wp.ddot(wp.mat44d(*a_values), wp.mat44d(*b_values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.ddot(wp.mat44h(*a_values), wp.mat44h(*b_values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + test.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + test.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + test.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + + +def test_mat22_float_args_precision(test, device): + a_values = (1.23, 2.34, 3.45, 4.56) + a_values_2d = (a_values[0:2], a_values[2:4]) + b_value = 0.12 + expected_00 = 0.14759999999999998122 + expected_01 = 0.28079999999999999405 + expected_10 = 0.41399999999999997913 + expected_11 = 0.54719999999999990870 + + result = wp.mul(wp.mat22d(*a_values), wp.float64(b_value)) + test.assertAlmostEqual(result[0][0], expected_00, places=12) + test.assertAlmostEqual(result[0][1], expected_01, places=12) + test.assertAlmostEqual(result[1][0], expected_10, places=12) + test.assertAlmostEqual(result[1][1], expected_11, places=12) + + result = wp.mul(wp.mat22f(*a_values), wp.float32(b_value)) + test.assertNotAlmostEqual(result[0][0], expected_00, places=12) + test.assertNotAlmostEqual(result[0][1], expected_01, places=12) + test.assertNotAlmostEqual(result[1][0], expected_10, places=12) + test.assertNotAlmostEqual(result[1][1], expected_11, places=12) + test.assertAlmostEqual(result[0][0], expected_00, places=5) + test.assertAlmostEqual(result[0][1], expected_01, places=5) + test.assertAlmostEqual(result[1][0], expected_10, places=5) + test.assertAlmostEqual(result[1][1], expected_11, places=5) + + result = wp.mul(wp.mat22h(*a_values), wp.float16(b_value)) + test.assertNotAlmostEqual(result[0][0], expected_00, places=5) + test.assertNotAlmostEqual(result[0][1], expected_01, places=5) + test.assertNotAlmostEqual(result[1][0], expected_10, places=5) + test.assertNotAlmostEqual(result[1][1], expected_11, places=5) + test.assertAlmostEqual(result[0][0], expected_00, places=1) + test.assertAlmostEqual(result[0][1], expected_01, places=1) + test.assertAlmostEqual(result[1][0], expected_10, places=1) + test.assertAlmostEqual(result[1][1], expected_11, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + # Multiplying a 1-D tuple of length 4 is ambiguous because it could match + # either the `vec4f` or `mat22f` overload. As a result, only the 2-D variant + # of the tuple is expected to resolve correctly. + test.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat22f(*a_values), wp.float32(b_value))) + + +def test_mat33_float_args_precision(test, device): + a_values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) + a_values_2d = (a_values[0:3], a_values[3:6], a_values[6:9]) + b_value = 0.12 + expected_00 = 0.14759999999999998122 + expected_01 = 0.28079999999999999405 + expected_02 = 0.41399999999999997913 + expected_10 = 0.54719999999999990870 + expected_11 = 0.68040000000000000480 + expected_12 = 0.81359999999999998987 + expected_20 = 0.94679999999999997495 + expected_21 = 1.06800000000000006040 + expected_22 = 1.08119999999999993889 + + result = wp.mul(wp.mat33d(*a_values), wp.float64(b_value)) + test.assertAlmostEqual(result[0][0], expected_00, places=12) + test.assertAlmostEqual(result[0][1], expected_01, places=12) + test.assertAlmostEqual(result[0][2], expected_02, places=12) + test.assertAlmostEqual(result[1][0], expected_10, places=12) + test.assertAlmostEqual(result[1][1], expected_11, places=12) + test.assertAlmostEqual(result[1][2], expected_12, places=12) + test.assertAlmostEqual(result[2][0], expected_20, places=12) + test.assertAlmostEqual(result[2][1], expected_21, places=12) + test.assertAlmostEqual(result[2][2], expected_22, places=12) + + result = wp.mul(wp.mat33f(*a_values), wp.float32(b_value)) + test.assertNotAlmostEqual(result[0][0], expected_00, places=12) + test.assertNotAlmostEqual(result[0][1], expected_01, places=12) + test.assertNotAlmostEqual(result[0][2], expected_02, places=12) + test.assertNotAlmostEqual(result[1][0], expected_10, places=12) + test.assertNotAlmostEqual(result[1][1], expected_11, places=12) + test.assertNotAlmostEqual(result[1][2], expected_12, places=12) + test.assertNotAlmostEqual(result[2][0], expected_20, places=12) + test.assertNotAlmostEqual(result[2][1], expected_21, places=12) + test.assertNotAlmostEqual(result[2][2], expected_22, places=12) + test.assertAlmostEqual(result[0][0], expected_00, places=5) + test.assertAlmostEqual(result[0][1], expected_01, places=5) + test.assertAlmostEqual(result[0][2], expected_02, places=5) + test.assertAlmostEqual(result[1][0], expected_10, places=5) + test.assertAlmostEqual(result[1][1], expected_11, places=5) + test.assertAlmostEqual(result[1][2], expected_12, places=5) + test.assertAlmostEqual(result[2][0], expected_20, places=5) + test.assertAlmostEqual(result[2][1], expected_21, places=5) + test.assertAlmostEqual(result[2][2], expected_22, places=5) + + result = wp.mul(wp.mat33h(*a_values), wp.float16(b_value)) + test.assertNotAlmostEqual(result[0][0], expected_00, places=5) + test.assertNotAlmostEqual(result[0][1], expected_01, places=5) + test.assertNotAlmostEqual(result[0][2], expected_02, places=5) + test.assertNotAlmostEqual(result[1][0], expected_10, places=5) + test.assertNotAlmostEqual(result[1][1], expected_11, places=5) + test.assertNotAlmostEqual(result[1][2], expected_12, places=5) + test.assertNotAlmostEqual(result[2][0], expected_20, places=5) + test.assertNotAlmostEqual(result[2][1], expected_21, places=5) + test.assertNotAlmostEqual(result[2][2], expected_22, places=5) + test.assertAlmostEqual(result[0][0], expected_00, places=1) + test.assertAlmostEqual(result[0][1], expected_01, places=1) + test.assertAlmostEqual(result[0][2], expected_02, places=1) + test.assertAlmostEqual(result[1][0], expected_10, places=1) + test.assertAlmostEqual(result[1][1], expected_11, places=1) + test.assertAlmostEqual(result[1][2], expected_12, places=1) + test.assertAlmostEqual(result[2][0], expected_20, places=1) + test.assertAlmostEqual(result[2][1], expected_21, places=1) + test.assertAlmostEqual(result[2][2], expected_22, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.mat33f(*a_values), wp.float32(b_value))) + test.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat33f(*a_values), wp.float32(b_value))) + + +def test_mat44_float_args_precision(test, device): + a_values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01, 10.12, 11.23, 12.34, 13.45, 14.56, 15.67, 16.78) + a_values_2d = (a_values[0:4], a_values[4:8], a_values[8:12], a_values[12:16]) + b_value = 0.12 + expected_00 = 0.14759999999999998122 + expected_01 = 0.28079999999999999405 + expected_02 = 0.41399999999999997913 + expected_03 = 0.54719999999999990870 + expected_10 = 0.68040000000000000480 + expected_11 = 0.81359999999999998987 + expected_12 = 0.94679999999999997495 + expected_13 = 1.06800000000000006040 + expected_20 = 1.08119999999999993889 + expected_21 = 1.21439999999999992397 + expected_22 = 1.34759999999999990905 + expected_23 = 1.48079999999999989413 + expected_30 = 1.61399999999999987921 + expected_31 = 1.74720000000000008633 + expected_32 = 1.88039999999999984936 + expected_33 = 2.01360000000000027853 + + result = wp.mul(wp.mat44d(*a_values), wp.float64(b_value)) + test.assertAlmostEqual(result[0][0], expected_00, places=12) + test.assertAlmostEqual(result[0][1], expected_01, places=12) + test.assertAlmostEqual(result[0][2], expected_02, places=12) + test.assertAlmostEqual(result[0][3], expected_03, places=12) + test.assertAlmostEqual(result[1][0], expected_10, places=12) + test.assertAlmostEqual(result[1][1], expected_11, places=12) + test.assertAlmostEqual(result[1][2], expected_12, places=12) + test.assertAlmostEqual(result[1][3], expected_13, places=12) + test.assertAlmostEqual(result[2][0], expected_20, places=12) + test.assertAlmostEqual(result[2][1], expected_21, places=12) + test.assertAlmostEqual(result[2][2], expected_22, places=12) + test.assertAlmostEqual(result[2][3], expected_23, places=12) + test.assertAlmostEqual(result[3][0], expected_30, places=12) + test.assertAlmostEqual(result[3][1], expected_31, places=12) + test.assertAlmostEqual(result[3][2], expected_32, places=12) + test.assertAlmostEqual(result[3][3], expected_33, places=12) + + result = wp.mul(wp.mat44f(*a_values), wp.float32(b_value)) + test.assertNotAlmostEqual(result[0][0], expected_00, places=12) + test.assertNotAlmostEqual(result[0][1], expected_01, places=12) + test.assertNotAlmostEqual(result[0][2], expected_02, places=12) + test.assertNotAlmostEqual(result[0][3], expected_03, places=12) + test.assertNotAlmostEqual(result[1][0], expected_10, places=12) + test.assertNotAlmostEqual(result[1][1], expected_11, places=12) + test.assertNotAlmostEqual(result[1][2], expected_12, places=12) + test.assertNotAlmostEqual(result[1][3], expected_13, places=12) + test.assertNotAlmostEqual(result[2][0], expected_20, places=12) + test.assertNotAlmostEqual(result[2][1], expected_21, places=12) + test.assertNotAlmostEqual(result[2][2], expected_22, places=12) + test.assertNotAlmostEqual(result[2][3], expected_23, places=12) + test.assertNotAlmostEqual(result[3][0], expected_30, places=12) + test.assertNotAlmostEqual(result[3][1], expected_31, places=12) + test.assertNotAlmostEqual(result[3][2], expected_32, places=12) + test.assertNotAlmostEqual(result[3][3], expected_33, places=12) + test.assertAlmostEqual(result[0][0], expected_00, places=5) + test.assertAlmostEqual(result[0][1], expected_01, places=5) + test.assertAlmostEqual(result[0][2], expected_02, places=5) + test.assertAlmostEqual(result[0][3], expected_03, places=5) + test.assertAlmostEqual(result[1][0], expected_10, places=5) + test.assertAlmostEqual(result[1][1], expected_11, places=5) + test.assertAlmostEqual(result[1][2], expected_12, places=5) + test.assertAlmostEqual(result[1][3], expected_13, places=5) + test.assertAlmostEqual(result[2][0], expected_20, places=5) + test.assertAlmostEqual(result[2][1], expected_21, places=5) + test.assertAlmostEqual(result[2][2], expected_22, places=5) + test.assertAlmostEqual(result[2][3], expected_23, places=5) + test.assertAlmostEqual(result[3][0], expected_30, places=5) + test.assertAlmostEqual(result[3][1], expected_31, places=5) + test.assertAlmostEqual(result[3][2], expected_32, places=5) + test.assertAlmostEqual(result[3][3], expected_33, places=5) + + result = wp.mul(wp.mat44h(*a_values), wp.float16(b_value)) + test.assertNotAlmostEqual(result[0][0], expected_00, places=5) + test.assertNotAlmostEqual(result[0][1], expected_01, places=5) + test.assertNotAlmostEqual(result[0][2], expected_02, places=5) + test.assertNotAlmostEqual(result[0][3], expected_03, places=5) + test.assertNotAlmostEqual(result[1][0], expected_10, places=5) + test.assertNotAlmostEqual(result[1][1], expected_11, places=5) + test.assertNotAlmostEqual(result[1][2], expected_12, places=5) + test.assertNotAlmostEqual(result[1][3], expected_13, places=5) + test.assertNotAlmostEqual(result[2][0], expected_20, places=5) + test.assertNotAlmostEqual(result[2][1], expected_21, places=5) + test.assertNotAlmostEqual(result[2][2], expected_22, places=5) + test.assertNotAlmostEqual(result[2][3], expected_23, places=5) + test.assertNotAlmostEqual(result[3][0], expected_30, places=5) + test.assertNotAlmostEqual(result[3][1], expected_31, places=5) + test.assertNotAlmostEqual(result[3][2], expected_32, places=5) + test.assertNotAlmostEqual(result[3][3], expected_33, places=5) + test.assertAlmostEqual(result[0][0], expected_00, places=1) + test.assertAlmostEqual(result[0][1], expected_01, places=1) + test.assertAlmostEqual(result[0][2], expected_02, places=1) + test.assertAlmostEqual(result[0][3], expected_03, places=1) + test.assertAlmostEqual(result[1][0], expected_10, places=1) + test.assertAlmostEqual(result[1][1], expected_11, places=1) + test.assertAlmostEqual(result[1][2], expected_12, places=1) + test.assertAlmostEqual(result[1][3], expected_13, places=1) + test.assertAlmostEqual(result[2][0], expected_20, places=1) + test.assertAlmostEqual(result[2][1], expected_21, places=1) + test.assertAlmostEqual(result[2][2], expected_22, places=1) + test.assertAlmostEqual(result[2][3], expected_23, places=1) + test.assertAlmostEqual(result[3][0], expected_30, places=1) + test.assertAlmostEqual(result[3][1], expected_31, places=1) + test.assertAlmostEqual(result[3][2], expected_32, places=1) + test.assertAlmostEqual(result[3][3], expected_33, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.mat44f(*a_values), wp.float32(b_value))) + test.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat44f(*a_values), wp.float32(b_value))) + + +def test_vec2_arg_precision(test, device): + values = (1.23, 2.34) + expected = 2.64357712200722438922 + + result = wp.length(wp.vec2d(*values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.length(wp.vec2f(*values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.length(wp.vec2h(*values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.length(values), wp.length(wp.vec2f(*values))) + + +def test_vec2_arg_overflow(test, device): + values = (-1234567890, -1234567890) + + test.assertEqual(wp.length_sq(wp.vec2b(*values)), -120) + test.assertEqual(wp.length_sq(wp.vec2s(*values)), -6008) + test.assertEqual(wp.length_sq(wp.vec2i(*values)), 608168072) + test.assertEqual(wp.length_sq(wp.vec2l(*values)), 3048315750038104200) + + test.assertEqual(wp.length_sq(wp.vec2ub(*values)), 136) + test.assertEqual(wp.length_sq(wp.vec2us(*values)), 59528) + test.assertEqual(wp.length_sq(wp.vec2ui(*values)), 608168072) + test.assertEqual(wp.length_sq(wp.vec2ul(*values)), 3048315750038104200) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec2i(*values))) + + +def test_vec3_arg_precision(test, device): + values = (1.23, 2.34, 3.45) + expected = 4.34637780226247727455 + + result = wp.length(wp.vec3d(*values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.length(wp.vec3f(*values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.length(wp.vec3h(*values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.length(values), wp.length(wp.vec3f(*values))) + + +def test_vec3_arg_overflow(test, device): + values = (-1234567890, -1234567890, -1234567890) + + test.assertEqual(wp.length_sq(wp.vec3b(*values)), -52) + test.assertEqual(wp.length_sq(wp.vec3s(*values)), -9012) + test.assertEqual(wp.length_sq(wp.vec3i(*values)), 912252108) + test.assertEqual(wp.length_sq(wp.vec3l(*values)), 4572473625057156300) + + test.assertEqual(wp.length_sq(wp.vec3ub(*values)), 204) + test.assertEqual(wp.length_sq(wp.vec3us(*values)), 56524) + test.assertEqual(wp.length_sq(wp.vec3ui(*values)), 912252108) + test.assertEqual(wp.length_sq(wp.vec3ul(*values)), 4572473625057156300) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec3i(*values))) + + +def test_vec4_arg_precision(test, device): + values = (1.23, 2.34, 3.45, 4.56) + expected = 6.29957141399317777086 + + result = wp.length(wp.vec4d(*values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.length(wp.vec4f(*values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.length(wp.vec4h(*values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.length(values), wp.length(wp.vec4f(*values))) + + +def test_vec4_arg_overflow(test, device): + values = (-1234567890, -1234567890, -1234567890, -1234567890) + + test.assertEqual(wp.length_sq(wp.vec4b(*values)), 16) + test.assertEqual(wp.length_sq(wp.vec4s(*values)), -12016) + test.assertEqual(wp.length_sq(wp.vec4i(*values)), 1216336144) + test.assertEqual(wp.length_sq(wp.vec4l(*values)), 6096631500076208400) + + test.assertEqual(wp.length_sq(wp.vec4ub(*values)), 16) + test.assertEqual(wp.length_sq(wp.vec4us(*values)), 53520) + test.assertEqual(wp.length_sq(wp.vec4ui(*values)), 1216336144) + test.assertEqual(wp.length_sq(wp.vec4ul(*values)), 6096631500076208400) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec4i(*values))) + + +def test_vec2_vec2_args_precision(test, device): + a_values = (1.23, 2.34) + b_values = (3.45, 4.56) + expected = 14.91389999999999815827 + + result = wp.dot(wp.vec2d(*a_values), wp.vec2d(*b_values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.dot(wp.vec2f(*a_values), wp.vec2f(*b_values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.dot(wp.vec2h(*a_values), wp.vec2h(*b_values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec2f(*a_values), wp.vec2f(*b_values))) + + +def test_vec2_vec2_args_overflow(test, device): + values = (-1234567890, -1234567890) + + test.assertEqual(wp.dot(wp.vec2b(*values), wp.vec2b(*values)), -120) + test.assertEqual(wp.dot(wp.vec2s(*values), wp.vec2s(*values)), -6008) + test.assertEqual(wp.dot(wp.vec2i(*values), wp.vec2i(*values)), 608168072) + test.assertEqual(wp.dot(wp.vec2l(*values), wp.vec2l(*values)), 3048315750038104200) + + test.assertEqual(wp.dot(wp.vec2ub(*values), wp.vec2ub(*values)), 136) + test.assertEqual(wp.dot(wp.vec2us(*values), wp.vec2us(*values)), 59528) + test.assertEqual(wp.dot(wp.vec2ui(*values), wp.vec2ui(*values)), 608168072) + test.assertEqual(wp.dot(wp.vec2ul(*values), wp.vec2ul(*values)), 3048315750038104200) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.dot(values, values), wp.dot(wp.vec2i(*values), wp.vec2i(*values))) + + +def test_vec3_vec3_args_precision(test, device): + a_values = (1.23, 2.34, 3.45) + b_values = (4.56, 5.67, 6.78) + expected = 42.26760000000000161435 + + result = wp.dot(wp.vec3d(*a_values), wp.vec3d(*b_values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.dot(wp.vec3f(*a_values), wp.vec3f(*b_values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.dot(wp.vec3h(*a_values), wp.vec3h(*b_values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec3f(*a_values), wp.vec3f(*b_values))) + + +def test_vec3_vec3_args_overflow(test, device): + values = (-1234567890, -1234567890, -1234567890) + + test.assertEqual(wp.dot(wp.vec3b(*values), wp.vec3b(*values)), -52) + test.assertEqual(wp.dot(wp.vec3s(*values), wp.vec3s(*values)), -9012) + test.assertEqual(wp.dot(wp.vec3i(*values), wp.vec3i(*values)), 912252108) + test.assertEqual(wp.dot(wp.vec3l(*values), wp.vec3l(*values)), 4572473625057156300) + + test.assertEqual(wp.dot(wp.vec3ub(*values), wp.vec3ub(*values)), 204) + test.assertEqual(wp.dot(wp.vec3us(*values), wp.vec3us(*values)), 56524) + test.assertEqual(wp.dot(wp.vec3ui(*values), wp.vec3ui(*values)), 912252108) + test.assertEqual(wp.dot(wp.vec3ul(*values), wp.vec3ul(*values)), 4572473625057156300) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.dot(values, values), wp.dot(wp.vec3i(*values), wp.vec3i(*values))) + + +def test_vec4_vec4_args_precision(test, device): + a_values = (1.23, 2.34, 3.45, 4.56) + b_values = (5.67, 6.78, 7.89, 8.90) + expected = 90.64379999999999881766 + + result = wp.dot(wp.vec4d(*a_values), wp.vec4d(*b_values)) + test.assertAlmostEqual(result, expected, places=12) + + result = wp.dot(wp.vec4f(*a_values), wp.vec4f(*b_values)) + test.assertNotAlmostEqual(result, expected, places=12) + test.assertAlmostEqual(result, expected, places=5) + + result = wp.dot(wp.vec4h(*a_values), wp.vec4h(*b_values)) + test.assertNotAlmostEqual(result, expected, places=5) + test.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec4f(*a_values), wp.vec4f(*b_values))) + + +def test_vec4_vec4_args_overflow(test, device): + values = (-1234567890, -1234567890, -1234567890, -1234567890) + + test.assertEqual(wp.dot(wp.vec4b(*values), wp.vec4b(*values)), 16) + test.assertEqual(wp.dot(wp.vec4s(*values), wp.vec4s(*values)), -12016) + test.assertEqual(wp.dot(wp.vec4i(*values), wp.vec4i(*values)), 1216336144) + test.assertEqual(wp.dot(wp.vec4l(*values), wp.vec4l(*values)), 6096631500076208400) + + test.assertEqual(wp.dot(wp.vec4ub(*values), wp.vec4ub(*values)), 16) + test.assertEqual(wp.dot(wp.vec4us(*values), wp.vec4us(*values)), 53520) + test.assertEqual(wp.dot(wp.vec4ui(*values), wp.vec4ui(*values)), 1216336144) + test.assertEqual(wp.dot(wp.vec4ul(*values), wp.vec4ul(*values)), 6096631500076208400) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.dot(values, values), wp.dot(wp.vec4i(*values), wp.vec4i(*values))) + + +def test_vec2_float_args_precision(test, device): + a_values = (1.23, 2.34) + b_value = 3.45 + expected_x = 4.24350000000000004974 + expected_y = 8.07300000000000039790 + + result = wp.mul(wp.vec2d(*a_values), wp.float64(b_value)) + test.assertAlmostEqual(result[0], expected_x, places=12) + test.assertAlmostEqual(result[1], expected_y, places=12) + + result = wp.mul(wp.vec2f(*a_values), wp.float32(b_value)) + test.assertNotAlmostEqual(result[0], expected_x, places=12) + test.assertNotAlmostEqual(result[1], expected_y, places=12) + test.assertAlmostEqual(result[0], expected_x, places=5) + test.assertAlmostEqual(result[1], expected_y, places=5) + + result = wp.mul(wp.vec2h(*a_values), wp.float16(b_value)) + test.assertNotAlmostEqual(result[0], expected_x, places=5) + test.assertNotAlmostEqual(result[1], expected_y, places=5) + test.assertAlmostEqual(result[0], expected_x, places=1) + test.assertAlmostEqual(result[1], expected_y, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec2f(*a_values), wp.float32(b_value))) + + +def test_vec3_float_args_precision(test, device): + a_values = (1.23, 2.34, 3.45) + b_value = 4.56 + expected_x = 5.60879999999999956373 + expected_y = 10.67039999999999899671 + expected_z = 15.73199999999999931788 + + result = wp.mul(wp.vec3d(*a_values), wp.float64(b_value)) + test.assertAlmostEqual(result[0], expected_x, places=12) + test.assertAlmostEqual(result[1], expected_y, places=12) + test.assertAlmostEqual(result[2], expected_z, places=12) + + result = wp.mul(wp.vec3f(*a_values), wp.float32(b_value)) + test.assertNotAlmostEqual(result[0], expected_x, places=12) + test.assertNotAlmostEqual(result[1], expected_y, places=12) + test.assertNotAlmostEqual(result[2], expected_z, places=12) + test.assertAlmostEqual(result[0], expected_x, places=5) + test.assertAlmostEqual(result[1], expected_y, places=5) + test.assertAlmostEqual(result[2], expected_z, places=5) + + result = wp.mul(wp.vec3h(*a_values), wp.float16(b_value)) + test.assertNotAlmostEqual(result[0], expected_x, places=5) + test.assertNotAlmostEqual(result[1], expected_y, places=5) + test.assertNotAlmostEqual(result[2], expected_z, places=5) + test.assertAlmostEqual(result[0], expected_x, places=1) + test.assertAlmostEqual(result[1], expected_y, places=1) + test.assertAlmostEqual(result[2], expected_z, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec3f(*a_values), wp.float32(b_value))) + + +def test_vec4_float_args_precision(test, device): + a_values = (1.23, 2.34, 3.45, 4.56) + b_value = 5.67 + expected_x = 6.97409999999999996589 + expected_y = 13.26779999999999937188 + expected_z = 19.56150000000000233058 + expected_w = 25.85519999999999640750 + + result = wp.mul(wp.vec4d(*a_values), wp.float64(b_value)) + test.assertAlmostEqual(result[0], expected_x, places=12) + test.assertAlmostEqual(result[1], expected_y, places=12) + test.assertAlmostEqual(result[2], expected_z, places=12) + test.assertAlmostEqual(result[3], expected_w, places=12) + + result = wp.mul(wp.vec4f(*a_values), wp.float32(b_value)) + test.assertNotAlmostEqual(result[0], expected_x, places=12) + test.assertNotAlmostEqual(result[1], expected_y, places=12) + test.assertNotAlmostEqual(result[2], expected_z, places=12) + test.assertNotAlmostEqual(result[3], expected_w, places=12) + test.assertAlmostEqual(result[0], expected_x, places=5) + test.assertAlmostEqual(result[1], expected_y, places=5) + test.assertAlmostEqual(result[2], expected_z, places=5) + test.assertAlmostEqual(result[3], expected_w, places=5) + + result = wp.mul(wp.vec4h(*a_values), wp.float16(b_value)) + test.assertNotAlmostEqual(result[0], expected_x, places=5) + test.assertNotAlmostEqual(result[1], expected_y, places=5) + test.assertNotAlmostEqual(result[2], expected_z, places=5) + test.assertNotAlmostEqual(result[3], expected_w, places=5) + test.assertAlmostEqual(result[0], expected_x, places=1) + test.assertAlmostEqual(result[1], expected_y, places=1) + test.assertAlmostEqual(result[2], expected_z, places=1) + test.assertAlmostEqual(result[3], expected_w, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec4f(*a_values), wp.float32(b_value))) + + +def test_int_arg_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + value = -1234567890123456789 + expected = wp.invert(dtype(value)) + + test.assertEqual(wp.invert(nps(np_type, value)), expected) + + +def test_float_arg_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + value = 1.23 + expected = wp.sin(dtype(value)) + + test.assertEqual(wp.sin(nps(np_type, value)), expected) + + +def test_int_int_args_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + value = -1234567890 + expected = wp.mul(dtype(value), dtype(value)) + + test.assertEqual(wp.mul(dtype(value), dtype(value)), expected) + test.assertEqual(wp.mul(dtype(value), nps(np_type, value)), expected) + + test.assertEqual(wp.mul(nps(np_type, value), dtype(value)), expected) + test.assertEqual(wp.mul(nps(np_type, value), nps(np_type, value)), expected) + + if dtype is wp.int32: + test.assertEqual(wp.mul(dtype(value), value), expected) + test.assertEqual(wp.mul(nps(np_type, value), value), expected) + test.assertEqual(wp.mul(value, value), expected) + + test.assertEqual(wp.mul(value, dtype(value)), expected) + test.assertEqual(wp.mul(value, nps(np_type, value)), expected) + else: + with test.assertRaisesRegex( + RuntimeError, + rf"Couldn't find a function 'mul' compatible with " + rf"the arguments '{dtype.__name__}, int'$", + ): + wp.mul(dtype(value), value) + + with test.assertRaisesRegex( + RuntimeError, + rf"Couldn't find a function 'mul' compatible with " + rf"the arguments '{np_type.__name__}, int'$", + ): + wp.mul(nps(np_type, value), value) + + with test.assertRaisesRegex( + RuntimeError, + rf"Couldn't find a function 'mul' compatible with " + rf"the arguments 'int, {dtype.__name__}'$", + ): + wp.mul(value, dtype(value)) + + with test.assertRaisesRegex( + RuntimeError, + rf"Couldn't find a function 'mul' compatible with " + rf"the arguments 'int, {np_type.__name__}'$", + ): + wp.mul(value, nps(np_type, value)) + + +def test_mat_arg_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + mat_cls = wp.types.matrix((3, 3), dtype) + values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) + expected = wp.trace(mat_cls(*values)) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.trace(wpv(dtype, values)), expected) + test.assertEqual(wp.trace(wpm(dtype, 3, values)), expected) + test.assertEqual(wp.trace(npv(np_type, values)), expected) + test.assertEqual(wp.trace(npm(np_type, 3, values)), expected) + test.assertEqual(wp.trace(np.array(npv(np_type, values))), expected) + + +def test_mat_mat_args_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + mat_cls = wp.types.matrix((3, 3), dtype) + a_values = (0.12, 1.23, 2.34, 0.12, 1.23, 2.34, 0.12, 1.23, 2.34) + b_values = (2.34, 1.23, 0.12, 2.34, 1.23, 0.12, 2.34, 1.23, 0.12) + expected = wp.ddot(mat_cls(*a_values), mat_cls(*b_values)) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.ddot(mat_cls(*a_values), mat_cls(*b_values)), expected) + test.assertEqual(wp.ddot(mat_cls(*a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.ddot(mat_cls(*a_values), wpm(dtype, 3, b_values)), expected) + test.assertEqual(wp.ddot(mat_cls(*a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.ddot(mat_cls(*a_values), npm(np_type, 3, b_values)), expected) + test.assertEqual(wp.ddot(mat_cls(*a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.ddot(wpv(dtype, a_values), mat_cls(*b_values)), expected) + test.assertEqual(wp.ddot(wpv(dtype, a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.ddot(wpv(dtype, a_values), wpm(dtype, 3, b_values)), expected) + test.assertEqual(wp.ddot(wpv(dtype, a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.ddot(wpv(dtype, a_values), npm(np_type, 3, b_values)), expected) + test.assertEqual(wp.ddot(wpv(dtype, a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.ddot(wpm(dtype, 3, a_values), mat_cls(*b_values)), expected) + test.assertEqual(wp.ddot(wpm(dtype, 3, a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.ddot(wpm(dtype, 3, a_values), wpm(dtype, 3, b_values)), expected) + test.assertEqual(wp.ddot(wpm(dtype, 3, a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.ddot(wpm(dtype, 3, a_values), npm(np_type, 3, b_values)), expected) + test.assertEqual(wp.ddot(wpm(dtype, 3, a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.ddot(npv(np_type, a_values), mat_cls(*b_values)), expected) + test.assertEqual(wp.ddot(npv(np_type, a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.ddot(npv(np_type, a_values), wpm(dtype, 3, b_values)), expected) + test.assertEqual(wp.ddot(npv(np_type, a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.ddot(npv(np_type, a_values), npm(np_type, 3, b_values)), expected) + test.assertEqual(wp.ddot(npv(np_type, a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.ddot(npm(np_type, 3, a_values), mat_cls(*b_values)), expected) + test.assertEqual(wp.ddot(npm(np_type, 3, a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.ddot(npm(np_type, 3, a_values), wpm(dtype, 3, b_values)), expected) + test.assertEqual(wp.ddot(npm(np_type, 3, a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.ddot(npm(np_type, 3, a_values), npm(np_type, 3, b_values)), expected) + test.assertEqual(wp.ddot(npm(np_type, 3, a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.ddot(np.array(npv(np_type, a_values)), mat_cls(*b_values)), expected) + test.assertEqual(wp.ddot(np.array(npv(np_type, a_values)), wpv(dtype, b_values)), expected) + test.assertEqual(wp.ddot(np.array(npv(np_type, a_values)), wpm(dtype, 3, b_values)), expected) + test.assertEqual(wp.ddot(np.array(npv(np_type, a_values)), npv(np_type, b_values)), expected) + test.assertEqual(wp.ddot(np.array(npv(np_type, a_values)), npm(np_type, 3, b_values)), expected) + test.assertEqual(wp.ddot(np.array(npv(np_type, a_values)), np.array(npv(np_type, b_values))), expected) + + if dtype is wp.float32: + test.assertEqual(wp.ddot(mat_cls(*a_values), b_values), expected) + test.assertEqual(wp.ddot(wpv(dtype, a_values), b_values), expected) + test.assertEqual(wp.ddot(wpm(dtype, 3, a_values), b_values), expected) + test.assertEqual(wp.ddot(npv(np_type, a_values), b_values), expected) + test.assertEqual(wp.ddot(npm(np_type, 3, a_values), b_values), expected) + test.assertEqual(wp.ddot(a_values, b_values), expected) + test.assertEqual(wp.ddot(np.array(npv(np_type, a_values)), b_values), expected) + + test.assertEqual(wp.ddot(a_values, mat_cls(*b_values)), expected) + test.assertEqual(wp.ddot(a_values, wpv(dtype, b_values)), expected) + test.assertEqual(wp.ddot(a_values, wpm(dtype, 3, b_values)), expected) + test.assertEqual(wp.ddot(a_values, npv(np_type, b_values)), expected) + test.assertEqual(wp.ddot(a_values, npm(np_type, 3, b_values)), expected) + test.assertEqual(wp.ddot(a_values, np.array(npv(np_type, b_values))), expected) + else: + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'mat_t, tuple'$", + ): + wp.ddot(mat_cls(*a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(wpv(dtype, a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(wpm(dtype, 3, a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(npv(np_type, a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(npm(np_type, 3, a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'ndarray, tuple'$", + ): + wp.ddot(np.array(npv(np_type, a_values)), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, mat_t'$", + ): + wp.ddot(a_values, mat_cls(*b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(a_values, wpv(dtype, b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(a_values, wpm(dtype, 3, b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(a_values, npv(np_type, b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.ddot(a_values, npm(np_type, 3, b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'ddot' compatible with " + r"the arguments 'tuple, ndarray'$", + ): + wp.ddot(a_values, np.array(npv(np_type, b_values))) + + +def test_mat_float_args_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + mat_cls = wp.types.matrix((3, 3), dtype) + a_values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) + b_value = 0.12 + expected = wp.mul(mat_cls(*a_values), dtype(b_value)) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.mul(mat_cls(*a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(mat_cls(*a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(wpv(dtype, a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(wpv(dtype, a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(wpm(dtype, 3, a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(wpm(dtype, 3, a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(npv(np_type, a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(npv(np_type, a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(npm(np_type, 3, a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(npm(np_type, 3, a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(np.array(npv(np_type, a_values)), dtype(b_value)), expected) + test.assertEqual(wp.mul(np.array(npv(np_type, a_values)), nps(np_type, b_value)), expected) + + if dtype is wp.float32: + test.assertEqual(wp.mul(mat_cls(*a_values), b_value), expected) + test.assertEqual(wp.mul(wpv(dtype, a_values), b_value), expected) + test.assertEqual(wp.mul(wpm(dtype, 3, a_values), b_value), expected) + test.assertEqual(wp.mul(npv(np_type, a_values), b_value), expected) + test.assertEqual(wp.mul(npm(np_type, 3, a_values), b_value), expected) + test.assertEqual(wp.mul(a_values, b_value), expected) + test.assertEqual(wp.mul(np.array(npv(np_type, a_values)), b_value), expected) + + test.assertEqual(wp.mul(a_values, dtype(b_value)), expected) + test.assertEqual(wp.mul(a_values, nps(np_type, b_value)), expected) + else: + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'mat_t, float'$", + ): + wp.mul(mat_cls(*a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'tuple, float'$", + ): + wp.mul(wpv(dtype, a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'tuple, float'$", + ): + wp.mul(wpm(dtype, 3, a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'tuple, float'$", + ): + wp.mul(npv(np_type, a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'tuple, float'$", + ): + wp.mul(npm(np_type, 3, a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'ndarray, float'$", + ): + wp.mul(np.array(npv(np_type, a_values)), b_value) + + with test.assertRaisesRegex( + RuntimeError, + fr"Couldn't find a function 'mul' compatible with " + fr"the arguments 'tuple, {dtype.__name__}'$", + ): + wp.mul(a_values, dtype(b_value)) + + with test.assertRaisesRegex( + RuntimeError, + fr"Couldn't find a function 'mul' compatible with " + fr"the arguments 'tuple, {np_type.__name__}'$", + ): + wp.mul(a_values, nps(np_type, b_value)) + + +def test_vec_arg_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + vec_cls = wp.types.vector(3, dtype) + values = (1.23, 2.34, 3.45) + expected = wp.length(vec_cls(*values)) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertAlmostEqual(wp.length(wpv(dtype, values)), expected) + test.assertAlmostEqual(wp.length(npv(np_type, values)), expected) + test.assertAlmostEqual(wp.length(np.array(npv(np_type, values))), expected) + + +def test_vec_vec_args_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + vec_cls = wp.types.vector(3, dtype) + a_values = (1.23, 2.34, 3.45) + b_values = (4.56, 5.67, 6.78) + expected = wp.dot(vec_cls(*a_values), vec_cls(*b_values)) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.dot(vec_cls(*a_values), vec_cls(*b_values)), expected) + test.assertEqual(wp.dot(vec_cls(*a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.dot(vec_cls(*a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.dot(vec_cls(*a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.dot(wpv(dtype, a_values), vec_cls(*b_values)), expected) + test.assertEqual(wp.dot(wpv(dtype, a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.dot(wpv(dtype, a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.dot(wpv(dtype, a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.dot(npv(np_type, a_values), vec_cls(*b_values)), expected) + test.assertEqual(wp.dot(npv(np_type, a_values), wpv(dtype, b_values)), expected) + test.assertEqual(wp.dot(npv(np_type, a_values), npv(np_type, b_values)), expected) + test.assertEqual(wp.dot(npv(np_type, a_values), np.array(npv(np_type, b_values))), expected) + + test.assertEqual(wp.dot(np.array(npv(np_type, a_values)), vec_cls(*b_values)), expected) + test.assertEqual(wp.dot(np.array(npv(np_type, a_values)), wpv(dtype, b_values)), expected) + test.assertEqual(wp.dot(np.array(npv(np_type, a_values)), npv(np_type, b_values)), expected) + test.assertEqual(wp.dot(np.array(npv(np_type, a_values)), np.array(npv(np_type, b_values))), expected) + + if dtype is wp.float32: + test.assertEqual(wp.dot(vec_cls(*a_values), b_values), expected) + test.assertEqual(wp.dot(wpv(dtype, a_values), b_values), expected) + test.assertEqual(wp.dot(npv(np_type, a_values), b_values), expected) + test.assertEqual(wp.dot(a_values, b_values), expected) + test.assertEqual(wp.dot(np.array(npv(np_type, a_values)), b_values), expected) + + test.assertEqual(wp.dot(a_values, vec_cls(*b_values)), expected) + test.assertEqual(wp.dot(a_values, wpv(dtype, b_values)), expected) + test.assertEqual(wp.dot(a_values, npv(np_type, b_values)), expected) + test.assertEqual(wp.dot(a_values, np.array(npv(np_type, b_values))), expected) + else: + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'vec_t, tuple'$", + ): + wp.dot(vec_cls(*a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.dot(wpv(dtype, a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.dot(npv(np_type, a_values), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'ndarray, tuple'$", + ): + wp.dot(np.array(npv(np_type, a_values)), b_values) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'tuple, vec_t'$", + ): + wp.dot(a_values, vec_cls(*b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.dot(a_values, wpv(dtype, b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'tuple, tuple'$", + ): + wp.dot(a_values, npv(np_type, b_values)) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'dot' compatible with " + r"the arguments 'tuple, ndarray'$", + ): + wp.dot(a_values, np.array(npv(np_type, b_values))) + + +def test_vec_float_args_support(test, device, dtype): + np_type = wp.types.warp_type_to_np_dtype[dtype] + vec_cls = wp.types.vector(3, dtype) + a_values = (1.23, 2.34, 3.45) + b_value = 4.56 + expected = wp.mul(vec_cls(*a_values), dtype(b_value)) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + test.assertEqual(wp.mul(vec_cls(*a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(vec_cls(*a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(wpv(dtype, a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(wpv(dtype, a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(npv(np_type, a_values), dtype(b_value)), expected) + test.assertEqual(wp.mul(npv(np_type, a_values), nps(np_type, b_value)), expected) + + test.assertEqual(wp.mul(np.array(npv(np_type, a_values)), dtype(b_value)), expected) + test.assertEqual(wp.mul(np.array(npv(np_type, a_values)), nps(np_type, b_value)), expected) + + if dtype is wp.float32: + test.assertEqual(wp.mul(vec_cls(*a_values), b_value), expected) + test.assertEqual(wp.mul(wpv(dtype, a_values), b_value), expected) + test.assertEqual(wp.mul(npv(np_type, a_values), b_value), expected) + test.assertEqual(wp.mul(a_values, b_value), expected) + test.assertEqual(wp.mul(np.array(npv(np_type, a_values)), b_value), expected) + + test.assertEqual(wp.mul(a_values, dtype(b_value)), expected) + test.assertEqual(wp.mul(a_values, nps(np_type, b_value)), expected) + else: + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'vec_t, float'$", + ): + wp.mul(vec_cls(*a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'tuple, float'$", + ): + wp.mul(wpv(dtype, a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'tuple, float'$", + ): + wp.mul(npv(np_type, a_values), b_value) + + with test.assertRaisesRegex( + RuntimeError, + r"Couldn't find a function 'mul' compatible with " + r"the arguments 'ndarray, float'$", + ): + wp.mul(np.array(npv(np_type, a_values)), b_value) + + with test.assertRaisesRegex( + RuntimeError, + fr"Couldn't find a function 'mul' compatible with " + fr"the arguments 'tuple, {dtype.__name__}'$", + ): + wp.mul(a_values, dtype(b_value)) + + with test.assertRaisesRegex( + RuntimeError, + fr"Couldn't find a function 'mul' compatible with " + fr"the arguments 'tuple, {np_type.__name__}'$", + ): + wp.mul(a_values, nps(np_type, b_value)) + + +def register(parent): + class TestBuiltinsResolution(parent): + pass + + add_function_test(TestBuiltinsResolution, "test_int_arg_overflow", test_int_arg_overflow) + add_function_test(TestBuiltinsResolution, "test_float_arg_precision", test_float_arg_precision) + add_function_test(TestBuiltinsResolution, "test_int_int_args_overflow", test_int_int_args_overflow) + add_function_test(TestBuiltinsResolution, "test_mat22_arg_precision", test_mat22_arg_precision) + add_function_test(TestBuiltinsResolution, "test_mat33_arg_precision", test_mat33_arg_precision) + add_function_test(TestBuiltinsResolution, "test_mat44_arg_precision", test_mat44_arg_precision) + add_function_test(TestBuiltinsResolution, "test_mat22_mat22_args_precision", test_mat22_mat22_args_precision) + add_function_test(TestBuiltinsResolution, "test_mat33_mat33_args_precision", test_mat33_mat33_args_precision) + add_function_test(TestBuiltinsResolution, "test_mat44_mat44_args", test_mat44_mat44_args) + add_function_test(TestBuiltinsResolution, "test_mat22_float_args_precision", test_mat22_float_args_precision) + add_function_test(TestBuiltinsResolution, "test_mat33_float_args_precision", test_mat33_float_args_precision) + add_function_test(TestBuiltinsResolution, "test_mat44_float_args_precision", test_mat44_float_args_precision) + add_function_test(TestBuiltinsResolution, "test_vec2_arg_precision", test_vec2_arg_precision) + add_function_test(TestBuiltinsResolution, "test_vec2_arg_overflow", test_vec2_arg_overflow) + add_function_test(TestBuiltinsResolution, "test_vec3_arg_precision", test_vec3_arg_precision) + add_function_test(TestBuiltinsResolution, "test_vec3_arg_overflow", test_vec3_arg_overflow) + add_function_test(TestBuiltinsResolution, "test_vec4_arg_precision", test_vec4_arg_precision) + add_function_test(TestBuiltinsResolution, "test_vec4_arg_overflow", test_vec4_arg_overflow) + add_function_test(TestBuiltinsResolution, "test_vec2_vec2_args_precision", test_vec2_vec2_args_precision) + add_function_test(TestBuiltinsResolution, "test_vec2_vec2_args_overflow", test_vec2_vec2_args_overflow) + add_function_test(TestBuiltinsResolution, "test_vec3_vec3_args_precision", test_vec3_vec3_args_precision) + add_function_test(TestBuiltinsResolution, "test_vec3_vec3_args_overflow", test_vec3_vec3_args_overflow) + add_function_test(TestBuiltinsResolution, "test_vec4_vec4_args_precision", test_vec4_vec4_args_precision) + add_function_test(TestBuiltinsResolution, "test_vec4_vec4_args_overflow", test_vec4_vec4_args_overflow) + add_function_test(TestBuiltinsResolution, "test_vec2_float_args_precision", test_vec2_float_args_precision) + add_function_test(TestBuiltinsResolution, "test_vec3_float_args_precision", test_vec3_float_args_precision) + add_function_test(TestBuiltinsResolution, "test_vec4_float_args_precision", test_vec4_float_args_precision) + + for dtype in wp.types.int_types: + add_function_test( + TestBuiltinsResolution, + f"test_int_arg_support_{dtype.__name__}", + test_int_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_int_int_args_support_{dtype.__name__}", + test_int_int_args_support, + dtype=dtype, + ) + + for dtype in wp.types.float_types: + add_function_test( + TestBuiltinsResolution, + f"test_float_arg_support_{dtype.__name__}", + test_float_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_mat_arg_support_{dtype.__name__}", + test_mat_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_mat_mat_args_support_{dtype.__name__}", + test_mat_mat_args_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_mat_float_args_support_{dtype.__name__}", + test_mat_float_args_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_vec_arg_support_{dtype.__name__}", + test_vec_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_vec_vec_args_support_{dtype.__name__}", + test_vec_vec_args_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_vec_float_args_support_{dtype.__name__}", + test_vec_float_args_support, + dtype=dtype, + ) + + return TestBuiltinsResolution + + +if __name__ == "__main__": + wp.build.clear_kernel_cache() + _ = register(unittest.TestCase) + unittest.main(verbosity=2) diff --git a/warp/tests/test_types.py b/warp/tests/test_types.py index 424a68c4d..9d140367e 100644 --- a/warp/tests/test_types.py +++ b/warp/tests/test_types.py @@ -5,9 +5,6 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import contextlib -import io -import inspect import unittest from warp.tests.test_base import * @@ -44,39 +41,213 @@ def test_constant_error_invalid_type(test, device): wp.constant((1, 2, 3)) -def test_vector(test, device): - for dtype in (int, float, wp.float16): - vec_cls = wp.vec(3, dtype) +def test_vector(test, device, dtype): + def make_scalar(x): + # Cast to the correct integer type to simulate wrapping. + if dtype in wp.types.int_types: + return dtype._type_(x).value - v = vec_cls(1, 2, 3) - test.assertEqual(v[0], 1) - test.assertSequenceEqual(v[0:2], (1, 2)) - test.assertSequenceEqual(v, (1, 2, 3)) + return x - v[0] = -1 - test.assertEqual(v[0], -1) - test.assertSequenceEqual(v[0:2], (-1, 2)) - test.assertSequenceEqual(v, (-1, 2, 3)) + def make_vec(*args): + if dtype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(dtype._type_(x).value for x in args) - v[1:3] = (-2, -3) - test.assertEqual(v[0], -1) - test.assertSequenceEqual(v[0:2], (-1, -2)) - test.assertSequenceEqual(v, (-1, -2, -3)) + return args - v += vec_cls(1, 1, 1) - test.assertSequenceEqual(v, (0, -1, -2)) + vec3_cls = wp.vec(3, dtype) + vec4_cls = wp.vec(4, dtype) + + v = vec4_cls(1, 2, 3, 4) + test.assertEqual(v[0], make_scalar(1)) + test.assertEqual(v.x, make_scalar(1)) + test.assertEqual(v.y, make_scalar(2)) + test.assertEqual(v.z, make_scalar(3)) + test.assertEqual(v.w, make_scalar(4)) + test.assertSequenceEqual(v[0:2], make_vec(1, 2)) + test.assertSequenceEqual(v, make_vec(1, 2, 3, 4)) + + v[0] = -1 + test.assertEqual(v[0], make_scalar(-1)) + test.assertEqual(v.x, make_scalar(-1)) + test.assertEqual(v.y, make_scalar(2)) + test.assertEqual(v.z, make_scalar(3)) + test.assertEqual(v.w, make_scalar(4)) + test.assertSequenceEqual(v[0:2], make_vec(-1, 2)) + test.assertSequenceEqual(v, make_vec(-1, 2, 3, 4)) + + v[1:3] = (-2, -3) + test.assertEqual(v[0], make_scalar(-1)) + test.assertEqual(v.x, make_scalar(-1)) + test.assertEqual(v.y, make_scalar(-2)) + test.assertEqual(v.z, make_scalar(-3)) + test.assertEqual(v.w, make_scalar(4)) + test.assertSequenceEqual(v[0:2], make_vec(-1, -2)) + test.assertSequenceEqual(v, make_vec(-1, -2, -3, 4)) + + v.x = 1 + test.assertEqual(v[0], make_scalar(1)) + test.assertEqual(v.x, make_scalar(1)) + test.assertEqual(v.y, make_scalar(-2)) + test.assertEqual(v.z, make_scalar(-3)) + test.assertEqual(v.w, make_scalar(4)) + test.assertSequenceEqual(v[0:2], make_vec(1, -2)) + test.assertSequenceEqual(v, make_vec(1, -2, -3, 4)) + + v = vec3_cls(2, 4, 6) + test.assertSequenceEqual(+v, make_vec(2, 4, 6)) + test.assertSequenceEqual(-v, make_vec(-2, -4, -6)) + test.assertSequenceEqual(v + vec3_cls(1, 1, 1), make_vec(3, 5, 7)) + test.assertSequenceEqual(v - vec3_cls(1, 1, 1), make_vec(1, 3, 5)) + test.assertSequenceEqual(v * dtype(2), make_vec(4, 8, 12)) + test.assertSequenceEqual(dtype(2) * v, make_vec(4, 8, 12)) + test.assertSequenceEqual(v / dtype(2), make_vec(1, 2, 3)) + test.assertSequenceEqual(dtype(12) / v, make_vec(6, 3, 2)) + + +def test_matrix(test, device, dtype): + def make_scalar(x): + # Cast to the correct integer type to simulate wrapping. + if dtype in wp.types.int_types: + return dtype._type_(x).value + + return x + + def make_vec(*args): + if dtype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(dtype._type_(x).value for x in args) + + return args + + def make_mat(*args): + if dtype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(tuple(dtype._type_(x).value for x in row) for row in args) + + return args + + mat22_cls = wp.mat((2, 2), dtype) + mat33_cls = wp.mat((3, 3), dtype) + + m = mat33_cls(((1, 2, 3), (4, 5, 6), (7, 8, 9))) + test.assertEqual(m[0][0], make_scalar(1)) + test.assertEqual(m[0][1], make_scalar(2)) + test.assertEqual(m[0][2], make_scalar(3)) + test.assertEqual(m[1][0], make_scalar(4)) + test.assertEqual(m[1][1], make_scalar(5)) + test.assertEqual(m[1][2], make_scalar(6)) + test.assertEqual(m[2][0], make_scalar(7)) + test.assertEqual(m[2][1], make_scalar(8)) + test.assertEqual(m[2][2], make_scalar(9)) + test.assertEqual(m[0, 0], make_scalar(1)) + test.assertEqual(m[0, 1], make_scalar(2)) + test.assertEqual(m[0, 2], make_scalar(3)) + test.assertEqual(m[1, 0], make_scalar(4)) + test.assertEqual(m[1, 1], make_scalar(5)) + test.assertEqual(m[1, 2], make_scalar(6)) + test.assertEqual(m[2, 0], make_scalar(7)) + test.assertEqual(m[2, 1], make_scalar(8)) + test.assertEqual(m[2, 2], make_scalar(9)) + test.assertSequenceEqual(m[0], make_vec(1, 2, 3)) + test.assertSequenceEqual(m[1], make_vec(4, 5, 6)) + test.assertSequenceEqual(m[2], make_vec(7, 8, 9)) + test.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) + test.assertSequenceEqual(m[1][0:2], make_vec(4, 5)) + test.assertSequenceEqual(m[2][0:3], make_vec(7, 8, 9)) + # test.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) + # test.assertSequenceEqual(m[1, 0:2], make_vec(4, 5)) + # test.assertSequenceEqual(m[2, 0:3], make_vec(7, 8, 9)) + test.assertSequenceEqual(m, make_mat((1, 2, 3), (4, 5, 6), (7, 8, 9))) + + m[1, 0] = -4 + test.assertEqual(m[0][0], make_scalar(1)) + test.assertEqual(m[0][1], make_scalar(2)) + test.assertEqual(m[0][2], make_scalar(3)) + test.assertEqual(m[1][0], make_scalar(-4)) + test.assertEqual(m[1][1], make_scalar(5)) + test.assertEqual(m[1][2], make_scalar(6)) + test.assertEqual(m[2][0], make_scalar(7)) + test.assertEqual(m[2][1], make_scalar(8)) + test.assertEqual(m[2][2], make_scalar(9)) + test.assertEqual(m[0, 0], make_scalar(1)) + test.assertEqual(m[0, 1], make_scalar(2)) + test.assertEqual(m[0, 2], make_scalar(3)) + test.assertEqual(m[1, 0], make_scalar(-4)) + test.assertEqual(m[1, 1], make_scalar(5)) + test.assertEqual(m[1, 2], make_scalar(6)) + test.assertEqual(m[2, 0], make_scalar(7)) + test.assertEqual(m[2, 1], make_scalar(8)) + test.assertEqual(m[2, 2], make_scalar(9)) + test.assertSequenceEqual(m[0], make_vec(1, 2, 3)) + test.assertSequenceEqual(m[1], make_vec(-4, 5, 6)) + test.assertSequenceEqual(m[2], make_vec(7, 8, 9)) + test.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) + test.assertSequenceEqual(m[1][0:2], make_vec(-4, 5)) + test.assertSequenceEqual(m[2][0:3], make_vec(7, 8, 9)) + # test.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) + # test.assertSequenceEqual(m[1, 0:2], make_vec(-4, 5)) + # test.assertSequenceEqual(m[2, 0:3], make_vec(7, 8, 9)) + test.assertSequenceEqual(m, make_mat((1, 2, 3), (-4, 5, 6), (7, 8, 9))) + + m[2] = (-7, 8, -9) + test.assertEqual(m[0][0], make_scalar(1)) + test.assertEqual(m[0][1], make_scalar(2)) + test.assertEqual(m[0][2], make_scalar(3)) + test.assertEqual(m[1][0], make_scalar(-4)) + test.assertEqual(m[1][1], make_scalar(5)) + test.assertEqual(m[1][2], make_scalar(6)) + test.assertEqual(m[2][0], make_scalar(-7)) + test.assertEqual(m[2][1], make_scalar(8)) + test.assertEqual(m[2][2], make_scalar(-9)) + test.assertEqual(m[0, 0], make_scalar(1)) + test.assertEqual(m[0, 1], make_scalar(2)) + test.assertEqual(m[0, 2], make_scalar(3)) + test.assertEqual(m[1, 0], make_scalar(-4)) + test.assertEqual(m[1, 1], make_scalar(5)) + test.assertEqual(m[1, 2], make_scalar(6)) + test.assertEqual(m[2, 0], make_scalar(-7)) + test.assertEqual(m[2, 1], make_scalar(8)) + test.assertEqual(m[2, 2], make_scalar(-9)) + test.assertSequenceEqual(m[0], make_vec(1, 2, 3)) + test.assertSequenceEqual(m[1], make_vec(-4, 5, 6)) + test.assertSequenceEqual(m[2], make_vec(-7, 8, -9)) + test.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) + test.assertSequenceEqual(m[1][0:2], make_vec(-4, 5)) + test.assertSequenceEqual(m[2][0:3], make_vec(-7, 8, -9)) + # test.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) + # test.assertSequenceEqual(m[1, 0:2], make_vec(-4, 5)) + # test.assertSequenceEqual(m[2, 0:3], make_vec(-7, 8, -9)) + test.assertSequenceEqual(m, make_mat((1, 2, 3), (-4, 5, 6), (-7, 8, -9))) + + m = mat22_cls(2, 4, 6, 8) + test.assertSequenceEqual(+m, make_mat((2, 4), (6, 8))) + test.assertSequenceEqual(-m, make_mat((-2, -4), (-6, -8))) + test.assertSequenceEqual(m + mat22_cls(1, 1, 1, 1), make_mat((3, 5), (7, 9))) + test.assertSequenceEqual(m - mat22_cls(1, 1, 1, 1), make_mat((1, 3), (5, 7))) + test.assertSequenceEqual(m * dtype(2), make_mat((4, 8), (12, 16))) + test.assertSequenceEqual(dtype(2) * m, make_mat((4, 8), (12, 16))) + test.assertSequenceEqual(m / dtype(2), make_mat((1, 2), (3, 4))) + test.assertSequenceEqual(dtype(24) / m, make_mat((12, 6), (4, 3))) def register(parent): devices = get_test_devices() - class TestUtils(parent): + class TestTypes(parent): pass - add_function_test(TestUtils, "test_constant", test_constant) - add_function_test(TestUtils, "test_constant_error_invalid_type", test_constant_error_invalid_type) - add_function_test(TestUtils, "test_vector", test_vector) - return TestUtils + add_function_test(TestTypes, "test_constant", test_constant) + add_function_test(TestTypes, "test_constant_error_invalid_type", test_constant_error_invalid_type) + + for dtype in tuple(wp.types.scalar_types) + (int, float): + add_function_test(TestTypes, f"test_vector_{dtype.__name__}", test_vector, devices=None, dtype=dtype) + + for dtype in tuple(wp.types.float_types) + (float,): + add_function_test(TestTypes, f"test_matrix_{dtype.__name__}", test_matrix, devices=None, dtype=dtype) + + return TestTypes if __name__ == "__main__": diff --git a/warp/types.py b/warp/types.py index 148109422..05f931548 100644 --- a/warp/types.py +++ b/warp/types.py @@ -177,9 +177,15 @@ def __setattr__(self, name, value): def __add__(self, y): return warp.add(self, y) + def __radd__(self, y): + return warp.add(y, self) + def __sub__(self, y): return warp.sub(self, y) + def __rsub__(self, y): + return warp.sub(y, self) + def __mul__(self, y): return warp.mul(self, y) @@ -287,9 +293,15 @@ def __init__(self, *args): def __add__(self, y): return warp.add(self, y) + def __radd__(self, y): + return warp.add(y, self) + def __sub__(self, y): return warp.sub(self, y) + def __rsub__(self, y): + return warp.sub(y, self) + def __mul__(self, y): return warp.mul(self, y) From a69872f79cd269eaac08eab358d16b3f7c565f5c Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Wed, 15 Nov 2023 15:46:01 +1300 Subject: [PATCH 38/50] Increase coverage of vector and matrix types --- warp/tests/test_types.py | 147 +++++++++++++++++++++++++++++++++++++++ 1 file changed, 147 insertions(+) diff --git a/warp/tests/test_types.py b/warp/tests/test_types.py index 9d140367e..450584aa1 100644 --- a/warp/tests/test_types.py +++ b/warp/tests/test_types.py @@ -105,6 +105,50 @@ def make_vec(*args): test.assertSequenceEqual(v / dtype(2), make_vec(1, 2, 3)) test.assertSequenceEqual(dtype(12) / v, make_vec(6, 3, 2)) + test.assertTrue(v != vec3_cls(1, 2, 3)) + test.assertEqual(str(v), "[{}]".format(", ".join(str(x) for x in v))) + + # Check added purely for coverage reasons but is this really a desired + # behaviour? Not allowing to define new attributes using systems like + # `__slots__` could help improving memory usage. + v.foo = 123 + test.assertEqual(v.foo, 123) + + +def test_vector_error_invalid_arg_count(test, device): + with test.assertRaisesRegex( + ValueError, + r"Invalid number of arguments in vector constructor, expected 3 elements, got 2$", + ): + wp.vec3(1, 2) + + +def test_vector_error_invalid_ptr(test, device): + with test.assertRaisesRegex( + RuntimeError, + r"NULL pointer exception", + ): + wp.vec3.from_ptr(0) + + +def test_vector_error_invalid_get_item_key(test, device): + v = wp.vec3(1, 2, 3) + + with test.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or slice", + ): + v[None] + + +def test_vector_error_invalid_set_item_key(test, device): + v = wp.vec3(1, 2, 3) + with test.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or slice", + ): + v[None] = 0 + def test_matrix(test, device, dtype): def make_scalar(x): @@ -130,6 +174,7 @@ def make_mat(*args): mat22_cls = wp.mat((2, 2), dtype) mat33_cls = wp.mat((3, 3), dtype) + vec2_cls = wp.vec(2, dtype) m = mat33_cls(((1, 2, 3), (4, 5, 6), (7, 8, 9))) test.assertEqual(m[0][0], make_scalar(1)) @@ -231,6 +276,94 @@ def make_mat(*args): test.assertSequenceEqual(m / dtype(2), make_mat((1, 2), (3, 4))) test.assertSequenceEqual(dtype(24) / m, make_mat((12, 6), (4, 3))) + test.assertSequenceEqual(m * vec2_cls(1, 2), make_vec(10, 22)) + test.assertSequenceEqual(m @ vec2_cls(1, 2), make_vec(10, 22)) + test.assertSequenceEqual(vec2_cls(1, 2) * m, make_vec(14, 20)) + test.assertSequenceEqual(vec2_cls(1, 2) @ m, make_vec(14, 20)) + + test.assertTrue(m != mat22_cls(1, 2, 3, 4)) + test.assertEqual( + str(m), "[{}]".format(",\n ".join("[{}]".format(", ".join(str(y) for y in m[x])) for x in range(m._shape_[0]))) + ) + + # Check added purely for coverage reasons but is this really a desired + # behaviour? Not allowing to define new attributes using systems like + # `__slots__` could help improving memory usage. + m.foo = 123 + test.assertEqual(m.foo, 123) + + +def test_matrix_error_invalid_arg_count(test, device): + with test.assertRaisesRegex( + ValueError, + r"Invalid number of arguments in matrix constructor, expected 4 elements, got 3$", + ): + wp.mat22(1, 2, 3) + + +def test_matrix_error_invalid_row_count(test, device): + with test.assertRaisesRegex( + TypeError, + r"Invalid argument in matrix constructor, expected row of length 2, got \(1, 2, 3\)$", + ): + wp.mat22((1, 2, 3), (3, 4, 5)) + + +def test_matrix_error_invalid_ptr(test, device): + with test.assertRaisesRegex( + RuntimeError, + r"NULL pointer exception", + ): + wp.mat22.from_ptr(0) + + +def test_matrix_error_invalid_set_row_index(test, device): + m = wp.mat22(1, 2, 3, 4) + with test.assertRaisesRegex( + IndexError, + r"Invalid row index$", + ): + m.set_row(2, (0, 0)) + + +def test_matrix_error_invalid_get_item_key(test, device): + m = wp.mat22(1, 2, 3, 4) + + with test.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or pair of ints", + ): + m[None] + + +def test_matrix_error_invalid_get_item_key_length(test, device): + m = wp.mat22(1, 2, 3, 4) + + with test.assertRaisesRegex( + KeyError, + r"Invalid key, expected one or two indices, got 3", + ): + m[0, 1, 2] + + +def test_matrix_error_invalid_set_item_key(test, device): + m = wp.mat22(1, 2, 3, 4) + with test.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or pair of ints", + ): + m[None] = 0 + + +def test_matrix_error_invalid_set_item_key_length(test, device): + m = wp.mat22(1, 2, 3, 4) + + with test.assertRaisesRegex( + KeyError, + r"Invalid key, expected one or two indices, got 3", + ): + m[0, 1, 2] = (0, 0) + def register(parent): devices = get_test_devices() @@ -244,9 +377,23 @@ class TestTypes(parent): for dtype in tuple(wp.types.scalar_types) + (int, float): add_function_test(TestTypes, f"test_vector_{dtype.__name__}", test_vector, devices=None, dtype=dtype) + add_function_test(TestTypes, "test_vector_error_invalid_arg_count", test_vector_error_invalid_arg_count) + add_function_test(TestTypes, "test_vector_error_invalid_ptr", test_vector_error_invalid_ptr) + add_function_test(TestTypes, "test_vector_error_invalid_get_item_key", test_vector_error_invalid_get_item_key) + add_function_test(TestTypes, "test_vector_error_invalid_set_item_key", test_vector_error_invalid_set_item_key) + for dtype in tuple(wp.types.float_types) + (float,): add_function_test(TestTypes, f"test_matrix_{dtype.__name__}", test_matrix, devices=None, dtype=dtype) + add_function_test(TestTypes, "test_matrix_error_invalid_arg_count", test_matrix_error_invalid_arg_count) + add_function_test(TestTypes, "test_matrix_error_invalid_row_count", test_matrix_error_invalid_row_count) + add_function_test(TestTypes, "test_matrix_error_invalid_ptr", test_matrix_error_invalid_ptr) + add_function_test(TestTypes, "test_matrix_error_invalid_set_row_index", test_matrix_error_invalid_set_row_index) + add_function_test(TestTypes, "test_matrix_error_invalid_get_item_key", test_matrix_error_invalid_get_item_key) + add_function_test(TestTypes, "test_matrix_error_invalid_get_item_key_length", test_matrix_error_invalid_get_item_key_length) + add_function_test(TestTypes, "test_matrix_error_invalid_set_item_key", test_matrix_error_invalid_set_item_key) + add_function_test(TestTypes, "test_matrix_error_invalid_set_item_key_length", test_matrix_error_invalid_set_item_key_length) + return TestTypes From 5c332973231fe9d243b92807c37b5bdc2e590f4c Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Mon, 20 Nov 2023 15:11:06 +1300 Subject: [PATCH 39/50] Address code using incorrect types --- examples/env/env_ant.py | 2 +- examples/env/env_cartpole.py | 2 +- examples/env/env_humanoid.py | 2 +- examples/example_jacobian_ik.py | 2 +- examples/example_mesh_intersect.py | 12 +- examples/example_nvdb.py | 6 +- examples/example_render_opengl.py | 4 +- examples/example_sim_cartpole.py | 2 +- examples/example_sim_cloth.py | 18 +-- examples/example_sim_fk_grad.py | 4 +- examples/example_sim_fk_grad_torch.py | 6 +- examples/example_sim_grad_bounce.py | 4 +- examples/example_sim_grad_cloth.py | 6 +- examples/example_sim_granular.py | 4 +- .../example_sim_granular_collision_sdf.py | 26 ++-- examples/example_sim_neo_hookean.py | 6 +- examples/example_sim_particle_chain.py | 4 +- examples/example_sim_quadruped.py | 2 +- examples/example_sim_rigid_chain.py | 2 +- examples/example_sim_rigid_contact.py | 12 +- examples/example_sim_rigid_fem.py | 4 +- examples/example_sim_rigid_gyroscopic.py | 4 +- examples/example_sim_rigid_kinematics.py | 2 +- examples/example_sim_trajopt.py | 2 +- examples/fem/example_apic_fluid.py | 8 +- warp/sim/import_mjcf.py | 20 ++- warp/sim/import_urdf.py | 24 ++-- warp/sim/inertia.py | 35 +++-- warp/sim/model.py | 134 +++++++++--------- warp/sim/render.py | 2 +- warp/tests/test_func.py | 4 +- warp/tests/test_model.py | 8 +- warp/types.py | 4 +- 33 files changed, 192 insertions(+), 185 deletions(-) diff --git a/examples/env/env_ant.py b/examples/env/env_ant.py index 1937d79ea..2491364c0 100644 --- a/examples/env/env_ant.py +++ b/examples/env/env_ant.py @@ -54,7 +54,7 @@ def create_articulation(self, builder): up_axis="y", ) builder.joint_q[7:] = [0.0, 1.0, 0.0, -1.0, 0.0, -1.0, 0.0, 1.0] - builder.joint_q[:7] = [0.0, 0.7, 0.0, *wp.quat_from_axis_angle((1.0, 0.0, 0.0), -math.pi * 0.5)] + builder.joint_q[:7] = [0.0, 0.7, 0.0, *wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.5)] if __name__ == "__main__": diff --git a/examples/env/env_cartpole.py b/examples/env/env_cartpole.py index ba51f1cf3..e96c67f43 100644 --- a/examples/env/env_cartpole.py +++ b/examples/env/env_cartpole.py @@ -39,7 +39,7 @@ def create_articulation(self, builder): wp.sim.parse_urdf( os.path.join(os.path.dirname(__file__), "../assets/cartpole.urdf"), builder, - xform=wp.transform((0.0, 0.0, 0.0), wp.quat_from_axis_angle((1.0, 0.0, 0.0), -math.pi * 0.5)), + xform=wp.transform((0.0, 0.0, 0.0), wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.5)), floating=False, armature=0.1, stiffness=0.0, diff --git a/examples/env/env_humanoid.py b/examples/env/env_humanoid.py index 7e052881b..59ac91e51 100644 --- a/examples/env/env_humanoid.py +++ b/examples/env/env_humanoid.py @@ -58,7 +58,7 @@ def create_articulation(self, builder): up_axis="y", ) - builder.joint_q[:7] = [0.0, 1.7, 0.0, *wp.quat_from_axis_angle((1.0, 0.0, 0.0), -math.pi * 0.5)] + builder.joint_q[:7] = [0.0, 1.7, 0.0, *wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.5)] if __name__ == "__main__": diff --git a/examples/example_jacobian_ik.py b/examples/example_jacobian_ik.py index 81959f66c..48cb4a8ba 100644 --- a/examples/example_jacobian_ik.py +++ b/examples/example_jacobian_ik.py @@ -87,7 +87,7 @@ def __init__(self, stage=None, enable_rendering=True, num_envs=1, device=None): builder.add_builder( articulation_builder, xform=wp.transform( - np.array((i * 2.0, 4.0, 0.0)), wp.quat_from_axis_angle((1.0, 0.0, 0.0), -math.pi * 0.5) + wp.vec3(i * 2.0, 4.0, 0.0), wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.5) ), ) self.target_origin.append((i * 2.0, 4.0, 0.0)) diff --git a/examples/example_mesh_intersect.py b/examples/example_mesh_intersect.py index fce3e83a2..e5e1b6de9 100644 --- a/examples/example_mesh_intersect.py +++ b/examples/example_mesh_intersect.py @@ -83,6 +83,8 @@ def intersect( class Example: def __init__(self, stage): + rng = np.random.default_rng() + self.query_count = 1024 self.has_queried = False @@ -102,10 +104,10 @@ def __init__(self, stage): for i in range(self.query_count): # random offset - p = (np.random.rand(3) * 0.5 - 0.5) * 5.0 + p = wp.vec3(rng.random(3) * 0.5 - 0.5) * 5.0 # random orientation - axis = wp.normalize(np.random.rand(3) * 0.5 - 0.5) + axis = wp.normalize(wp.vec3(rng.random(3) * 0.5 - 0.5)) angle = float(np.random.rand(1)[0]) q = wp.quat_from_axis_angle(wp.normalize(axis), angle) @@ -143,14 +145,14 @@ def render(self): os.path.join(os.path.dirname(__file__), self.path_0), pos=wp.vec3(xform.p[0] + offset, xform.p[1], xform.p[2]), rot=xform.q, - scale=(1.0, 1.0, 1.0), + scale=wp.vec3(1.0, 1.0, 1.0), ) self.renderer.render_ref( f"mesh_{i}_1", os.path.join(os.path.dirname(__file__), self.path_1), - pos=(offset, 0.0, 0.0), + pos=wp.vec3(offset, 0.0, 0.0), rot=wp.quat_identity(), - scale=(1.0, 1.0, 1.0), + scale=wp.vec3(1.0, 1.0, 1.0), ) # if pair intersects then draw a small box above the pair diff --git a/examples/example_nvdb.py b/examples/example_nvdb.py index 53448eaa4..5e3a32b9a 100644 --- a/examples/example_nvdb.py +++ b/examples/example_nvdb.py @@ -143,9 +143,9 @@ def render(self, is_live=False): self.renderer.render_ref( name="collision", path=os.path.join(os.path.dirname(__file__), "assets/rocks.usd"), - pos=(0.0, 0.0, 0.0), - rot=wp.quat_from_axis_angle((1.0, 0.0, 0.0), math.pi), - scale=(1.0, 1.0, 1.0), + pos=wp.vec3(0.0, 0.0, 0.0), + rot=wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), math.pi), + scale=wp.vec3(1.0, 1.0, 1.0), ) self.renderer.render_points(name="points", points=self.positions.numpy(), radius=self.sim_margin) diff --git a/examples/example_render_opengl.py b/examples/example_render_opengl.py index 8bf2ffa38..3c5d2e23a 100644 --- a/examples/example_render_opengl.py +++ b/examples/example_render_opengl.py @@ -104,14 +104,14 @@ renderer.render_cylinder( "cylinder", [3.2, 1.0, np.sin(time + 0.5)], - np.array(wp.quat_from_axis_angle((1.0, 0.0, 0.0), np.sin(time + 0.5))), + np.array(wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), wp.sin(time + 0.5))), radius=0.5, half_height=0.8, ) renderer.render_cone( "cone", [-1.2, 1.0, 0.0], - np.array(wp.quat_from_axis_angle((0.707, 0.707, 0.0), time)), + np.array(wp.quat_from_axis_angle(wp.vec3(0.707, 0.707, 0.0), time)), radius=0.5, half_height=0.8, ) diff --git a/examples/example_sim_cartpole.py b/examples/example_sim_cartpole.py index 9c80337b6..5c2724d8f 100644 --- a/examples/example_sim_cartpole.py +++ b/examples/example_sim_cartpole.py @@ -37,7 +37,7 @@ def __init__(self, stage=None, num_envs=1, enable_rendering=True, print_timers=T wp.sim.parse_urdf( os.path.join(os.path.dirname(__file__), "assets/cartpole.urdf"), articulation_builder, - xform=wp.transform(np.zeros(3), wp.quat_from_axis_angle((1.0, 0.0, 0.0), -math.pi * 0.5)), + xform=wp.transform(wp.vec3(), wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.5)), floating=False, density=100, armature=0.1, diff --git a/examples/example_sim_cloth.py b/examples/example_sim_cloth.py index 83caef096..5ec7dfcf7 100644 --- a/examples/example_sim_cloth.py +++ b/examples/example_sim_cloth.py @@ -68,9 +68,9 @@ def __init__(self, stage): if self.integrator_type == IntegratorType.EULER: builder.add_cloth_grid( - pos=(0.0, 4.0, 0.0), - rot=wp.quat_from_axis_angle((1.0, 0.0, 0.0), math.pi * 0.5), - vel=(0.0, 0.0, 0.0), + pos=wp.vec3(0.0, 4.0, 0.0), + rot=wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), math.pi * 0.5), + vel=wp.vec3(0.0, 0.0, 0.0), dim_x=self.sim_width, dim_y=self.sim_height, cell_x=0.1, @@ -83,9 +83,9 @@ def __init__(self, stage): ) else: builder.add_cloth_grid( - pos=(0.0, 4.0, 0.0), - rot=wp.quat_from_axis_angle((1.0, 0.0, 0.0), math.pi * 0.5), - vel=(0.0, 0.0, 0.0), + pos=wp.vec3(0.0, 4.0, 0.0), + rot=wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), math.pi * 0.5), + vel=wp.vec3(0.0, 0.0, 0.0), dim_x=self.sim_width, dim_y=self.sim_height, cell_x=0.1, @@ -109,9 +109,9 @@ def __init__(self, stage): builder.add_shape_mesh( body=-1, mesh=mesh, - pos=(1.0, 0.0, 1.0), - rot=wp.quat_from_axis_angle((0.0, 1.0, 0.0), math.pi * 0.5), - scale=(2.0, 2.0, 2.0), + pos=wp.vec3(1.0, 0.0, 1.0), + rot=wp.quat_from_axis_angle(wp.vec3(0.0, 1.0, 0.0), math.pi * 0.5), + scale=wp.vec3(2.0, 2.0, 2.0), ke=1.0e2, kd=1.0e2, kf=1.0e1, diff --git a/examples/example_sim_fk_grad.py b/examples/example_sim_fk_grad.py index ba4c5edaa..92d711147 100644 --- a/examples/example_sim_fk_grad.py +++ b/examples/example_sim_fk_grad.py @@ -84,12 +84,12 @@ def __init__(self, stage, device=None, verbose=False): if i == chain_length - 1: # create end effector - builder.add_shape_sphere(pos=(0.0, 0.0, 0.0), radius=0.1, density=10.0, body=b) + builder.add_shape_sphere(pos=wp.vec3(0.0, 0.0, 0.0), radius=0.1, density=10.0, body=b) else: # create shape builder.add_shape_box( - pos=(chain_width * 0.5, 0.0, 0.0), hx=chain_width * 0.5, hy=0.1, hz=0.1, density=10.0, body=b + pos=wp.vec3(chain_width * 0.5, 0.0, 0.0), hx=chain_width * 0.5, hy=0.1, hz=0.1, density=10.0, body=b ) self.device = wp.get_device(device) diff --git a/examples/example_sim_fk_grad_torch.py b/examples/example_sim_fk_grad_torch.py index 6fb5b453d..f047c5b7f 100644 --- a/examples/example_sim_fk_grad_torch.py +++ b/examples/example_sim_fk_grad_torch.py @@ -95,7 +95,7 @@ def __init__(self, stage, device=None, verbose=False): builder.add_joint_revolute( parent=parent, child=b, - axis=(0.0, 0.0, 1.0), + axis=wp.vec3(0.0, 0.0, 1.0), parent_xform=parent_joint_xform, child_xform=wp.transform_identity(), limit_lower=-np.deg2rad(60.0), @@ -108,12 +108,12 @@ def __init__(self, stage, device=None, verbose=False): if i == chain_length - 1: # create end effector - builder.add_shape_sphere(pos=(0.0, 0.0, 0.0), radius=0.1, density=10.0, body=b) + builder.add_shape_sphere(pos=wp.vec3(0.0, 0.0, 0.0), radius=0.1, density=10.0, body=b) else: # create shape builder.add_shape_box( - pos=(chain_width * 0.5, 0.0, 0.0), hx=chain_width * 0.5, hy=0.1, hz=0.1, density=10.0, body=b + pos=wp.vec3(chain_width * 0.5, 0.0, 0.0), hx=chain_width * 0.5, hy=0.1, hz=0.1, density=10.0, body=b ) # finalize model diff --git a/examples/example_sim_grad_bounce.py b/examples/example_sim_grad_bounce.py index de524a7b0..526f86742 100644 --- a/examples/example_sim_grad_bounce.py +++ b/examples/example_sim_grad_bounce.py @@ -71,8 +71,8 @@ def __init__(self, stage=None, enable_rendering=True, profile=False, adapter=Non mu = 0.2 builder = wp.sim.ModelBuilder() - builder.add_particle(pos=(-0.5, 1.0, 0.0), vel=(5.0, -5.0, 0.0), mass=1.0) - builder.add_shape_box(body=-1, pos=(2.0, 1.0, 0.0), hx=0.25, hy=1.0, hz=1.0, ke=ke, kf=kf, kd=kd, mu=mu) + builder.add_particle(pos=wp.vec3(-0.5, 1.0, 0.0), vel=wp.vec3(5.0, -5.0, 0.0), mass=1.0) + builder.add_shape_box(body=-1, pos=wp.vec3(2.0, 1.0, 0.0), hx=0.25, hy=1.0, hz=1.0, ke=ke, kf=kf, kd=kd, mu=mu) self.device = wp.get_device(adapter) self.profile = profile diff --git a/examples/example_sim_grad_cloth.py b/examples/example_sim_grad_cloth.py index b1d1944cd..d0afb6905 100644 --- a/examples/example_sim_grad_cloth.py +++ b/examples/example_sim_grad_cloth.py @@ -80,9 +80,9 @@ def __init__(self, stage, profile=False, adapter=None, verbose=False): dim_y = 16 builder.add_cloth_grid( - pos=(0.0, 0.0, 0.0), - vel=(0.1, 0.1, 0.0), - rot=wp.quat_from_axis_angle((1.0, 0.0, 0.0), -math.pi * 0.25), + pos=wp.vec3(0.0, 0.0, 0.0), + vel=wp.vec3(0.1, 0.1, 0.0), + rot=wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.25), dim_x=dim_x, dim_y=dim_y, cell_x=1.0 / dim_x, diff --git a/examples/example_sim_granular.py b/examples/example_sim_granular.py index 3eb29181c..b868e850b 100644 --- a/examples/example_sim_granular.py +++ b/examples/example_sim_granular.py @@ -44,9 +44,9 @@ def __init__(self, stage): cell_x=self.radius * 2.0, cell_y=self.radius * 2.0, cell_z=self.radius * 2.0, - pos=(0.0, 1.0, 0.0), + pos=wp.vec3(0.0, 1.0, 0.0), rot=wp.quat_identity(), - vel=(5.0, 0.0, 0.0), + vel=wp.vec3(5.0, 0.0, 0.0), mass=0.1, jitter=self.radius * 0.1, ) diff --git a/examples/example_sim_granular_collision_sdf.py b/examples/example_sim_granular_collision_sdf.py index 60fcd2e92..175b1067d 100644 --- a/examples/example_sim_granular_collision_sdf.py +++ b/examples/example_sim_granular_collision_sdf.py @@ -48,9 +48,9 @@ def __init__(self, stage): cell_x=self.radius * 2.0, cell_y=self.radius * 2.0, cell_z=self.radius * 2.0, - pos=(0.0, 20.0, 0.0), + pos=wp.vec3(0.0, 20.0, 0.0), rot=wp.quat_identity(), - vel=(2.0, 0.0, 0.0), + vel=wp.vec3(2.0, 0.0, 0.0), mass=0.1, jitter=self.radius * 0.1, ) @@ -67,9 +67,9 @@ def __init__(self, stage): mu=0.5, sdf=rock_sdf, body=-1, - pos=(0.0, 0.0, 0.0), - rot=wp.quat_from_axis_angle((1.0, 0.0, 0.0), -0.5 * math.pi), - scale=(0.01, 0.01, 0.01), + pos=wp.vec3(0.0, 0.0, 0.0), + rot=wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -0.5 * math.pi), + scale=wp.vec3(0.01, 0.01, 0.01), ) mins = np.array([-3.0, -3.0, -3.0]) @@ -89,7 +89,7 @@ def __init__(self, stage): sphere_vdb = wp.Volume.load_from_numpy(sphere_sdf_np, mins, voxel_size, rad + 3.0 * voxel_size) sphere_sdf = wp.sim.SDF(sphere_vdb) - self.sphere_pos = (3.0, 15.0, 0.0) + self.sphere_pos = wp.vec3(3.0, 15.0, 0.0) self.sphere_scale = 1.0 self.sphere_radius = rad builder.add_shape_sdf( @@ -100,7 +100,7 @@ def __init__(self, stage): sdf=sphere_sdf, body=-1, pos=self.sphere_pos, - scale=(self.sphere_scale, self.sphere_scale, self.sphere_scale), + scale=wp.vec3(self.sphere_scale, self.sphere_scale, self.sphere_scale), ) self.model = builder.finalize() @@ -136,21 +136,21 @@ def render(self, is_live=False): self.renderer.begin_frame(time) - # Note the extra wp.quat_from_axis_angle((1.0, 0.0, 0.0), math.pi) is because .usd is oriented differently from .nvdb + # Note the extra wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), math.pi) is because .usd is oriented differently from .nvdb self.renderer.render_ref( name="collision", path=os.path.join(os.path.dirname(__file__), "assets/rocks.usd"), - pos=(0.0, 0.0, 0.0), - rot=wp.quat_from_axis_angle((1.0, 0.0, 0.0), -0.5 * math.pi) - * wp.quat_from_axis_angle((1.0, 0.0, 0.0), math.pi), - scale=(0.01, 0.01, 0.01), + pos=wp.vec3(0.0, 0.0, 0.0), + rot=wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -0.5 * math.pi) + * wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), math.pi), + scale=wp.vec3(0.01, 0.01, 0.01), ) self.renderer.render_sphere( name="sphere", pos=self.sphere_pos, radius=self.sphere_scale * self.sphere_radius, - rot=(0.0, 0.0, 0.0, 1.0), + rot=wp.quat(0.0, 0.0, 0.0, 1.0), ) self.renderer.render(self.state_0) diff --git a/examples/example_sim_neo_hookean.py b/examples/example_sim_neo_hookean.py index 19cb463cf..99e9506d4 100644 --- a/examples/example_sim_neo_hookean.py +++ b/examples/example_sim_neo_hookean.py @@ -80,9 +80,9 @@ def __init__(self, stage): center = cell_size * cell_dim * 0.5 builder.add_soft_grid( - pos=(-center, 0.0, -center), + pos=wp.vec3(-center, 0.0, -center), rot=wp.quat_identity(), - vel=(0.0, 0.0, 0.0), + vel=wp.vec3(0.0, 0.0, 0.0), dim_x=cell_dim, dim_y=cell_dim, dim_z=cell_dim, @@ -117,7 +117,7 @@ def update(self): with wp.ScopedTimer("simulate"): xform = wp.transform( (0.0, self.lift_speed * self.sim_time, 0.0), - wp.quat_from_axis_angle((0.0, 1.0, 0.0), self.rot_speed * self.sim_time), + wp.quat_from_axis_angle(wp.vec3(0.0, 1.0, 0.0), self.rot_speed * self.sim_time), ) wp.launch( kernel=twist_points, diff --git a/examples/example_sim_particle_chain.py b/examples/example_sim_particle_chain.py index d93a82c19..712f40d82 100644 --- a/examples/example_sim_particle_chain.py +++ b/examples/example_sim_particle_chain.py @@ -38,13 +38,13 @@ def __init__(self, stage): builder = wp.sim.ModelBuilder() # anchor - builder.add_particle((0.0, 1.0, 0.0), (0.0, 0.0, 0.0), 0.0) + builder.add_particle(wp.vec3(0.0, 1.0, 0.0), wp.vec3(0.0, 0.0, 0.0), 0.0) # chain for i in range(1, 10): radius = math.sqrt(i) * 0.2 mass = math.pi * radius * radius * radius - builder.add_particle((i, 1.0, 0.0), (0.0, 0.0, 0.0), mass, radius=radius) + builder.add_particle(wp.vec3(i, 1.0, 0.0), wp.vec3(0.0, 0.0, 0.0), mass, radius=radius) builder.add_spring(i - 1, i, 1.0e6, 0.0, 0) self.model = builder.finalize() diff --git a/examples/example_sim_quadruped.py b/examples/example_sim_quadruped.py index c982d07cc..f0413f40b 100644 --- a/examples/example_sim_quadruped.py +++ b/examples/example_sim_quadruped.py @@ -75,7 +75,7 @@ def __init__(self, stage=None, num_envs=1, enable_rendering=True, print_timers=T wp.sim.parse_urdf( os.path.join(os.path.dirname(__file__), "assets/quadruped.urdf"), articulation_builder, - xform=wp.transform([0.0, 0.7, 0.0], wp.quat_from_axis_angle((1.0, 0.0, 0.0), -math.pi * 0.5)), + xform=wp.transform([0.0, 0.7, 0.0], wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.5)), floating=True, density=1000, armature=0.01, diff --git a/examples/example_sim_rigid_chain.py b/examples/example_sim_rigid_chain.py index a33f34c32..4309536ca 100644 --- a/examples/example_sim_rigid_chain.py +++ b/examples/example_sim_rigid_chain.py @@ -65,7 +65,7 @@ def __init__(self, stage): # create shape builder.add_shape_box( - pos=(self.chain_width * 0.5, 0.0, 0.0), + pos=wp.vec3(self.chain_width * 0.5, 0.0, 0.0), hx=self.chain_width * 0.5, hy=0.1, hz=0.1, diff --git a/examples/example_sim_rigid_contact.py b/examples/example_sim_rigid_contact.py index 051fe0346..53450ce12 100644 --- a/examples/example_sim_rigid_contact.py +++ b/examples/example_sim_rigid_contact.py @@ -50,7 +50,7 @@ def __init__(self, stage): b = builder.add_body(origin=wp.transform((i, 1.0, 0.0), wp.quat_identity())) builder.add_shape_box( - pos=(0.0, 0.0, 0.0), + pos=wp.vec3(0.0, 0.0, 0.0), hx=0.5 * self.scale, hy=0.2 * self.scale, hz=0.2 * self.scale, @@ -65,7 +65,7 @@ def __init__(self, stage): b = builder.add_body(origin=wp.transform((i, 1.0, 2.0), wp.quat_identity())) builder.add_shape_sphere( - pos=(0.0, 0.0, 0.0), radius=0.25 * self.scale, body=b, ke=self.ke, kd=self.kd, kf=self.kf + pos=wp.vec3(0.0, 0.0, 0.0), radius=0.25 * self.scale, body=b, ke=self.ke, kd=self.kd, kf=self.kf ) # capsules @@ -73,7 +73,7 @@ def __init__(self, stage): b = builder.add_body(origin=wp.transform((i, 1.0, 6.0), wp.quat_identity())) builder.add_shape_capsule( - pos=(0.0, 0.0, 0.0), + pos=wp.vec3(0.0, 0.0, 0.0), radius=0.25 * self.scale, half_height=self.scale * 0.5, up_axis=0, @@ -93,15 +93,15 @@ def __init__(self, stage): b = builder.add_body( origin=wp.transform( (i * 0.5 * self.scale, 1.0 + i * 1.7 * self.scale, 4.0 + i * 0.5 * self.scale), - wp.quat_from_axis_angle((0.0, 1.0, 0.0), math.pi * 0.1 * i), + wp.quat_from_axis_angle(wp.vec3(0.0, 1.0, 0.0), math.pi * 0.1 * i), ) ) builder.add_shape_mesh( body=b, mesh=bunny, - pos=(0.0, 0.0, 0.0), - scale=(self.scale, self.scale, self.scale), + pos=wp.vec3(0.0, 0.0, 0.0), + scale=wp.vec3(self.scale, self.scale, self.scale), ke=self.ke, kd=self.kd, kf=self.kf, diff --git a/examples/example_sim_rigid_fem.py b/examples/example_sim_rigid_fem.py index a62a72e7a..80e34f6c3 100644 --- a/examples/example_sim_rigid_fem.py +++ b/examples/example_sim_rigid_fem.py @@ -40,9 +40,9 @@ def __init__(self, stage): builder.default_particle_radius = 0.01 builder.add_soft_grid( - pos=(0.0, 0.0, 0.0), + pos=wp.vec3(0.0, 0.0, 0.0), rot=wp.quat_identity(), - vel=(0.0, 0.0, 0.0), + vel=wp.vec3(0.0, 0.0, 0.0), dim_x=20, dim_y=10, dim_z=10, diff --git a/examples/example_sim_rigid_gyroscopic.py b/examples/example_sim_rigid_gyroscopic.py index 89cf18a81..de1c1b61d 100644 --- a/examples/example_sim_rigid_gyroscopic.py +++ b/examples/example_sim_rigid_gyroscopic.py @@ -36,7 +36,7 @@ def __init__(self, stage): # axis shape builder.add_shape_box( - pos=(0.3 * self.scale, 0.0, 0.0), + pos=wp.vec3(0.3 * self.scale, 0.0, 0.0), hx=0.25 * self.scale, hy=0.1 * self.scale, hz=0.1 * self.scale, @@ -46,7 +46,7 @@ def __init__(self, stage): # tip shape builder.add_shape_box( - pos=(0.0, 0.0, 0.0), hx=0.05 * self.scale, hy=0.2 * self.scale, hz=1.0 * self.scale, density=100.0, body=b + pos=wp.vec3(0.0, 0.0, 0.0), hx=0.05 * self.scale, hy=0.2 * self.scale, hz=1.0 * self.scale, density=100.0, body=b ) # initial spin diff --git a/examples/example_sim_rigid_kinematics.py b/examples/example_sim_rigid_kinematics.py index be794e9ac..cdb6c8ca1 100644 --- a/examples/example_sim_rigid_kinematics.py +++ b/examples/example_sim_rigid_kinematics.py @@ -59,7 +59,7 @@ def __init__(self, stage, num_envs=1, device=None, verbose=False): # base builder.joint_q[coord_start : coord_start + 3] = [i * 2.0, 0.70, 0.0] builder.joint_q[coord_start + 3 : coord_start + 7] = wp.quat_from_axis_angle( - (1.0, 0.0, 0.0), -math.pi * 0.5 + wp.vec3(1.0, 0.0, 0.0), -math.pi * 0.5 ) # joints diff --git a/examples/example_sim_trajopt.py b/examples/example_sim_trajopt.py index fc01472fd..279fb5f32 100644 --- a/examples/example_sim_trajopt.py +++ b/examples/example_sim_trajopt.py @@ -72,7 +72,7 @@ def __init__(self, stage, device=None, verbose=False): builder = wp.sim.ModelBuilder(gravity=0.0) builder.add_articulation() b = builder.add_body(origin=wp.transform()) - builder.add_shape_box(pos=(0.0, 0.0, 0.0), hx=0.5, hy=0.5, hz=0.5, density=100.0, body=b) + builder.add_shape_box(pos=wp.vec3(0.0, 0.0, 0.0), hx=0.5, hy=0.5, hz=0.5, density=100.0, body=b) # compute reference trajectory rad = np.linspace(0.0, np.pi * 2, self.episode_frames) diff --git a/examples/fem/example_apic_fluid.py b/examples/fem/example_apic_fluid.py index 211602f3c..84c2535ec 100644 --- a/examples/fem/example_apic_fluid.py +++ b/examples/fem/example_apic_fluid.py @@ -169,10 +169,10 @@ def __init__(self, stage, num_frames=1000, res=[32, 64, 16], quiet=False): grid_cell_volume = np.prod(grid_cell_size) PARTICLES_PER_CELL_DIM = 3 - self.radius = np.max(grid_cell_size) / (2 * PARTICLES_PER_CELL_DIM) + self.radius = float(np.max(grid_cell_size) / (2 * PARTICLES_PER_CELL_DIM)) particle_grid_res = np.array(particle_fill_frac * grid_res * PARTICLES_PER_CELL_DIM, dtype=int) - particle_grid_offset = self.radius * np.ones(3) + particle_grid_offset = wp.vec3(self.radius, self.radius, self.radius) np.random.seed(0) builder = wp.sim.ModelBuilder() @@ -183,9 +183,9 @@ def __init__(self, stage, num_frames=1000, res=[32, 64, 16], quiet=False): cell_x=self.radius * 2.0, cell_y=self.radius * 2.0, cell_z=self.radius * 2.0, - pos=(0.0, 0.0, 0.0) + particle_grid_offset, + pos=wp.vec3(0.0, 0.0, 0.0) + particle_grid_offset, rot=wp.quat_identity(), - vel=(0.0, 0.0, 0.0), + vel=wp.vec3(0.0, 0.0, 0.0), mass=grid_cell_volume / PARTICLES_PER_CELL_DIM**3, jitter=self.radius * 1.0, radius_mean=self.radius, diff --git a/warp/sim/import_mjcf.py b/warp/sim/import_mjcf.py index 355fa669f..f84017dfe 100644 --- a/warp/sim/import_mjcf.py +++ b/warp/sim/import_mjcf.py @@ -150,9 +150,15 @@ def parse_float(attrib, key, default): def parse_vec(attrib, key, default): if key in attrib: - return np.fromstring(attrib[key], sep=" ") + out = np.fromstring(attrib[key], sep=" ", dtype=np.float32) else: - return np.array(default) + out = np.array(default, dtype=np.float32) + + length = len(out) + if length == 1: + return wp.vec(len(default), wp.float32)(out[0], out[0], out[0]) + + return wp.vec(length, wp.float32)(out) def parse_orientation(attrib): if "quat" in attrib: @@ -397,19 +403,19 @@ def parse_body(body, parent, incoming_defaults: dict): if "fromto" in geom_attrib: geom_fromto = parse_vec(geom_attrib, "fromto", (0.0, 0.0, 0.0, 1.0, 0.0, 0.0)) - start = geom_fromto[0:3] * scale - end = geom_fromto[3:6] * scale + start = wp.vec3(geom_fromto[0:3]) * scale + end = wp.vec3(geom_fromto[3:6]) * scale # compute rotation to align the Warp capsule (along x-axis), with mjcf fromto direction axis = wp.normalize(end - start) - angle = math.acos(np.dot(axis, (0.0, 1.0, 0.0))) - axis = wp.normalize(np.cross(axis, (0.0, 1.0, 0.0))) + angle = math.acos(wp.dot(axis, wp.vec3(0.0, 1.0, 0.0))) + axis = wp.normalize(wp.cross(axis, wp.vec3(0.0, 1.0, 0.0))) geom_pos = (start + end) * 0.5 geom_rot = wp.quat_from_axis_angle(axis, -angle) geom_radius = geom_size[0] - geom_height = np.linalg.norm(end - start) * 0.5 + geom_height = wp.length(end - start) * 0.5 geom_up_axis = 1 else: diff --git a/warp/sim/import_urdf.py b/warp/sim/import_urdf.py index b1458b6da..a80786413 100644 --- a/warp/sim/import_urdf.py +++ b/warp/sim/import_urdf.py @@ -100,8 +100,8 @@ def parse_shapes(link, collisions, density, incoming_xform=None): size = [float(x) for x in size.split()] builder.add_shape_box( body=link, - pos=tf.p, - rot=tf.q, + pos=wp.vec3(tf.p), + rot=wp.quat(tf.q), hx=size[0] * 0.5 * scale, hy=size[1] * 0.5 * scale, hz=size[2] * 0.5 * scale, @@ -117,8 +117,8 @@ def parse_shapes(link, collisions, density, incoming_xform=None): for sphere in geo.findall("sphere"): builder.add_shape_sphere( body=link, - pos=tf.p, - rot=tf.q, + pos=wp.vec3(tf.p), + rot=wp.quat(tf.q), radius=float(sphere.get("radius") or "1") * scale, density=density, ke=shape_ke, @@ -132,8 +132,8 @@ def parse_shapes(link, collisions, density, incoming_xform=None): for cylinder in geo.findall("cylinder"): builder.add_shape_capsule( body=link, - pos=tf.p, - rot=tf.q, + pos=wp.vec3(tf.p), + rot=wp.quat(tf.q), radius=float(cylinder.get("radius") or "1") * scale, half_height=float(cylinder.get("length") or "1") * 0.5 * scale, density=density, @@ -184,8 +184,8 @@ def parse_shapes(link, collisions, density, incoming_xform=None): mesh = Mesh(vertices, faces) builder.add_shape_mesh( body=link, - pos=tf.p, - rot=tf.q, + pos=wp.vec3(tf.p), + rot=wp.quat(tf.q), mesh=mesh, density=density, ke=shape_ke, @@ -252,22 +252,22 @@ def parse_shapes(link, collisions, density, incoming_xform=None): I_m[2, 0] = I_m[0, 2] I_m[2, 1] = I_m[1, 2] rot = wp.quat_to_matrix(inertial_frame.q) - I_m = rot @ I_m + I_m = rot @ wp.mat33(I_m) m = float(inertial.find("mass").get("value") or "0") builder.body_mass[link] = m builder.body_inv_mass[link] = 1.0 / m builder.body_com[link] = com builder.body_inertia[link] = I_m - builder.body_inv_inertia[link] = np.linalg.inv(I_m) + builder.body_inv_inertia[link] = wp.inverse(I_m) if m == 0.0 and ensure_nonstatic_links: # set the mass to something nonzero to ensure the body is dynamic m = static_link_mass # cube with side length 0.5 - I_m = np.eye(3) * m / 12.0 * (0.5 * scale) ** 2 * 2.0 + I_m = wp.mat33(np.eye(3)) * m / 12.0 * (0.5 * scale) ** 2 * 2.0 builder.body_mass[link] = m builder.body_inv_mass[link] = 1.0 / m builder.body_inertia[link] = I_m - builder.body_inv_inertia[link] = np.linalg.inv(I_m) + builder.body_inv_inertia[link] = wp.inverse(I_m) end_shape_count = len(builder.shape_geo_type) diff --git a/warp/sim/inertia.py b/warp/sim/inertia.py index 5be776104..9569c8166 100644 --- a/warp/sim/inertia.py +++ b/warp/sim/inertia.py @@ -149,9 +149,9 @@ def compute_sphere_inertia(density: float, r: float) -> tuple: m = density * v Ia = 2.0 / 5.0 * m * r * r - I = np.array([[Ia, 0.0, 0.0], [0.0, Ia, 0.0], [0.0, 0.0, Ia]]) + I = wp.mat33([[Ia, 0.0, 0.0], [0.0, Ia, 0.0], [0.0, 0.0, Ia]]) - return (m, np.zeros(3), I) + return (m, wp.vec3(), I) def compute_capsule_inertia(density: float, r: float, h: float) -> tuple: @@ -177,9 +177,9 @@ def compute_capsule_inertia(density: float, r: float, h: float) -> tuple: Ia = mc * (0.25 * r * r + (1.0 / 12.0) * h * h) + ms * (0.4 * r * r + 0.375 * r * h + 0.25 * h * h) Ib = (mc * 0.5 + ms * 0.4) * r * r - I = np.array([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ia]]) + I = wp.mat33([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ia]]) - return (m, np.zeros(3), I) + return (m, wp.vec3(), I) def compute_cylinder_inertia(density: float, r: float, h: float) -> tuple: @@ -200,9 +200,9 @@ def compute_cylinder_inertia(density: float, r: float, h: float) -> tuple: Ia = 1 / 12 * m * (3 * r * r + h * h) Ib = 1 / 2 * m * r * r - I = np.array([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ia]]) + I = wp.mat33([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ia]]) - return (m, np.zeros(3), I) + return (m, wp.vec3(), I) def compute_cone_inertia(density: float, r: float, h: float) -> tuple: @@ -223,9 +223,9 @@ def compute_cone_inertia(density: float, r: float, h: float) -> tuple: Ia = 1 / 20 * m * (3 * r * r + 2 * h * h) Ib = 3 / 10 * m * r * r - I = np.array([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ia]]) + I = wp.mat33([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ia]]) - return (m, np.zeros(3), I) + return (m, wp.vec3(), I) def compute_box_inertia(density: float, w: float, h: float, d: float) -> tuple: @@ -249,17 +249,16 @@ def compute_box_inertia(density: float, w: float, h: float, d: float) -> tuple: Ib = 1.0 / 12.0 * m * (w * w + d * d) Ic = 1.0 / 12.0 * m * (w * w + h * h) - I = np.array([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ic]]) + I = wp.mat33([[Ia, 0.0, 0.0], [0.0, Ib, 0.0], [0.0, 0.0, Ic]]) - return (m, np.zeros(3), I) + return (m, wp.vec3(), I) def compute_mesh_inertia( density: float, vertices: list, indices: list, is_solid: bool = True, thickness: Union[List[float], float] = 0.001 ) -> tuple: """Computes mass, center of mass, 3x3 inertia matrix, and volume for a mesh.""" - com = np.mean(vertices, 0) - com_warp = wp.vec3(com[0], com[1], com[2]) + com = wp.vec3(np.mean(vertices, 0)) num_tris = len(indices) // 3 @@ -279,7 +278,7 @@ def compute_mesh_inertia( kernel=compute_solid_mesh_inertia, dim=num_tris, inputs=[ - com_warp, + com, weight, wp.array(indices, dtype=int), wp.array(vertices, dtype=wp.vec3), @@ -294,7 +293,7 @@ def compute_mesh_inertia( kernel=compute_hollow_mesh_inertia, dim=num_tris, inputs=[ - com_warp, + com, weight, wp.array(indices, dtype=int), wp.array(vertices, dtype=wp.vec3), @@ -304,14 +303,14 @@ def compute_mesh_inertia( ) # Extract mass and inertia and save to class attributes. - mass = mass_warp.numpy()[0] * density - I = I_warp.numpy()[0] * density + mass = float(mass_warp.numpy()[0] * density) + I = wp.mat33(*(I_warp.numpy()[0] * density)) volume = vol_warp.numpy()[0] return mass, com, I, volume def transform_inertia(m, I, p, q): - R = np.array(wp.quat_to_matrix(q)).reshape(3, 3) + R = wp.quat_to_matrix(q) # Steiner's theorem - return R @ I @ R.T + m * (np.dot(p, p) * np.eye(3) - np.outer(p, p)) + return R @ I @ wp.transpose(R) + m * (wp.dot(p, p) * wp.mat33(np.eye(3)) - wp.outer(p, p)) diff --git a/warp/sim/model.py b/warp/sim/model.py index 6cd1e2ac8..8c2ee1de4 100644 --- a/warp/sim/model.py +++ b/warp/sim/model.py @@ -113,8 +113,8 @@ class JointAxis: def __init__( self, axis, - limit_lower=-np.inf, - limit_upper=np.inf, + limit_lower=-math.inf, + limit_upper=math.inf, limit_ke=100.0, limit_kd=10.0, target=None, @@ -133,7 +133,7 @@ def __init__( self.target_kd = axis.target_kd self.mode = axis.mode else: - self.axis = np.array(wp.normalize(np.array(axis, dtype=np.float32))) + self.axis = wp.normalize(wp.vec3(axis)) self.limit_lower = limit_lower self.limit_upper = limit_upper self.limit_ke = limit_ke @@ -159,7 +159,7 @@ class SDF: mass (float): The total mass of the SDF com (Vec3): The center of mass of the SDF """ - def __init__(self, volume=None, I=np.eye(3, dtype=np.float32), mass=1.0, com=np.array((0.0, 0.0, 0.0))): + def __init__(self, volume=None, I=wp.mat33(np.eye(3)), mass=1.0, com=wp.vec3()): self.volume = volume self.I = I self.mass = mass @@ -234,9 +234,9 @@ def __init__(self, vertices: List[Vec3], indices: List[int], compute_inertia=Tru if compute_inertia: self.mass, self.com, self.I, _ = compute_mesh_inertia(1.0, vertices, indices, is_solid=is_solid) else: - self.I = np.eye(3, dtype=np.float32) + self.I = wp.mat33(np.eye(3)) self.mass = 1.0 - self.com = np.array((0.0, 0.0, 0.0)) + self.com = wp.vec3() def finalize(self, device=None): """ @@ -325,7 +325,7 @@ def flatten(self): def compute_shape_mass(type, scale, src, density, is_solid, thickness): if density == 0.0 or type == GEO_PLANE: # zero density means fixed - return 0.0, np.zeros(3), np.zeros((3, 3)) + return 0.0, wp.vec3(), wp.mat33() if type == GEO_SPHERE: solid = compute_sphere_inertia(density, scale[0]) @@ -335,7 +335,7 @@ def compute_shape_mass(type, scale, src, density, is_solid, thickness): hollow = compute_sphere_inertia(density, scale[0] - thickness) return solid[0] - hollow[0], solid[1], solid[2] - hollow[2] elif type == GEO_BOX: - w, h, d = np.array(scale[:3]) * 2.0 + w, h, d = scale * 2.0 solid = compute_box_inertia(density, w, h, d) if is_solid: return solid @@ -370,13 +370,12 @@ def compute_shape_mass(type, scale, src, density, is_solid, thickness): if src.has_inertia and src.mass > 0.0 and src.is_solid == is_solid: m, c, I = src.mass, src.com, src.I - s = np.array(scale[:3]) - sx, sy, sz = s + sx, sy, sz = scale mass_ratio = sx * sy * sz * density m_new = m * mass_ratio - c_new = c * s + c_new = wp.cw_mul(c, scale) Ixx = I[0, 0] * (sy**2 + sz**2) / 2 * mass_ratio Iyy = I[1, 1] * (sx**2 + sz**2) / 2 * mass_ratio @@ -385,12 +384,12 @@ def compute_shape_mass(type, scale, src, density, is_solid, thickness): Ixz = I[0, 2] * sx * sz * mass_ratio Iyz = I[1, 2] * sy * sz * mass_ratio - I_new = np.array([[Ixx, Ixy, Ixz], [Ixy, Iyy, Iyz], [Ixz, Iyz, Izz]]) + I_new = wp.mat33([[Ixx, Ixy, Ixz], [Ixy, Iyy, Iyz], [Ixz, Iyz, Izz]]) return m_new, c_new, I_new elif type == GEO_MESH: # fall back to computing inertia from mesh geometry - vertices = np.array(src.vertices) * np.array(scale[:3]) + vertices = np.array(src.vertices) * np.array(scale) m, c, I, vol = compute_mesh_inertia(density, vertices, src.indices, is_solid, thickness) return m, c, I raise ValueError("Unsupported shape type: {}".format(type)) @@ -1131,8 +1130,8 @@ def __init__(self, up_vector=(0.0, 1.0, 0.0), gravity=-9.80665): self.joint_coord_count = 0 self.joint_axis_total_count = 0 - self.up_vector = np.array(up_vector) - self.up_axis = np.argmax(np.abs(up_vector)) + self.up_vector = wp.vec3(up_vector) + self.up_axis = wp.vec3(np.argmax(np.abs(up_vector))) self.gravity = gravity # indicates whether a ground plane has been created self._ground_created = False @@ -1366,8 +1365,8 @@ def add_body( self, origin: Transform = wp.transform(), armature: float = 0.0, - com: Vec3 = np.zeros(3), - I_m: Mat33 = np.zeros((3, 3)), + com: Vec3 = wp.vec3(), + I_m: Mat33 = wp.mat33(), m: float = 0.0, name: str = None, ) -> int: @@ -1392,7 +1391,7 @@ def add_body( body_id = len(self.body_mass) # body data - inertia = I_m + np.eye(3) * armature + inertia = I_m + wp.mat33(np.eye(3)) * armature self.body_inertia.append(inertia) self.body_mass.append(m) self.body_com.append(com) @@ -1402,8 +1401,8 @@ def add_body( else: self.body_inv_mass.append(0.0) - if inertia.any(): - self.body_inv_inertia.append(np.linalg.inv(inertia)) + if any(x for x in inertia): + self.body_inv_inertia.append(wp.inverse(inertia)) else: self.body_inv_inertia.append(inertia) @@ -1459,8 +1458,8 @@ def add_joint( else: self.joint_parents[child].append(parent) self.joint_child.append(child) - self.joint_X_p.append([*parent_xform]) - self.joint_X_c.append([*child_xform]) + self.joint_X_p.append(wp.transform(parent_xform)) + self.joint_X_c.append(wp.transform(child_xform)) self.joint_name.append(name or f"joint {self.joint_count}") self.joint_axis_start.append(len(self.joint_axis)) self.joint_axis_dim.append((len(linear_axes), len(angular_axes))) @@ -2331,7 +2330,7 @@ def add_shape_plane( angle = np.arcsin(np.linalg.norm(c)) axis = c / np.linalg.norm(c) rot = wp.quat_from_axis_angle(axis, angle) - scale = (width, length, 0.0) + scale = wp.vec3(width, length, 0.0) return self._add_shape( body, @@ -2390,10 +2389,10 @@ def add_shape_sphere( return self._add_shape( body, - pos, - rot, + wp.vec3(pos), + wp.quat(rot), GEO_SPHERE, - (radius, 0.0, 0.0, 0.0), + wp.vec3(radius, 0.0, 0.0), None, density, ke, @@ -2450,10 +2449,10 @@ def add_shape_box( return self._add_shape( body, - pos, - rot, + wp.vec3(pos), + wp.quat(rot), GEO_BOX, - (hx, hy, hz, 0.0), + wp.vec3(hx, hy, hz), None, density, ke, @@ -2508,19 +2507,19 @@ def add_shape_capsule( """ - q = rot + q = wp.quat(rot) sqh = math.sqrt(0.5) if up_axis == 0: - q = wp.mul(rot, wp.quat(0.0, 0.0, -sqh, sqh)) + q = wp.mul(q, wp.quat(0.0, 0.0, -sqh, sqh)) elif up_axis == 2: - q = wp.mul(rot, wp.quat(sqh, 0.0, 0.0, sqh)) + q = wp.mul(q, wp.quat(sqh, 0.0, 0.0, sqh)) return self._add_shape( body, - pos, - q, + wp.vec3(pos), + wp.quat(q), GEO_CAPSULE, - (radius, half_height, 0.0, 0.0), + wp.vec3(radius, half_height, 0.0), None, density, ke, @@ -2584,10 +2583,10 @@ def add_shape_cylinder( return self._add_shape( body, - pos, - q, + wp.vec3(pos), + wp.quat(q), GEO_CYLINDER, - (radius, half_height, 0.0, 0.0), + wp.vec3(radius, half_height, 0.0), None, density, ke, @@ -2651,10 +2650,10 @@ def add_shape_cone( return self._add_shape( body, - pos, - q, + wp.vec3(pos), + wp.quat(q), GEO_CONE, - (radius, half_height, 0.0, 0.0), + wp.vec3(radius, half_height, 0.0), None, density, ke, @@ -2670,10 +2669,10 @@ def add_shape_cone( def add_shape_mesh( self, body: int, - pos: Vec3 = (0.0, 0.0, 0.0), - rot: Quat = (0.0, 0.0, 0.0, 1.0), + pos: Vec3 = wp.vec3(0.0, 0.0, 0.0), + rot: Quat = wp.quat(0.0, 0.0, 0.0, 1.0), mesh: Mesh = None, - scale: Vec3 = (1.0, 1.0, 1.0), + scale: Vec3 = wp.vec3(1.0, 1.0, 1.0), density: float = default_shape_density, ke: float = default_shape_ke, kd: float = default_shape_kd, @@ -2712,7 +2711,7 @@ def add_shape_mesh( pos, rot, GEO_MESH, - (scale[0], scale[1], scale[2], 0.0), + wp.vec3(scale[0], scale[1], scale[2]), mesh, density, ke, @@ -2765,10 +2764,10 @@ def add_shape_sdf( """ return self._add_shape( body, - pos, - rot, + wp.vec3(pos), + wp.quat(rot), GEO_SDF, - (scale[0], scale[1], scale[2], 0.0), + wp.vec3(scale[0], scale[1], scale[2]), sdf, density, ke, @@ -2859,7 +2858,7 @@ def _add_shape( (m, c, I) = compute_shape_mass(type, scale, src, density, is_solid, thickness) - self._update_body_mass(body, m, I, np.array(pos) + c, np.array(rot)) + self._update_body_mass(body, m, I, pos + c, rot) return shape # particles @@ -2954,9 +2953,9 @@ def add_triangle( """ # compute basis for 2D rest pose - p = np.array(self.particle_q[i]) - q = np.array(self.particle_q[j]) - r = np.array(self.particle_q[k]) + p = self.particle_q[i] + q = self.particle_q[j] + r = self.particle_q[k] qp = q - p rp = r - p @@ -3153,13 +3152,13 @@ def add_edge( """ # compute rest angle if rest is None: - x1 = np.array(self.particle_q[i]) - x2 = np.array(self.particle_q[j]) - x3 = np.array(self.particle_q[k]) - x4 = np.array(self.particle_q[l]) + x1 = self.particle_q[i] + x2 = self.particle_q[j] + x3 = self.particle_q[k] + x4 = self.particle_q[l] - n1 = wp.normalize(np.cross(x3 - x1, x4 - x1)) - n2 = wp.normalize(np.cross(x4 - x2, x3 - x2)) + n1 = wp.normalize(wp.cross(x3 - x1, x4 - x1)) + n2 = wp.normalize(wp.cross(x4 - x2, x3 - x2)) e = wp.normalize(x4 - x3) d = np.clip(np.dot(n2, n1), -1.0, 1.0) @@ -3299,8 +3298,8 @@ def grid_index(x, y, dim_x): for y in range(0, dim_y + 1): for x in range(0, dim_x + 1): - g = np.array((x * cell_x, y * cell_y, 0.0)) - p = np.array(wp.quat_rotate(rot, g)) + pos + g = wp.vec3(x * cell_x, y * cell_y, 0.0) + p = wp.quat_rotate(rot, g) + pos m = mass if x == 0 and fix_left: @@ -3425,7 +3424,7 @@ def add_cloth_mesh( # particles for v in vertices: - p = np.array(wp.quat_rotate(rot, v * scale)) + pos + p = wp.quat_rotate(rot, v * scale) + pos self.add_particle(p, vel, 0.0) @@ -3498,13 +3497,14 @@ def add_particle_grid( radius_mean: float = default_particle_radius, radius_std: float = 0.0, ): + rng = np.random.default_rng() for z in range(dim_z): for y in range(dim_y): for x in range(dim_x): - v = np.array((x * cell_x, y * cell_y, z * cell_z)) + v = wp.vec3(x * cell_x, y * cell_y, z * cell_z) m = mass - p = np.array(wp.quat_rotate(rot, v)) + pos + np.random.rand(3) * jitter + p = wp.quat_rotate(rot, v) + pos + wp.vec3(rng.random(3) * jitter) if radius_std > 0.0: r = radius_mean + np.random.randn() * radius_std @@ -3570,7 +3570,7 @@ def add_soft_grid( for z in range(dim_z + 1): for y in range(dim_y + 1): for x in range(dim_x + 1): - v = np.array((x * cell_x, y * cell_y, z * cell_z)) + v = wp.vec3(x * cell_x, y * cell_y, z * cell_z) m = mass if fix_left and x == 0: @@ -3585,7 +3585,7 @@ def add_soft_grid( if fix_bottom and y == 0: m = 0.0 - p = np.array(wp.quat_rotate(rot, v)) + pos + p = wp.quat_rotate(rot, v) + pos self.add_particle(p, vel, m) @@ -3752,8 +3752,8 @@ def _update_body_mass(self, i, m, I, p, q): else: self.body_inv_mass[i] = 0.0 - if new_inertia.any(): - self.body_inv_inertia[i] = np.linalg.inv(new_inertia) + if any(x for x in new_inertia): + self.body_inv_inertia[i] = wp.inverse(new_inertia) else: self.body_inv_inertia[i] = new_inertia diff --git a/warp/sim/render.py b/warp/sim/render.py index 726060377..020269897 100644 --- a/warp/sim/render.py +++ b/warp/sim/render.py @@ -268,7 +268,7 @@ def populate(self, model: warp.sim.Model): q = wp.quat(tf[3:]) # compute rotation between axis and y axis = axis / np.linalg.norm(axis) - q = q * wp.quat_between_vectors(wp.vec3(*axis), y_axis) + q = q * wp.quat_between_vectors(wp.vec3(axis), y_axis) name = f"joint_{i}_{a}" self.add_shape_instance(name, shape, body, p, q, scale, color1=color, color2=color) self.instance_count += 1 diff --git a/warp/tests/test_func.py b/warp/tests/test_func.py index 9acfd4a8a..109d70a15 100644 --- a/warp/tests/test_func.py +++ b/warp/tests/test_func.py @@ -89,7 +89,7 @@ def test_native_func_export(test, device): q = wp.quat(0.0, 0.0, 0.0, 1.0) assert_np_equal(np.array([*q]), np.array([0.0, 0.0, 0.0, 1.0])) - r = wp.quat_from_axis_angle((1.0, 0.0, 0.0), 2.0) + r = wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), 2.0) assert_np_equal(np.array([*r]), np.array([0.8414709568023682, 0.0, 0.0, 0.5403022170066833]), tol=1.0e-3) q = wp.quat(1.0, 2.0, 3.0, 4.0) @@ -149,7 +149,7 @@ def test_native_func_export(test, device): wp.quat(4.0, 5.0, 6.0, 7.0), ) test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t * (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0), (396.0, 432.0, 720.0, 56.0, 70.0, 84.0, -28.0)) + test.assertSequenceEqual(t * wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0), (396.0, 432.0, 720.0, 56.0, 70.0, 84.0, -28.0)) test.assertSequenceEqual( t * wp.transform((1.0, 2.0, 3.0), (4.0, 5.0, 6.0, 7.0)), (396.0, 432.0, 720.0, 56.0, 70.0, 84.0, -28.0) ) diff --git a/warp/tests/test_model.py b/warp/tests/test_model.py index 750efb5e8..f88e96657 100644 --- a/warp/tests/test_model.py +++ b/warp/tests/test_model.py @@ -35,8 +35,8 @@ def test_add_triangles(self): builder1 = ModelBuilder() builder2 = ModelBuilder() for pt in pts: - builder1.add_particle(pt, [0.0, 0.0, 0.0], 1.0) - builder2.add_particle(pt, [0.0, 0.0, 0.0], 1.0) + builder1.add_particle(wp.vec3(pt), wp.vec3(), 1.0) + builder2.add_particle(wp.vec3(pt), wp.vec3(), 1.0) # test add_triangle(s) with default arguments: areas = builder2.add_triangles(tris[:, 0], tris[:, 1], tris[:, 2]) @@ -85,8 +85,8 @@ def test_add_edges(self): builder1 = ModelBuilder() builder2 = ModelBuilder() for pt in pts: - builder1.add_particle(pt, [0.0, 0.0, 0.0], 1.0) - builder2.add_particle(pt, [0.0, 0.0, 0.0], 1.0) + builder1.add_particle(wp.vec3(pt), wp.vec3(), 1.0) + builder2.add_particle(wp.vec3(pt), wp.vec3(), 1.0) # test defaults: for i in range(2): diff --git a/warp/types.py b/warp/types.py index 05f931548..e7a50e1c1 100644 --- a/warp/types.py +++ b/warp/types.py @@ -582,11 +582,11 @@ def __init__(self, *args, **kwargs): @property def p(self): - return self[0:3] + return vec3(self[0:3]) @property def q(self): - return self[3:7] + return quat(self[3:7]) return transform_t From 676e69d9570e27f3c19788fce78d1073dfb046ab Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Fri, 15 Dec 2023 10:35:16 +1300 Subject: [PATCH 40/50] Pass compound types to built-ins by reference --- warp/context.py | 33 +- warp/native/exports.h | 2354 ++++++++++++++++++++--------------------- 2 files changed, 1197 insertions(+), 1190 deletions(-) diff --git a/warp/context.py b/warp/context.py index 1b788d79a..d196b20f3 100644 --- a/warp/context.py +++ b/warp/context.py @@ -364,12 +364,8 @@ def call_builtin(func: Function, *params) -> Tuple[bool, Any]: return (False, None) # The argument expects a built-in Warp type like a vector or a matrix. - # We need to wrap the given argument into a ctypes' structure - # to ensure that it's passed by value to the dll rather than by reference. - class Param(ctypes.Structure): - _fields_ = [("value", arg_type)] - c_param = Param() + c_param = None if isinstance(param, ctypes.Array): # The given parameter is also a built-in Warp type, so we only need @@ -378,14 +374,14 @@ class Param(ctypes.Structure): return (False, None) if isinstance(param, arg_type): - c_param.value = param + c_param = param else: # Cast the value to its argument type to make sure that it # can be assigned to the field of the `Param` struct. # This could error otherwise when, for example, the field type # is set to `vec3i` while the value is of type `vector(length=3, dtype=int)`, # even though both types are semantically identical. - c_param.value = arg_type(param) + c_param = arg_type(param) else: # Flatten the parameter values into a flat 1-D array. arr = [] @@ -446,18 +442,19 @@ class Param(ctypes.Structure): # Extract the floating-point values. arr = tuple(x.value for x in arr) + c_param = arg_type() if warp.types.type_is_matrix(arg_type): rows, cols = arg_type._shape_ for i in range(rows): idx_start = i * cols idx_end = idx_start + cols - c_param.value[i] = arr[idx_start:idx_end] + c_param[i] = arr[idx_start:idx_end] else: - c_param.value[:] = arr + c_param[:] = arr uses_non_warp_array_type = True - c_params.append(c_param) + c_params.append(ctypes.byref(c_param)) else: if issubclass(arg_type, ctypes.Array): return (False, None) @@ -4232,7 +4229,17 @@ def export_stubs(file): # pragma: no cover def export_builtins(file: io.TextIOBase): # pragma: no cover - def ctype_str(t): + def ctype_arg_str(t): + if isinstance(t, int): + return "int" + elif isinstance(t, float): + return "float" + elif t in warp.types.vector_types: + return f"{t.__name__}&" + else: + return t.__name__ + + def ctype_ret_str(t): if isinstance(t, int): return "int" elif isinstance(t, float): @@ -4259,7 +4266,7 @@ def ctype_str(t): if not simple or f.variadic: continue - args = ", ".join(f"{ctype_str(v)} {k}" for k, v in f.input_types.items()) + args = ", ".join(f"{ctype_arg_str(v)} {k}" for k, v in f.input_types.items()) params = ", ".join(f.input_types.keys()) return_type = "" @@ -4267,7 +4274,7 @@ def ctype_str(t): try: # todo: construct a default value for each of the functions args # so we can generate the return type for overloaded functions - return_type = ctype_str(f.value_func(None, None, None)) + return_type = ctype_ret_str(f.value_func(None, None, None)) except Exception: continue diff --git a/warp/native/exports.h b/warp/native/exports.h index fa35feff6..8f7079d5e 100644 --- a/warp/native/exports.h +++ b/warp/native/exports.h @@ -13,78 +13,78 @@ WP_API void builtin_min_uint16_uint16(uint16 x, uint16 y, uint16* ret) { *ret = WP_API void builtin_min_uint32_uint32(uint32 x, uint32 y, uint32* ret) { *ret = wp::min(x, y); } WP_API void builtin_min_uint64_uint64(uint64 x, uint64 y, uint64* ret) { *ret = wp::min(x, y); } WP_API void builtin_min_uint8_uint8(uint8 x, uint8 y, uint8* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2h_vec2h(vec2h x, vec2h y, vec2h* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3h_vec3h(vec3h x, vec3h y, vec3h* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4h_vec4h(vec4h x, vec4h y, vec4h* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2f_vec2f(vec2f x, vec2f y, vec2f* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3f_vec3f(vec3f x, vec3f y, vec3f* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4f_vec4f(vec4f x, vec4f y, vec4f* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2d_vec2d(vec2d x, vec2d y, vec2d* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3d_vec3d(vec3d x, vec3d y, vec3d* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4d_vec4d(vec4d x, vec4d y, vec4d* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2s_vec2s(vec2s x, vec2s y, vec2s* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3s_vec3s(vec3s x, vec3s y, vec3s* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4s_vec4s(vec4s x, vec4s y, vec4s* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2i_vec2i(vec2i x, vec2i y, vec2i* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3i_vec3i(vec3i x, vec3i y, vec3i* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4i_vec4i(vec4i x, vec4i y, vec4i* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2l_vec2l(vec2l x, vec2l y, vec2l* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3l_vec3l(vec3l x, vec3l y, vec3l* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4l_vec4l(vec4l x, vec4l y, vec4l* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2b_vec2b(vec2b x, vec2b y, vec2b* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3b_vec3b(vec3b x, vec3b y, vec3b* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4b_vec4b(vec4b x, vec4b y, vec4b* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2us_vec2us(vec2us x, vec2us y, vec2us* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3us_vec3us(vec3us x, vec3us y, vec3us* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4us_vec4us(vec4us x, vec4us y, vec4us* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2ui_vec2ui(vec2ui x, vec2ui y, vec2ui* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3ui_vec3ui(vec3ui x, vec3ui y, vec3ui* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4ui_vec4ui(vec4ui x, vec4ui y, vec4ui* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2ul_vec2ul(vec2ul x, vec2ul y, vec2ul* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3ul_vec3ul(vec3ul x, vec3ul y, vec3ul* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4ul_vec4ul(vec4ul x, vec4ul y, vec4ul* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2ub_vec2ub(vec2ub x, vec2ub y, vec2ub* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec3ub_vec3ub(vec3ub x, vec3ub y, vec3ub* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec4ub_vec4ub(vec4ub x, vec4ub y, vec4ub* ret) { *ret = wp::min(x, y); } -WP_API void builtin_min_vec2h(vec2h v, float16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3h(vec3h v, float16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4h(vec4h v, float16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_spatial_vectorh(spatial_vectorh v, float16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2f(vec2f v, float32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3f(vec3f v, float32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4f(vec4f v, float32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_spatial_vectorf(spatial_vectorf v, float32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2d(vec2d v, float64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3d(vec3d v, float64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4d(vec4d v, float64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_spatial_vectord(spatial_vectord v, float64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2s(vec2s v, int16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3s(vec3s v, int16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4s(vec4s v, int16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2i(vec2i v, int32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3i(vec3i v, int32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4i(vec4i v, int32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2l(vec2l v, int64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3l(vec3l v, int64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4l(vec4l v, int64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2b(vec2b v, int8* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3b(vec3b v, int8* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4b(vec4b v, int8* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2us(vec2us v, uint16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3us(vec3us v, uint16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4us(vec4us v, uint16* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2ui(vec2ui v, uint32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3ui(vec3ui v, uint32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4ui(vec4ui v, uint32* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2ul(vec2ul v, uint64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3ul(vec3ul v, uint64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4ul(vec4ul v, uint64* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec2ub(vec2ub v, uint8* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec3ub(vec3ub v, uint8* ret) { *ret = wp::min(v); } -WP_API void builtin_min_vec4ub(vec4ub v, uint8* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2h_vec2h(vec2h& x, vec2h& y, vec2h* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3h_vec3h(vec3h& x, vec3h& y, vec3h* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4h_vec4h(vec4h& x, vec4h& y, vec4h* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2f_vec2f(vec2f& x, vec2f& y, vec2f* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3f_vec3f(vec3f& x, vec3f& y, vec3f* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4f_vec4f(vec4f& x, vec4f& y, vec4f* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2d_vec2d(vec2d& x, vec2d& y, vec2d* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3d_vec3d(vec3d& x, vec3d& y, vec3d* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4d_vec4d(vec4d& x, vec4d& y, vec4d* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2s_vec2s(vec2s& x, vec2s& y, vec2s* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3s_vec3s(vec3s& x, vec3s& y, vec3s* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4s_vec4s(vec4s& x, vec4s& y, vec4s* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2i_vec2i(vec2i& x, vec2i& y, vec2i* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3i_vec3i(vec3i& x, vec3i& y, vec3i* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4i_vec4i(vec4i& x, vec4i& y, vec4i* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2l_vec2l(vec2l& x, vec2l& y, vec2l* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3l_vec3l(vec3l& x, vec3l& y, vec3l* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4l_vec4l(vec4l& x, vec4l& y, vec4l* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2b_vec2b(vec2b& x, vec2b& y, vec2b* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3b_vec3b(vec3b& x, vec3b& y, vec3b* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4b_vec4b(vec4b& x, vec4b& y, vec4b* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2us_vec2us(vec2us& x, vec2us& y, vec2us* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3us_vec3us(vec3us& x, vec3us& y, vec3us* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4us_vec4us(vec4us& x, vec4us& y, vec4us* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2ui_vec2ui(vec2ui& x, vec2ui& y, vec2ui* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3ui_vec3ui(vec3ui& x, vec3ui& y, vec3ui* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4ui_vec4ui(vec4ui& x, vec4ui& y, vec4ui* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2ul_vec2ul(vec2ul& x, vec2ul& y, vec2ul* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3ul_vec3ul(vec3ul& x, vec3ul& y, vec3ul* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4ul_vec4ul(vec4ul& x, vec4ul& y, vec4ul* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2ub_vec2ub(vec2ub& x, vec2ub& y, vec2ub* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec3ub_vec3ub(vec3ub& x, vec3ub& y, vec3ub* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec4ub_vec4ub(vec4ub& x, vec4ub& y, vec4ub* ret) { *ret = wp::min(x, y); } +WP_API void builtin_min_vec2h(vec2h& v, float16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3h(vec3h& v, float16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4h(vec4h& v, float16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_spatial_vectorh(spatial_vectorh& v, float16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2f(vec2f& v, float32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3f(vec3f& v, float32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4f(vec4f& v, float32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_spatial_vectorf(spatial_vectorf& v, float32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2d(vec2d& v, float64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3d(vec3d& v, float64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4d(vec4d& v, float64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_spatial_vectord(spatial_vectord& v, float64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2s(vec2s& v, int16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3s(vec3s& v, int16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4s(vec4s& v, int16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2i(vec2i& v, int32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3i(vec3i& v, int32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4i(vec4i& v, int32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2l(vec2l& v, int64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3l(vec3l& v, int64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4l(vec4l& v, int64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2b(vec2b& v, int8* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3b(vec3b& v, int8* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4b(vec4b& v, int8* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2us(vec2us& v, uint16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3us(vec3us& v, uint16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4us(vec4us& v, uint16* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2ui(vec2ui& v, uint32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3ui(vec3ui& v, uint32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4ui(vec4ui& v, uint32* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2ul(vec2ul& v, uint64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3ul(vec3ul& v, uint64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4ul(vec4ul& v, uint64* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec2ub(vec2ub& v, uint8* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec3ub(vec3ub& v, uint8* ret) { *ret = wp::min(v); } +WP_API void builtin_min_vec4ub(vec4ub& v, uint8* ret) { *ret = wp::min(v); } WP_API void builtin_max_float16_float16(float16 x, float16 y, float16* ret) { *ret = wp::max(x, y); } WP_API void builtin_max_float32_float32(float32 x, float32 y, float32* ret) { *ret = wp::max(x, y); } WP_API void builtin_max_float64_float64(float64 x, float64 y, float64* ret) { *ret = wp::max(x, y); } @@ -96,78 +96,78 @@ WP_API void builtin_max_uint16_uint16(uint16 x, uint16 y, uint16* ret) { *ret = WP_API void builtin_max_uint32_uint32(uint32 x, uint32 y, uint32* ret) { *ret = wp::max(x, y); } WP_API void builtin_max_uint64_uint64(uint64 x, uint64 y, uint64* ret) { *ret = wp::max(x, y); } WP_API void builtin_max_uint8_uint8(uint8 x, uint8 y, uint8* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2h_vec2h(vec2h x, vec2h y, vec2h* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3h_vec3h(vec3h x, vec3h y, vec3h* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4h_vec4h(vec4h x, vec4h y, vec4h* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2f_vec2f(vec2f x, vec2f y, vec2f* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3f_vec3f(vec3f x, vec3f y, vec3f* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4f_vec4f(vec4f x, vec4f y, vec4f* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2d_vec2d(vec2d x, vec2d y, vec2d* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3d_vec3d(vec3d x, vec3d y, vec3d* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4d_vec4d(vec4d x, vec4d y, vec4d* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2s_vec2s(vec2s x, vec2s y, vec2s* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3s_vec3s(vec3s x, vec3s y, vec3s* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4s_vec4s(vec4s x, vec4s y, vec4s* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2i_vec2i(vec2i x, vec2i y, vec2i* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3i_vec3i(vec3i x, vec3i y, vec3i* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4i_vec4i(vec4i x, vec4i y, vec4i* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2l_vec2l(vec2l x, vec2l y, vec2l* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3l_vec3l(vec3l x, vec3l y, vec3l* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4l_vec4l(vec4l x, vec4l y, vec4l* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2b_vec2b(vec2b x, vec2b y, vec2b* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3b_vec3b(vec3b x, vec3b y, vec3b* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4b_vec4b(vec4b x, vec4b y, vec4b* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2us_vec2us(vec2us x, vec2us y, vec2us* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3us_vec3us(vec3us x, vec3us y, vec3us* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4us_vec4us(vec4us x, vec4us y, vec4us* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2ui_vec2ui(vec2ui x, vec2ui y, vec2ui* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3ui_vec3ui(vec3ui x, vec3ui y, vec3ui* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4ui_vec4ui(vec4ui x, vec4ui y, vec4ui* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2ul_vec2ul(vec2ul x, vec2ul y, vec2ul* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3ul_vec3ul(vec3ul x, vec3ul y, vec3ul* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4ul_vec4ul(vec4ul x, vec4ul y, vec4ul* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2ub_vec2ub(vec2ub x, vec2ub y, vec2ub* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec3ub_vec3ub(vec3ub x, vec3ub y, vec3ub* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec4ub_vec4ub(vec4ub x, vec4ub y, vec4ub* ret) { *ret = wp::max(x, y); } -WP_API void builtin_max_vec2h(vec2h v, float16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3h(vec3h v, float16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4h(vec4h v, float16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_spatial_vectorh(spatial_vectorh v, float16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2f(vec2f v, float32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3f(vec3f v, float32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4f(vec4f v, float32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_spatial_vectorf(spatial_vectorf v, float32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2d(vec2d v, float64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3d(vec3d v, float64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4d(vec4d v, float64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_spatial_vectord(spatial_vectord v, float64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2s(vec2s v, int16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3s(vec3s v, int16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4s(vec4s v, int16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2i(vec2i v, int32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3i(vec3i v, int32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4i(vec4i v, int32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2l(vec2l v, int64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3l(vec3l v, int64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4l(vec4l v, int64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2b(vec2b v, int8* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3b(vec3b v, int8* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4b(vec4b v, int8* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2us(vec2us v, uint16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3us(vec3us v, uint16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4us(vec4us v, uint16* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2ui(vec2ui v, uint32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3ui(vec3ui v, uint32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4ui(vec4ui v, uint32* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2ul(vec2ul v, uint64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3ul(vec3ul v, uint64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4ul(vec4ul v, uint64* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec2ub(vec2ub v, uint8* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec3ub(vec3ub v, uint8* ret) { *ret = wp::max(v); } -WP_API void builtin_max_vec4ub(vec4ub v, uint8* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2h_vec2h(vec2h& x, vec2h& y, vec2h* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3h_vec3h(vec3h& x, vec3h& y, vec3h* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4h_vec4h(vec4h& x, vec4h& y, vec4h* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2f_vec2f(vec2f& x, vec2f& y, vec2f* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3f_vec3f(vec3f& x, vec3f& y, vec3f* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4f_vec4f(vec4f& x, vec4f& y, vec4f* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2d_vec2d(vec2d& x, vec2d& y, vec2d* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3d_vec3d(vec3d& x, vec3d& y, vec3d* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4d_vec4d(vec4d& x, vec4d& y, vec4d* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2s_vec2s(vec2s& x, vec2s& y, vec2s* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3s_vec3s(vec3s& x, vec3s& y, vec3s* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4s_vec4s(vec4s& x, vec4s& y, vec4s* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2i_vec2i(vec2i& x, vec2i& y, vec2i* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3i_vec3i(vec3i& x, vec3i& y, vec3i* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4i_vec4i(vec4i& x, vec4i& y, vec4i* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2l_vec2l(vec2l& x, vec2l& y, vec2l* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3l_vec3l(vec3l& x, vec3l& y, vec3l* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4l_vec4l(vec4l& x, vec4l& y, vec4l* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2b_vec2b(vec2b& x, vec2b& y, vec2b* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3b_vec3b(vec3b& x, vec3b& y, vec3b* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4b_vec4b(vec4b& x, vec4b& y, vec4b* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2us_vec2us(vec2us& x, vec2us& y, vec2us* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3us_vec3us(vec3us& x, vec3us& y, vec3us* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4us_vec4us(vec4us& x, vec4us& y, vec4us* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2ui_vec2ui(vec2ui& x, vec2ui& y, vec2ui* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3ui_vec3ui(vec3ui& x, vec3ui& y, vec3ui* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4ui_vec4ui(vec4ui& x, vec4ui& y, vec4ui* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2ul_vec2ul(vec2ul& x, vec2ul& y, vec2ul* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3ul_vec3ul(vec3ul& x, vec3ul& y, vec3ul* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4ul_vec4ul(vec4ul& x, vec4ul& y, vec4ul* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2ub_vec2ub(vec2ub& x, vec2ub& y, vec2ub* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec3ub_vec3ub(vec3ub& x, vec3ub& y, vec3ub* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec4ub_vec4ub(vec4ub& x, vec4ub& y, vec4ub* ret) { *ret = wp::max(x, y); } +WP_API void builtin_max_vec2h(vec2h& v, float16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3h(vec3h& v, float16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4h(vec4h& v, float16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_spatial_vectorh(spatial_vectorh& v, float16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2f(vec2f& v, float32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3f(vec3f& v, float32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4f(vec4f& v, float32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_spatial_vectorf(spatial_vectorf& v, float32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2d(vec2d& v, float64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3d(vec3d& v, float64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4d(vec4d& v, float64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_spatial_vectord(spatial_vectord& v, float64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2s(vec2s& v, int16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3s(vec3s& v, int16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4s(vec4s& v, int16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2i(vec2i& v, int32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3i(vec3i& v, int32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4i(vec4i& v, int32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2l(vec2l& v, int64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3l(vec3l& v, int64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4l(vec4l& v, int64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2b(vec2b& v, int8* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3b(vec3b& v, int8* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4b(vec4b& v, int8* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2us(vec2us& v, uint16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3us(vec3us& v, uint16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4us(vec4us& v, uint16* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2ui(vec2ui& v, uint32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3ui(vec3ui& v, uint32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4ui(vec4ui& v, uint32* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2ul(vec2ul& v, uint64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3ul(vec3ul& v, uint64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4ul(vec4ul& v, uint64* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec2ub(vec2ub& v, uint8* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec3ub(vec3ub& v, uint8* ret) { *ret = wp::max(v); } +WP_API void builtin_max_vec4ub(vec4ub& v, uint8* ret) { *ret = wp::max(v); } WP_API void builtin_clamp_float16_float16_float16(float16 x, float16 a, float16 b, float16* ret) { *ret = wp::clamp(x, a, b); } WP_API void builtin_clamp_float32_float32_float32(float32 x, float32 a, float32 b, float32* ret) { *ret = wp::clamp(x, a, b); } WP_API void builtin_clamp_float64_float64_float64(float64 x, float64 a, float64 b, float64* ret) { *ret = wp::clamp(x, a, b); } @@ -298,494 +298,494 @@ WP_API void builtin_ceil_float64(float64 x, float64* ret) { *ret = wp::ceil(x); WP_API void builtin_frac_float16(float16 x, float16* ret) { *ret = wp::frac(x); } WP_API void builtin_frac_float32(float32 x, float32* ret) { *ret = wp::frac(x); } WP_API void builtin_frac_float64(float64 x, float64* ret) { *ret = wp::frac(x); } -WP_API void builtin_dot_vec2h_vec2h(vec2h x, vec2h y, float16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3h_vec3h(vec3h x, vec3h y, float16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4h_vec4h(vec4h x, vec4h y, float16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, float16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2f_vec2f(vec2f x, vec2f y, float32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3f_vec3f(vec3f x, vec3f y, float32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4f_vec4f(vec4f x, vec4f y, float32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, float32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2d_vec2d(vec2d x, vec2d y, float64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3d_vec3d(vec3d x, vec3d y, float64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4d_vec4d(vec4d x, vec4d y, float64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, float64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2s_vec2s(vec2s x, vec2s y, int16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3s_vec3s(vec3s x, vec3s y, int16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4s_vec4s(vec4s x, vec4s y, int16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2i_vec2i(vec2i x, vec2i y, int32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3i_vec3i(vec3i x, vec3i y, int32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4i_vec4i(vec4i x, vec4i y, int32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2l_vec2l(vec2l x, vec2l y, int64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3l_vec3l(vec3l x, vec3l y, int64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4l_vec4l(vec4l x, vec4l y, int64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2b_vec2b(vec2b x, vec2b y, int8* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3b_vec3b(vec3b x, vec3b y, int8* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4b_vec4b(vec4b x, vec4b y, int8* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2us_vec2us(vec2us x, vec2us y, uint16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3us_vec3us(vec3us x, vec3us y, uint16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4us_vec4us(vec4us x, vec4us y, uint16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2ui_vec2ui(vec2ui x, vec2ui y, uint32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3ui_vec3ui(vec3ui x, vec3ui y, uint32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4ui_vec4ui(vec4ui x, vec4ui y, uint32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2ul_vec2ul(vec2ul x, vec2ul y, uint64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3ul_vec3ul(vec3ul x, vec3ul y, uint64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4ul_vec4ul(vec4ul x, vec4ul y, uint64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec2ub_vec2ub(vec2ub x, vec2ub y, uint8* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec3ub_vec3ub(vec3ub x, vec3ub y, uint8* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_vec4ub_vec4ub(vec4ub x, vec4ub y, uint8* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_quath_quath(quath x, quath y, float16* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_quatf_quatf(quatf x, quatf y, float32* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_dot_quatd_quatd(quatd x, quatd y, float64* ret) { *ret = wp::dot(x, y); } -WP_API void builtin_ddot_mat22h_mat22h(mat22h x, mat22h y, float16* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat33h_mat33h(mat33h x, mat33h y, float16* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat44h_mat44h(mat44h x, mat44h y, float16* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_spatial_matrixh_spatial_matrixh(spatial_matrixh x, spatial_matrixh y, float16* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat22f_mat22f(mat22f x, mat22f y, float32* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat33f_mat33f(mat33f x, mat33f y, float32* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat44f_mat44f(mat44f x, mat44f y, float32* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_spatial_matrixf_spatial_matrixf(spatial_matrixf x, spatial_matrixf y, float32* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat22d_mat22d(mat22d x, mat22d y, float64* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat33d_mat33d(mat33d x, mat33d y, float64* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_mat44d_mat44d(mat44d x, mat44d y, float64* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_ddot_spatial_matrixd_spatial_matrixd(spatial_matrixd x, spatial_matrixd y, float64* ret) { *ret = wp::ddot(x, y); } -WP_API void builtin_argmin_vec2h(vec2h v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3h(vec3h v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4h(vec4h v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_spatial_vectorh(spatial_vectorh v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2f(vec2f v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3f(vec3f v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4f(vec4f v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_spatial_vectorf(spatial_vectorf v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2d(vec2d v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3d(vec3d v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4d(vec4d v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_spatial_vectord(spatial_vectord v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2s(vec2s v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3s(vec3s v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4s(vec4s v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2i(vec2i v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3i(vec3i v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4i(vec4i v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2l(vec2l v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3l(vec3l v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4l(vec4l v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2b(vec2b v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3b(vec3b v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4b(vec4b v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2us(vec2us v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3us(vec3us v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4us(vec4us v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2ui(vec2ui v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3ui(vec3ui v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4ui(vec4ui v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2ul(vec2ul v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3ul(vec3ul v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4ul(vec4ul v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec2ub(vec2ub v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec3ub(vec3ub v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmin_vec4ub(vec4ub v, uint32* ret) { *ret = wp::argmin(v); } -WP_API void builtin_argmax_vec2h(vec2h v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3h(vec3h v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4h(vec4h v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_spatial_vectorh(spatial_vectorh v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2f(vec2f v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3f(vec3f v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4f(vec4f v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_spatial_vectorf(spatial_vectorf v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2d(vec2d v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3d(vec3d v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4d(vec4d v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_spatial_vectord(spatial_vectord v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2s(vec2s v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3s(vec3s v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4s(vec4s v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2i(vec2i v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3i(vec3i v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4i(vec4i v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2l(vec2l v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3l(vec3l v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4l(vec4l v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2b(vec2b v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3b(vec3b v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4b(vec4b v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2us(vec2us v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3us(vec3us v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4us(vec4us v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2ui(vec2ui v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3ui(vec3ui v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4ui(vec4ui v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2ul(vec2ul v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3ul(vec3ul v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4ul(vec4ul v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec2ub(vec2ub v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec3ub(vec3ub v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_argmax_vec4ub(vec4ub v, uint32* ret) { *ret = wp::argmax(v); } -WP_API void builtin_outer_vec2h_vec2h(vec2h x, vec2h y, mat22h* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec3h_vec3h(vec3h x, vec3h y, mat33h* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec4h_vec4h(vec4h x, vec4h y, mat44h* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, spatial_matrixh* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec2f_vec2f(vec2f x, vec2f y, mat22f* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec3f_vec3f(vec3f x, vec3f y, mat33f* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec4f_vec4f(vec4f x, vec4f y, mat44f* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, spatial_matrixf* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec2d_vec2d(vec2d x, vec2d y, mat22d* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec3d_vec3d(vec3d x, vec3d y, mat33d* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_vec4d_vec4d(vec4d x, vec4d y, mat44d* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_outer_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, spatial_matrixd* ret) { *ret = wp::outer(x, y); } -WP_API void builtin_cross_vec3h_vec3h(vec3h x, vec3h y, vec3h* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3f_vec3f(vec3f x, vec3f y, vec3f* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3d_vec3d(vec3d x, vec3d y, vec3d* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3s_vec3s(vec3s x, vec3s y, vec3s* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3i_vec3i(vec3i x, vec3i y, vec3i* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3l_vec3l(vec3l x, vec3l y, vec3l* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3b_vec3b(vec3b x, vec3b y, vec3b* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3us_vec3us(vec3us x, vec3us y, vec3us* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3ui_vec3ui(vec3ui x, vec3ui y, vec3ui* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3ul_vec3ul(vec3ul x, vec3ul y, vec3ul* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_cross_vec3ub_vec3ub(vec3ub x, vec3ub y, vec3ub* ret) { *ret = wp::cross(x, y); } -WP_API void builtin_skew_vec3h(vec3h x, mat33h* ret) { *ret = wp::skew(x); } -WP_API void builtin_skew_vec3f(vec3f x, mat33f* ret) { *ret = wp::skew(x); } -WP_API void builtin_skew_vec3d(vec3d x, mat33d* ret) { *ret = wp::skew(x); } -WP_API void builtin_length_vec2h(vec2h x, float16* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec3h(vec3h x, float16* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec4h(vec4h x, float16* ret) { *ret = wp::length(x); } -WP_API void builtin_length_spatial_vectorh(spatial_vectorh x, float16* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec2f(vec2f x, float32* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec3f(vec3f x, float32* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec4f(vec4f x, float32* ret) { *ret = wp::length(x); } -WP_API void builtin_length_spatial_vectorf(spatial_vectorf x, float32* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec2d(vec2d x, float64* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec3d(vec3d x, float64* ret) { *ret = wp::length(x); } -WP_API void builtin_length_vec4d(vec4d x, float64* ret) { *ret = wp::length(x); } -WP_API void builtin_length_spatial_vectord(spatial_vectord x, float64* ret) { *ret = wp::length(x); } -WP_API void builtin_length_quath(quath x, float16* ret) { *ret = wp::length(x); } -WP_API void builtin_length_quatf(quatf x, float32* ret) { *ret = wp::length(x); } -WP_API void builtin_length_quatd(quatd x, float64* ret) { *ret = wp::length(x); } -WP_API void builtin_length_sq_vec2h(vec2h x, float16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3h(vec3h x, float16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4h(vec4h x, float16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_spatial_vectorh(spatial_vectorh x, float16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2f(vec2f x, float32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3f(vec3f x, float32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4f(vec4f x, float32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_spatial_vectorf(spatial_vectorf x, float32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2d(vec2d x, float64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3d(vec3d x, float64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4d(vec4d x, float64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_spatial_vectord(spatial_vectord x, float64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2s(vec2s x, int16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3s(vec3s x, int16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4s(vec4s x, int16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2i(vec2i x, int32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3i(vec3i x, int32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4i(vec4i x, int32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2l(vec2l x, int64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3l(vec3l x, int64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4l(vec4l x, int64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2b(vec2b x, int8* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3b(vec3b x, int8* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4b(vec4b x, int8* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2us(vec2us x, uint16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3us(vec3us x, uint16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4us(vec4us x, uint16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2ui(vec2ui x, uint32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3ui(vec3ui x, uint32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4ui(vec4ui x, uint32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2ul(vec2ul x, uint64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3ul(vec3ul x, uint64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4ul(vec4ul x, uint64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec2ub(vec2ub x, uint8* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec3ub(vec3ub x, uint8* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_vec4ub(vec4ub x, uint8* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_quath(quath x, float16* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_quatf(quatf x, float32* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_length_sq_quatd(quatd x, float64* ret) { *ret = wp::length_sq(x); } -WP_API void builtin_normalize_vec2h(vec2h x, vec2h* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec3h(vec3h x, vec3h* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec4h(vec4h x, vec4h* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_spatial_vectorh(spatial_vectorh x, spatial_vectorh* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec2f(vec2f x, vec2f* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec3f(vec3f x, vec3f* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec4f(vec4f x, vec4f* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_spatial_vectorf(spatial_vectorf x, spatial_vectorf* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec2d(vec2d x, vec2d* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec3d(vec3d x, vec3d* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_vec4d(vec4d x, vec4d* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_spatial_vectord(spatial_vectord x, spatial_vectord* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_quath(quath x, quath* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_quatf(quatf x, quatf* ret) { *ret = wp::normalize(x); } -WP_API void builtin_normalize_quatd(quatd x, quatd* ret) { *ret = wp::normalize(x); } -WP_API void builtin_transpose_mat22h(mat22h m, mat22h* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat33h(mat33h m, mat33h* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat44h(mat44h m, mat44h* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_spatial_matrixh(spatial_matrixh m, spatial_matrixh* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat22f(mat22f m, mat22f* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat33f(mat33f m, mat33f* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat44f(mat44f m, mat44f* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_spatial_matrixf(spatial_matrixf m, spatial_matrixf* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat22d(mat22d m, mat22d* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat33d(mat33d m, mat33d* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_mat44d(mat44d m, mat44d* ret) { *ret = wp::transpose(m); } -WP_API void builtin_transpose_spatial_matrixd(spatial_matrixd m, spatial_matrixd* ret) { *ret = wp::transpose(m); } -WP_API void builtin_inverse_mat22h(mat22h m, mat22h* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat22f(mat22f m, mat22f* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat22d(mat22d m, mat22d* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat33h(mat33h m, mat33h* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat33f(mat33f m, mat33f* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat33d(mat33d m, mat33d* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat44h(mat44h m, mat44h* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat44f(mat44f m, mat44f* ret) { *ret = wp::inverse(m); } -WP_API void builtin_inverse_mat44d(mat44d m, mat44d* ret) { *ret = wp::inverse(m); } -WP_API void builtin_determinant_mat22h(mat22h m, float16* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat22f(mat22f m, float32* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat22d(mat22d m, float64* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat33h(mat33h m, float16* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat33f(mat33f m, float32* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat33d(mat33d m, float64* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat44h(mat44h m, float16* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat44f(mat44f m, float32* ret) { *ret = wp::determinant(m); } -WP_API void builtin_determinant_mat44d(mat44d m, float64* ret) { *ret = wp::determinant(m); } -WP_API void builtin_trace_mat22h(mat22h m, float16* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat33h(mat33h m, float16* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat44h(mat44h m, float16* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_spatial_matrixh(spatial_matrixh m, float16* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat22f(mat22f m, float32* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat33f(mat33f m, float32* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat44f(mat44f m, float32* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_spatial_matrixf(spatial_matrixf m, float32* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat22d(mat22d m, float64* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat33d(mat33d m, float64* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_mat44d(mat44d m, float64* ret) { *ret = wp::trace(m); } -WP_API void builtin_trace_spatial_matrixd(spatial_matrixd m, float64* ret) { *ret = wp::trace(m); } -WP_API void builtin_diag_vec2h(vec2h d, mat22h* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec3h(vec3h d, mat33h* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec4h(vec4h d, mat44h* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_spatial_vectorh(spatial_vectorh d, spatial_matrixh* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec2f(vec2f d, mat22f* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec3f(vec3f d, mat33f* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec4f(vec4f d, mat44f* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_spatial_vectorf(spatial_vectorf d, spatial_matrixf* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec2d(vec2d d, mat22d* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec3d(vec3d d, mat33d* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_vec4d(vec4d d, mat44d* ret) { *ret = wp::diag(d); } -WP_API void builtin_diag_spatial_vectord(spatial_vectord d, spatial_matrixd* ret) { *ret = wp::diag(d); } -WP_API void builtin_get_diag_mat22h(mat22h m, vec2h* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat33h(mat33h m, vec3h* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat44h(mat44h m, vec4h* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_spatial_matrixh(spatial_matrixh m, spatial_vectorh* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat22f(mat22f m, vec2f* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat33f(mat33f m, vec3f* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat44f(mat44f m, vec4f* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_spatial_matrixf(spatial_matrixf m, spatial_vectorf* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat22d(mat22d m, vec2d* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat33d(mat33d m, vec3d* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_mat44d(mat44d m, vec4d* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_get_diag_spatial_matrixd(spatial_matrixd m, spatial_vectord* ret) { *ret = wp::get_diag(m); } -WP_API void builtin_cw_mul_vec2h_vec2h(vec2h x, vec2h y, vec2h* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3h_vec3h(vec3h x, vec3h y, vec3h* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4h_vec4h(vec4h x, vec4h y, vec4h* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2f_vec2f(vec2f x, vec2f y, vec2f* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3f_vec3f(vec3f x, vec3f y, vec3f* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4f_vec4f(vec4f x, vec4f y, vec4f* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2d_vec2d(vec2d x, vec2d y, vec2d* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3d_vec3d(vec3d x, vec3d y, vec3d* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4d_vec4d(vec4d x, vec4d y, vec4d* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2s_vec2s(vec2s x, vec2s y, vec2s* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3s_vec3s(vec3s x, vec3s y, vec3s* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4s_vec4s(vec4s x, vec4s y, vec4s* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2i_vec2i(vec2i x, vec2i y, vec2i* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3i_vec3i(vec3i x, vec3i y, vec3i* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4i_vec4i(vec4i x, vec4i y, vec4i* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2l_vec2l(vec2l x, vec2l y, vec2l* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3l_vec3l(vec3l x, vec3l y, vec3l* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4l_vec4l(vec4l x, vec4l y, vec4l* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2b_vec2b(vec2b x, vec2b y, vec2b* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3b_vec3b(vec3b x, vec3b y, vec3b* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4b_vec4b(vec4b x, vec4b y, vec4b* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2us_vec2us(vec2us x, vec2us y, vec2us* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3us_vec3us(vec3us x, vec3us y, vec3us* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4us_vec4us(vec4us x, vec4us y, vec4us* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2ui_vec2ui(vec2ui x, vec2ui y, vec2ui* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3ui_vec3ui(vec3ui x, vec3ui y, vec3ui* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4ui_vec4ui(vec4ui x, vec4ui y, vec4ui* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2ul_vec2ul(vec2ul x, vec2ul y, vec2ul* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3ul_vec3ul(vec3ul x, vec3ul y, vec3ul* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4ul_vec4ul(vec4ul x, vec4ul y, vec4ul* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec2ub_vec2ub(vec2ub x, vec2ub y, vec2ub* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec3ub_vec3ub(vec3ub x, vec3ub y, vec3ub* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_vec4ub_vec4ub(vec4ub x, vec4ub y, vec4ub* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat22h_mat22h(mat22h x, mat22h y, mat22h* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat33h_mat33h(mat33h x, mat33h y, mat33h* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat44h_mat44h(mat44h x, mat44h y, mat44h* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_spatial_matrixh_spatial_matrixh(spatial_matrixh x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat22f_mat22f(mat22f x, mat22f y, mat22f* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat33f_mat33f(mat33f x, mat33f y, mat33f* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat44f_mat44f(mat44f x, mat44f y, mat44f* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_spatial_matrixf_spatial_matrixf(spatial_matrixf x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat22d_mat22d(mat22d x, mat22d y, mat22d* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat33d_mat33d(mat33d x, mat33d y, mat33d* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_mat44d_mat44d(mat44d x, mat44d y, mat44d* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_mul_spatial_matrixd_spatial_matrixd(spatial_matrixd x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::cw_mul(x, y); } -WP_API void builtin_cw_div_vec2h_vec2h(vec2h x, vec2h y, vec2h* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3h_vec3h(vec3h x, vec3h y, vec3h* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4h_vec4h(vec4h x, vec4h y, vec4h* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2f_vec2f(vec2f x, vec2f y, vec2f* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3f_vec3f(vec3f x, vec3f y, vec3f* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4f_vec4f(vec4f x, vec4f y, vec4f* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2d_vec2d(vec2d x, vec2d y, vec2d* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3d_vec3d(vec3d x, vec3d y, vec3d* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4d_vec4d(vec4d x, vec4d y, vec4d* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2s_vec2s(vec2s x, vec2s y, vec2s* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3s_vec3s(vec3s x, vec3s y, vec3s* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4s_vec4s(vec4s x, vec4s y, vec4s* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2i_vec2i(vec2i x, vec2i y, vec2i* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3i_vec3i(vec3i x, vec3i y, vec3i* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4i_vec4i(vec4i x, vec4i y, vec4i* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2l_vec2l(vec2l x, vec2l y, vec2l* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3l_vec3l(vec3l x, vec3l y, vec3l* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4l_vec4l(vec4l x, vec4l y, vec4l* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2b_vec2b(vec2b x, vec2b y, vec2b* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3b_vec3b(vec3b x, vec3b y, vec3b* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4b_vec4b(vec4b x, vec4b y, vec4b* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2us_vec2us(vec2us x, vec2us y, vec2us* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3us_vec3us(vec3us x, vec3us y, vec3us* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4us_vec4us(vec4us x, vec4us y, vec4us* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2ui_vec2ui(vec2ui x, vec2ui y, vec2ui* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3ui_vec3ui(vec3ui x, vec3ui y, vec3ui* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4ui_vec4ui(vec4ui x, vec4ui y, vec4ui* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2ul_vec2ul(vec2ul x, vec2ul y, vec2ul* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3ul_vec3ul(vec3ul x, vec3ul y, vec3ul* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4ul_vec4ul(vec4ul x, vec4ul y, vec4ul* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec2ub_vec2ub(vec2ub x, vec2ub y, vec2ub* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec3ub_vec3ub(vec3ub x, vec3ub y, vec3ub* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_vec4ub_vec4ub(vec4ub x, vec4ub y, vec4ub* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat22h_mat22h(mat22h x, mat22h y, mat22h* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat33h_mat33h(mat33h x, mat33h y, mat33h* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat44h_mat44h(mat44h x, mat44h y, mat44h* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_spatial_matrixh_spatial_matrixh(spatial_matrixh x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat22f_mat22f(mat22f x, mat22f y, mat22f* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat33f_mat33f(mat33f x, mat33f y, mat33f* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat44f_mat44f(mat44f x, mat44f y, mat44f* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_spatial_matrixf_spatial_matrixf(spatial_matrixf x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat22d_mat22d(mat22d x, mat22d y, mat22d* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat33d_mat33d(mat33d x, mat33d y, mat33d* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_mat44d_mat44d(mat44d x, mat44d y, mat44d* ret) { *ret = wp::cw_div(x, y); } -WP_API void builtin_cw_div_spatial_matrixd_spatial_matrixd(spatial_matrixd x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_dot_vec2h_vec2h(vec2h& x, vec2h& y, float16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3h_vec3h(vec3h& x, vec3h& y, float16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4h_vec4h(vec4h& x, vec4h& y, float16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, float16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2f_vec2f(vec2f& x, vec2f& y, float32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3f_vec3f(vec3f& x, vec3f& y, float32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4f_vec4f(vec4f& x, vec4f& y, float32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, float32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2d_vec2d(vec2d& x, vec2d& y, float64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3d_vec3d(vec3d& x, vec3d& y, float64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4d_vec4d(vec4d& x, vec4d& y, float64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, float64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2s_vec2s(vec2s& x, vec2s& y, int16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3s_vec3s(vec3s& x, vec3s& y, int16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4s_vec4s(vec4s& x, vec4s& y, int16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2i_vec2i(vec2i& x, vec2i& y, int32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3i_vec3i(vec3i& x, vec3i& y, int32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4i_vec4i(vec4i& x, vec4i& y, int32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2l_vec2l(vec2l& x, vec2l& y, int64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3l_vec3l(vec3l& x, vec3l& y, int64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4l_vec4l(vec4l& x, vec4l& y, int64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2b_vec2b(vec2b& x, vec2b& y, int8* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3b_vec3b(vec3b& x, vec3b& y, int8* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4b_vec4b(vec4b& x, vec4b& y, int8* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2us_vec2us(vec2us& x, vec2us& y, uint16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3us_vec3us(vec3us& x, vec3us& y, uint16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4us_vec4us(vec4us& x, vec4us& y, uint16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2ui_vec2ui(vec2ui& x, vec2ui& y, uint32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3ui_vec3ui(vec3ui& x, vec3ui& y, uint32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4ui_vec4ui(vec4ui& x, vec4ui& y, uint32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2ul_vec2ul(vec2ul& x, vec2ul& y, uint64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3ul_vec3ul(vec3ul& x, vec3ul& y, uint64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4ul_vec4ul(vec4ul& x, vec4ul& y, uint64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec2ub_vec2ub(vec2ub& x, vec2ub& y, uint8* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec3ub_vec3ub(vec3ub& x, vec3ub& y, uint8* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_vec4ub_vec4ub(vec4ub& x, vec4ub& y, uint8* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_quath_quath(quath& x, quath& y, float16* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_quatf_quatf(quatf& x, quatf& y, float32* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_dot_quatd_quatd(quatd& x, quatd& y, float64* ret) { *ret = wp::dot(x, y); } +WP_API void builtin_ddot_mat22h_mat22h(mat22h& x, mat22h& y, float16* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat33h_mat33h(mat33h& x, mat33h& y, float16* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat44h_mat44h(mat44h& x, mat44h& y, float16* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_spatial_matrixh_spatial_matrixh(spatial_matrixh& x, spatial_matrixh& y, float16* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat22f_mat22f(mat22f& x, mat22f& y, float32* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat33f_mat33f(mat33f& x, mat33f& y, float32* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat44f_mat44f(mat44f& x, mat44f& y, float32* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_spatial_matrixf_spatial_matrixf(spatial_matrixf& x, spatial_matrixf& y, float32* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat22d_mat22d(mat22d& x, mat22d& y, float64* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat33d_mat33d(mat33d& x, mat33d& y, float64* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_mat44d_mat44d(mat44d& x, mat44d& y, float64* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_ddot_spatial_matrixd_spatial_matrixd(spatial_matrixd& x, spatial_matrixd& y, float64* ret) { *ret = wp::ddot(x, y); } +WP_API void builtin_argmin_vec2h(vec2h& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3h(vec3h& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4h(vec4h& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_spatial_vectorh(spatial_vectorh& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2f(vec2f& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3f(vec3f& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4f(vec4f& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_spatial_vectorf(spatial_vectorf& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2d(vec2d& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3d(vec3d& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4d(vec4d& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_spatial_vectord(spatial_vectord& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2s(vec2s& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3s(vec3s& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4s(vec4s& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2i(vec2i& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3i(vec3i& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4i(vec4i& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2l(vec2l& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3l(vec3l& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4l(vec4l& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2b(vec2b& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3b(vec3b& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4b(vec4b& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2us(vec2us& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3us(vec3us& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4us(vec4us& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2ui(vec2ui& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3ui(vec3ui& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4ui(vec4ui& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2ul(vec2ul& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3ul(vec3ul& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4ul(vec4ul& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec2ub(vec2ub& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec3ub(vec3ub& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmin_vec4ub(vec4ub& v, uint32* ret) { *ret = wp::argmin(v); } +WP_API void builtin_argmax_vec2h(vec2h& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3h(vec3h& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4h(vec4h& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_spatial_vectorh(spatial_vectorh& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2f(vec2f& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3f(vec3f& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4f(vec4f& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_spatial_vectorf(spatial_vectorf& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2d(vec2d& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3d(vec3d& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4d(vec4d& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_spatial_vectord(spatial_vectord& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2s(vec2s& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3s(vec3s& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4s(vec4s& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2i(vec2i& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3i(vec3i& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4i(vec4i& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2l(vec2l& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3l(vec3l& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4l(vec4l& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2b(vec2b& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3b(vec3b& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4b(vec4b& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2us(vec2us& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3us(vec3us& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4us(vec4us& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2ui(vec2ui& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3ui(vec3ui& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4ui(vec4ui& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2ul(vec2ul& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3ul(vec3ul& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4ul(vec4ul& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec2ub(vec2ub& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec3ub(vec3ub& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_argmax_vec4ub(vec4ub& v, uint32* ret) { *ret = wp::argmax(v); } +WP_API void builtin_outer_vec2h_vec2h(vec2h& x, vec2h& y, mat22h* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec3h_vec3h(vec3h& x, vec3h& y, mat33h* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec4h_vec4h(vec4h& x, vec4h& y, mat44h* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, spatial_matrixh* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec2f_vec2f(vec2f& x, vec2f& y, mat22f* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec3f_vec3f(vec3f& x, vec3f& y, mat33f* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec4f_vec4f(vec4f& x, vec4f& y, mat44f* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, spatial_matrixf* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec2d_vec2d(vec2d& x, vec2d& y, mat22d* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec3d_vec3d(vec3d& x, vec3d& y, mat33d* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_vec4d_vec4d(vec4d& x, vec4d& y, mat44d* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_outer_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, spatial_matrixd* ret) { *ret = wp::outer(x, y); } +WP_API void builtin_cross_vec3h_vec3h(vec3h& x, vec3h& y, vec3h* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3f_vec3f(vec3f& x, vec3f& y, vec3f* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3d_vec3d(vec3d& x, vec3d& y, vec3d* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3s_vec3s(vec3s& x, vec3s& y, vec3s* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3i_vec3i(vec3i& x, vec3i& y, vec3i* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3l_vec3l(vec3l& x, vec3l& y, vec3l* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3b_vec3b(vec3b& x, vec3b& y, vec3b* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3us_vec3us(vec3us& x, vec3us& y, vec3us* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3ui_vec3ui(vec3ui& x, vec3ui& y, vec3ui* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3ul_vec3ul(vec3ul& x, vec3ul& y, vec3ul* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_cross_vec3ub_vec3ub(vec3ub& x, vec3ub& y, vec3ub* ret) { *ret = wp::cross(x, y); } +WP_API void builtin_skew_vec3h(vec3h& x, mat33h* ret) { *ret = wp::skew(x); } +WP_API void builtin_skew_vec3f(vec3f& x, mat33f* ret) { *ret = wp::skew(x); } +WP_API void builtin_skew_vec3d(vec3d& x, mat33d* ret) { *ret = wp::skew(x); } +WP_API void builtin_length_vec2h(vec2h& x, float16* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec3h(vec3h& x, float16* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec4h(vec4h& x, float16* ret) { *ret = wp::length(x); } +WP_API void builtin_length_spatial_vectorh(spatial_vectorh& x, float16* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec2f(vec2f& x, float32* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec3f(vec3f& x, float32* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec4f(vec4f& x, float32* ret) { *ret = wp::length(x); } +WP_API void builtin_length_spatial_vectorf(spatial_vectorf& x, float32* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec2d(vec2d& x, float64* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec3d(vec3d& x, float64* ret) { *ret = wp::length(x); } +WP_API void builtin_length_vec4d(vec4d& x, float64* ret) { *ret = wp::length(x); } +WP_API void builtin_length_spatial_vectord(spatial_vectord& x, float64* ret) { *ret = wp::length(x); } +WP_API void builtin_length_quath(quath& x, float16* ret) { *ret = wp::length(x); } +WP_API void builtin_length_quatf(quatf& x, float32* ret) { *ret = wp::length(x); } +WP_API void builtin_length_quatd(quatd& x, float64* ret) { *ret = wp::length(x); } +WP_API void builtin_length_sq_vec2h(vec2h& x, float16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3h(vec3h& x, float16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4h(vec4h& x, float16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_spatial_vectorh(spatial_vectorh& x, float16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2f(vec2f& x, float32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3f(vec3f& x, float32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4f(vec4f& x, float32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_spatial_vectorf(spatial_vectorf& x, float32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2d(vec2d& x, float64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3d(vec3d& x, float64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4d(vec4d& x, float64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_spatial_vectord(spatial_vectord& x, float64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2s(vec2s& x, int16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3s(vec3s& x, int16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4s(vec4s& x, int16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2i(vec2i& x, int32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3i(vec3i& x, int32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4i(vec4i& x, int32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2l(vec2l& x, int64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3l(vec3l& x, int64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4l(vec4l& x, int64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2b(vec2b& x, int8* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3b(vec3b& x, int8* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4b(vec4b& x, int8* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2us(vec2us& x, uint16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3us(vec3us& x, uint16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4us(vec4us& x, uint16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2ui(vec2ui& x, uint32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3ui(vec3ui& x, uint32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4ui(vec4ui& x, uint32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2ul(vec2ul& x, uint64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3ul(vec3ul& x, uint64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4ul(vec4ul& x, uint64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec2ub(vec2ub& x, uint8* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec3ub(vec3ub& x, uint8* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_vec4ub(vec4ub& x, uint8* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_quath(quath& x, float16* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_quatf(quatf& x, float32* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_length_sq_quatd(quatd& x, float64* ret) { *ret = wp::length_sq(x); } +WP_API void builtin_normalize_vec2h(vec2h& x, vec2h* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec3h(vec3h& x, vec3h* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec4h(vec4h& x, vec4h* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_spatial_vectorh(spatial_vectorh& x, spatial_vectorh* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec2f(vec2f& x, vec2f* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec3f(vec3f& x, vec3f* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec4f(vec4f& x, vec4f* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_spatial_vectorf(spatial_vectorf& x, spatial_vectorf* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec2d(vec2d& x, vec2d* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec3d(vec3d& x, vec3d* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_vec4d(vec4d& x, vec4d* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_spatial_vectord(spatial_vectord& x, spatial_vectord* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_quath(quath& x, quath* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_quatf(quatf& x, quatf* ret) { *ret = wp::normalize(x); } +WP_API void builtin_normalize_quatd(quatd& x, quatd* ret) { *ret = wp::normalize(x); } +WP_API void builtin_transpose_mat22h(mat22h& m, mat22h* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat33h(mat33h& m, mat33h* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat44h(mat44h& m, mat44h* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_spatial_matrixh(spatial_matrixh& m, spatial_matrixh* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat22f(mat22f& m, mat22f* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat33f(mat33f& m, mat33f* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat44f(mat44f& m, mat44f* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_spatial_matrixf(spatial_matrixf& m, spatial_matrixf* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat22d(mat22d& m, mat22d* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat33d(mat33d& m, mat33d* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_mat44d(mat44d& m, mat44d* ret) { *ret = wp::transpose(m); } +WP_API void builtin_transpose_spatial_matrixd(spatial_matrixd& m, spatial_matrixd* ret) { *ret = wp::transpose(m); } +WP_API void builtin_inverse_mat22h(mat22h& m, mat22h* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat22f(mat22f& m, mat22f* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat22d(mat22d& m, mat22d* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat33h(mat33h& m, mat33h* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat33f(mat33f& m, mat33f* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat33d(mat33d& m, mat33d* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat44h(mat44h& m, mat44h* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat44f(mat44f& m, mat44f* ret) { *ret = wp::inverse(m); } +WP_API void builtin_inverse_mat44d(mat44d& m, mat44d* ret) { *ret = wp::inverse(m); } +WP_API void builtin_determinant_mat22h(mat22h& m, float16* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat22f(mat22f& m, float32* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat22d(mat22d& m, float64* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat33h(mat33h& m, float16* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat33f(mat33f& m, float32* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat33d(mat33d& m, float64* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat44h(mat44h& m, float16* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat44f(mat44f& m, float32* ret) { *ret = wp::determinant(m); } +WP_API void builtin_determinant_mat44d(mat44d& m, float64* ret) { *ret = wp::determinant(m); } +WP_API void builtin_trace_mat22h(mat22h& m, float16* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat33h(mat33h& m, float16* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat44h(mat44h& m, float16* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_spatial_matrixh(spatial_matrixh& m, float16* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat22f(mat22f& m, float32* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat33f(mat33f& m, float32* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat44f(mat44f& m, float32* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_spatial_matrixf(spatial_matrixf& m, float32* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat22d(mat22d& m, float64* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat33d(mat33d& m, float64* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_mat44d(mat44d& m, float64* ret) { *ret = wp::trace(m); } +WP_API void builtin_trace_spatial_matrixd(spatial_matrixd& m, float64* ret) { *ret = wp::trace(m); } +WP_API void builtin_diag_vec2h(vec2h& d, mat22h* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec3h(vec3h& d, mat33h* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec4h(vec4h& d, mat44h* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_spatial_vectorh(spatial_vectorh& d, spatial_matrixh* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec2f(vec2f& d, mat22f* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec3f(vec3f& d, mat33f* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec4f(vec4f& d, mat44f* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_spatial_vectorf(spatial_vectorf& d, spatial_matrixf* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec2d(vec2d& d, mat22d* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec3d(vec3d& d, mat33d* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_vec4d(vec4d& d, mat44d* ret) { *ret = wp::diag(d); } +WP_API void builtin_diag_spatial_vectord(spatial_vectord& d, spatial_matrixd* ret) { *ret = wp::diag(d); } +WP_API void builtin_get_diag_mat22h(mat22h& m, vec2h* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat33h(mat33h& m, vec3h* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat44h(mat44h& m, vec4h* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_spatial_matrixh(spatial_matrixh& m, spatial_vectorh* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat22f(mat22f& m, vec2f* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat33f(mat33f& m, vec3f* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat44f(mat44f& m, vec4f* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_spatial_matrixf(spatial_matrixf& m, spatial_vectorf* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat22d(mat22d& m, vec2d* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat33d(mat33d& m, vec3d* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_mat44d(mat44d& m, vec4d* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_get_diag_spatial_matrixd(spatial_matrixd& m, spatial_vectord* ret) { *ret = wp::get_diag(m); } +WP_API void builtin_cw_mul_vec2h_vec2h(vec2h& x, vec2h& y, vec2h* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3h_vec3h(vec3h& x, vec3h& y, vec3h* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4h_vec4h(vec4h& x, vec4h& y, vec4h* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2f_vec2f(vec2f& x, vec2f& y, vec2f* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3f_vec3f(vec3f& x, vec3f& y, vec3f* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4f_vec4f(vec4f& x, vec4f& y, vec4f* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2d_vec2d(vec2d& x, vec2d& y, vec2d* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3d_vec3d(vec3d& x, vec3d& y, vec3d* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4d_vec4d(vec4d& x, vec4d& y, vec4d* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2s_vec2s(vec2s& x, vec2s& y, vec2s* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3s_vec3s(vec3s& x, vec3s& y, vec3s* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4s_vec4s(vec4s& x, vec4s& y, vec4s* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2i_vec2i(vec2i& x, vec2i& y, vec2i* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3i_vec3i(vec3i& x, vec3i& y, vec3i* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4i_vec4i(vec4i& x, vec4i& y, vec4i* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2l_vec2l(vec2l& x, vec2l& y, vec2l* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3l_vec3l(vec3l& x, vec3l& y, vec3l* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4l_vec4l(vec4l& x, vec4l& y, vec4l* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2b_vec2b(vec2b& x, vec2b& y, vec2b* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3b_vec3b(vec3b& x, vec3b& y, vec3b* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4b_vec4b(vec4b& x, vec4b& y, vec4b* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2us_vec2us(vec2us& x, vec2us& y, vec2us* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3us_vec3us(vec3us& x, vec3us& y, vec3us* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4us_vec4us(vec4us& x, vec4us& y, vec4us* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2ui_vec2ui(vec2ui& x, vec2ui& y, vec2ui* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3ui_vec3ui(vec3ui& x, vec3ui& y, vec3ui* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4ui_vec4ui(vec4ui& x, vec4ui& y, vec4ui* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2ul_vec2ul(vec2ul& x, vec2ul& y, vec2ul* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3ul_vec3ul(vec3ul& x, vec3ul& y, vec3ul* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4ul_vec4ul(vec4ul& x, vec4ul& y, vec4ul* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec2ub_vec2ub(vec2ub& x, vec2ub& y, vec2ub* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec3ub_vec3ub(vec3ub& x, vec3ub& y, vec3ub* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_vec4ub_vec4ub(vec4ub& x, vec4ub& y, vec4ub* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat22h_mat22h(mat22h& x, mat22h& y, mat22h* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat33h_mat33h(mat33h& x, mat33h& y, mat33h* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat44h_mat44h(mat44h& x, mat44h& y, mat44h* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_spatial_matrixh_spatial_matrixh(spatial_matrixh& x, spatial_matrixh& y, spatial_matrixh* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat22f_mat22f(mat22f& x, mat22f& y, mat22f* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat33f_mat33f(mat33f& x, mat33f& y, mat33f* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat44f_mat44f(mat44f& x, mat44f& y, mat44f* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_spatial_matrixf_spatial_matrixf(spatial_matrixf& x, spatial_matrixf& y, spatial_matrixf* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat22d_mat22d(mat22d& x, mat22d& y, mat22d* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat33d_mat33d(mat33d& x, mat33d& y, mat33d* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_mat44d_mat44d(mat44d& x, mat44d& y, mat44d* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_mul_spatial_matrixd_spatial_matrixd(spatial_matrixd& x, spatial_matrixd& y, spatial_matrixd* ret) { *ret = wp::cw_mul(x, y); } +WP_API void builtin_cw_div_vec2h_vec2h(vec2h& x, vec2h& y, vec2h* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3h_vec3h(vec3h& x, vec3h& y, vec3h* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4h_vec4h(vec4h& x, vec4h& y, vec4h* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2f_vec2f(vec2f& x, vec2f& y, vec2f* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3f_vec3f(vec3f& x, vec3f& y, vec3f* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4f_vec4f(vec4f& x, vec4f& y, vec4f* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2d_vec2d(vec2d& x, vec2d& y, vec2d* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3d_vec3d(vec3d& x, vec3d& y, vec3d* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4d_vec4d(vec4d& x, vec4d& y, vec4d* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2s_vec2s(vec2s& x, vec2s& y, vec2s* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3s_vec3s(vec3s& x, vec3s& y, vec3s* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4s_vec4s(vec4s& x, vec4s& y, vec4s* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2i_vec2i(vec2i& x, vec2i& y, vec2i* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3i_vec3i(vec3i& x, vec3i& y, vec3i* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4i_vec4i(vec4i& x, vec4i& y, vec4i* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2l_vec2l(vec2l& x, vec2l& y, vec2l* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3l_vec3l(vec3l& x, vec3l& y, vec3l* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4l_vec4l(vec4l& x, vec4l& y, vec4l* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2b_vec2b(vec2b& x, vec2b& y, vec2b* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3b_vec3b(vec3b& x, vec3b& y, vec3b* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4b_vec4b(vec4b& x, vec4b& y, vec4b* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2us_vec2us(vec2us& x, vec2us& y, vec2us* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3us_vec3us(vec3us& x, vec3us& y, vec3us* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4us_vec4us(vec4us& x, vec4us& y, vec4us* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2ui_vec2ui(vec2ui& x, vec2ui& y, vec2ui* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3ui_vec3ui(vec3ui& x, vec3ui& y, vec3ui* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4ui_vec4ui(vec4ui& x, vec4ui& y, vec4ui* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2ul_vec2ul(vec2ul& x, vec2ul& y, vec2ul* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3ul_vec3ul(vec3ul& x, vec3ul& y, vec3ul* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4ul_vec4ul(vec4ul& x, vec4ul& y, vec4ul* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec2ub_vec2ub(vec2ub& x, vec2ub& y, vec2ub* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec3ub_vec3ub(vec3ub& x, vec3ub& y, vec3ub* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_vec4ub_vec4ub(vec4ub& x, vec4ub& y, vec4ub* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat22h_mat22h(mat22h& x, mat22h& y, mat22h* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat33h_mat33h(mat33h& x, mat33h& y, mat33h* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat44h_mat44h(mat44h& x, mat44h& y, mat44h* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_spatial_matrixh_spatial_matrixh(spatial_matrixh& x, spatial_matrixh& y, spatial_matrixh* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat22f_mat22f(mat22f& x, mat22f& y, mat22f* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat33f_mat33f(mat33f& x, mat33f& y, mat33f* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat44f_mat44f(mat44f& x, mat44f& y, mat44f* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_spatial_matrixf_spatial_matrixf(spatial_matrixf& x, spatial_matrixf& y, spatial_matrixf* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat22d_mat22d(mat22d& x, mat22d& y, mat22d* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat33d_mat33d(mat33d& x, mat33d& y, mat33d* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_mat44d_mat44d(mat44d& x, mat44d& y, mat44d* ret) { *ret = wp::cw_div(x, y); } +WP_API void builtin_cw_div_spatial_matrixd_spatial_matrixd(spatial_matrixd& x, spatial_matrixd& y, spatial_matrixd* ret) { *ret = wp::cw_div(x, y); } WP_API void builtin_quat_identity(quatf* ret) { *ret = wp::quat_identity(); } -WP_API void builtin_quat_from_axis_angle_vec3h_float16(vec3h axis, float16 angle, quath* ret) { *ret = wp::quat_from_axis_angle(axis, angle); } -WP_API void builtin_quat_from_axis_angle_vec3f_float32(vec3f axis, float32 angle, quatf* ret) { *ret = wp::quat_from_axis_angle(axis, angle); } -WP_API void builtin_quat_from_axis_angle_vec3d_float64(vec3d axis, float64 angle, quatd* ret) { *ret = wp::quat_from_axis_angle(axis, angle); } -WP_API void builtin_quat_from_matrix_mat33h(mat33h m, quath* ret) { *ret = wp::quat_from_matrix(m); } -WP_API void builtin_quat_from_matrix_mat33f(mat33f m, quatf* ret) { *ret = wp::quat_from_matrix(m); } -WP_API void builtin_quat_from_matrix_mat33d(mat33d m, quatd* ret) { *ret = wp::quat_from_matrix(m); } +WP_API void builtin_quat_from_axis_angle_vec3h_float16(vec3h& axis, float16 angle, quath* ret) { *ret = wp::quat_from_axis_angle(axis, angle); } +WP_API void builtin_quat_from_axis_angle_vec3f_float32(vec3f& axis, float32 angle, quatf* ret) { *ret = wp::quat_from_axis_angle(axis, angle); } +WP_API void builtin_quat_from_axis_angle_vec3d_float64(vec3d& axis, float64 angle, quatd* ret) { *ret = wp::quat_from_axis_angle(axis, angle); } +WP_API void builtin_quat_from_matrix_mat33h(mat33h& m, quath* ret) { *ret = wp::quat_from_matrix(m); } +WP_API void builtin_quat_from_matrix_mat33f(mat33f& m, quatf* ret) { *ret = wp::quat_from_matrix(m); } +WP_API void builtin_quat_from_matrix_mat33d(mat33d& m, quatd* ret) { *ret = wp::quat_from_matrix(m); } WP_API void builtin_quat_rpy_float16_float16_float16(float16 roll, float16 pitch, float16 yaw, quath* ret) { *ret = wp::quat_rpy(roll, pitch, yaw); } WP_API void builtin_quat_rpy_float32_float32_float32(float32 roll, float32 pitch, float32 yaw, quatf* ret) { *ret = wp::quat_rpy(roll, pitch, yaw); } WP_API void builtin_quat_rpy_float64_float64_float64(float64 roll, float64 pitch, float64 yaw, quatd* ret) { *ret = wp::quat_rpy(roll, pitch, yaw); } -WP_API void builtin_quat_inverse_quath(quath q, quath* ret) { *ret = wp::quat_inverse(q); } -WP_API void builtin_quat_inverse_quatf(quatf q, quatf* ret) { *ret = wp::quat_inverse(q); } -WP_API void builtin_quat_inverse_quatd(quatd q, quatd* ret) { *ret = wp::quat_inverse(q); } -WP_API void builtin_quat_rotate_quath_vec3h(quath q, vec3h p, vec3h* ret) { *ret = wp::quat_rotate(q, p); } -WP_API void builtin_quat_rotate_quatf_vec3f(quatf q, vec3f p, vec3f* ret) { *ret = wp::quat_rotate(q, p); } -WP_API void builtin_quat_rotate_quatd_vec3d(quatd q, vec3d p, vec3d* ret) { *ret = wp::quat_rotate(q, p); } -WP_API void builtin_quat_rotate_inv_quath_vec3h(quath q, vec3h p, vec3h* ret) { *ret = wp::quat_rotate_inv(q, p); } -WP_API void builtin_quat_rotate_inv_quatf_vec3f(quatf q, vec3f p, vec3f* ret) { *ret = wp::quat_rotate_inv(q, p); } -WP_API void builtin_quat_rotate_inv_quatd_vec3d(quatd q, vec3d p, vec3d* ret) { *ret = wp::quat_rotate_inv(q, p); } -WP_API void builtin_quat_slerp_quath_quath_float16(quath q0, quath q1, float16 t, quath* ret) { *ret = wp::quat_slerp(q0, q1, t); } -WP_API void builtin_quat_slerp_quatf_quatf_float32(quatf q0, quatf q1, float32 t, quatf* ret) { *ret = wp::quat_slerp(q0, q1, t); } -WP_API void builtin_quat_slerp_quatd_quatd_float64(quatd q0, quatd q1, float64 t, quatd* ret) { *ret = wp::quat_slerp(q0, q1, t); } -WP_API void builtin_quat_to_matrix_quath(quath q, mat33h* ret) { *ret = wp::quat_to_matrix(q); } -WP_API void builtin_quat_to_matrix_quatf(quatf q, mat33f* ret) { *ret = wp::quat_to_matrix(q); } -WP_API void builtin_quat_to_matrix_quatd(quatd q, mat33d* ret) { *ret = wp::quat_to_matrix(q); } +WP_API void builtin_quat_inverse_quath(quath& q, quath* ret) { *ret = wp::quat_inverse(q); } +WP_API void builtin_quat_inverse_quatf(quatf& q, quatf* ret) { *ret = wp::quat_inverse(q); } +WP_API void builtin_quat_inverse_quatd(quatd& q, quatd* ret) { *ret = wp::quat_inverse(q); } +WP_API void builtin_quat_rotate_quath_vec3h(quath& q, vec3h& p, vec3h* ret) { *ret = wp::quat_rotate(q, p); } +WP_API void builtin_quat_rotate_quatf_vec3f(quatf& q, vec3f& p, vec3f* ret) { *ret = wp::quat_rotate(q, p); } +WP_API void builtin_quat_rotate_quatd_vec3d(quatd& q, vec3d& p, vec3d* ret) { *ret = wp::quat_rotate(q, p); } +WP_API void builtin_quat_rotate_inv_quath_vec3h(quath& q, vec3h& p, vec3h* ret) { *ret = wp::quat_rotate_inv(q, p); } +WP_API void builtin_quat_rotate_inv_quatf_vec3f(quatf& q, vec3f& p, vec3f* ret) { *ret = wp::quat_rotate_inv(q, p); } +WP_API void builtin_quat_rotate_inv_quatd_vec3d(quatd& q, vec3d& p, vec3d* ret) { *ret = wp::quat_rotate_inv(q, p); } +WP_API void builtin_quat_slerp_quath_quath_float16(quath& q0, quath& q1, float16 t, quath* ret) { *ret = wp::quat_slerp(q0, q1, t); } +WP_API void builtin_quat_slerp_quatf_quatf_float32(quatf& q0, quatf& q1, float32 t, quatf* ret) { *ret = wp::quat_slerp(q0, q1, t); } +WP_API void builtin_quat_slerp_quatd_quatd_float64(quatd& q0, quatd& q1, float64 t, quatd* ret) { *ret = wp::quat_slerp(q0, q1, t); } +WP_API void builtin_quat_to_matrix_quath(quath& q, mat33h* ret) { *ret = wp::quat_to_matrix(q); } +WP_API void builtin_quat_to_matrix_quatf(quatf& q, mat33f* ret) { *ret = wp::quat_to_matrix(q); } +WP_API void builtin_quat_to_matrix_quatd(quatd& q, mat33d* ret) { *ret = wp::quat_to_matrix(q); } WP_API void builtin_transform_identity(transformf* ret) { *ret = wp::transform_identity(); } -WP_API void builtin_transform_get_translation_transformh(transformh t, vec3h* ret) { *ret = wp::transform_get_translation(t); } -WP_API void builtin_transform_get_translation_transformf(transformf t, vec3f* ret) { *ret = wp::transform_get_translation(t); } -WP_API void builtin_transform_get_translation_transformd(transformd t, vec3d* ret) { *ret = wp::transform_get_translation(t); } -WP_API void builtin_transform_get_rotation_transformh(transformh t, quath* ret) { *ret = wp::transform_get_rotation(t); } -WP_API void builtin_transform_get_rotation_transformf(transformf t, quatf* ret) { *ret = wp::transform_get_rotation(t); } -WP_API void builtin_transform_get_rotation_transformd(transformd t, quatd* ret) { *ret = wp::transform_get_rotation(t); } -WP_API void builtin_transform_multiply_transformh_transformh(transformh a, transformh b, transformh* ret) { *ret = wp::transform_multiply(a, b); } -WP_API void builtin_transform_multiply_transformf_transformf(transformf a, transformf b, transformf* ret) { *ret = wp::transform_multiply(a, b); } -WP_API void builtin_transform_multiply_transformd_transformd(transformd a, transformd b, transformd* ret) { *ret = wp::transform_multiply(a, b); } -WP_API void builtin_transform_point_transformh_vec3h(transformh t, vec3h p, vec3h* ret) { *ret = wp::transform_point(t, p); } -WP_API void builtin_transform_point_transformf_vec3f(transformf t, vec3f p, vec3f* ret) { *ret = wp::transform_point(t, p); } -WP_API void builtin_transform_point_transformd_vec3d(transformd t, vec3d p, vec3d* ret) { *ret = wp::transform_point(t, p); } -WP_API void builtin_transform_point_mat44h_vec3h(mat44h m, vec3h p, vec3h* ret) { *ret = wp::transform_point(m, p); } -WP_API void builtin_transform_point_mat44f_vec3f(mat44f m, vec3f p, vec3f* ret) { *ret = wp::transform_point(m, p); } -WP_API void builtin_transform_point_mat44d_vec3d(mat44d m, vec3d p, vec3d* ret) { *ret = wp::transform_point(m, p); } -WP_API void builtin_transform_vector_transformh_vec3h(transformh t, vec3h v, vec3h* ret) { *ret = wp::transform_vector(t, v); } -WP_API void builtin_transform_vector_transformf_vec3f(transformf t, vec3f v, vec3f* ret) { *ret = wp::transform_vector(t, v); } -WP_API void builtin_transform_vector_transformd_vec3d(transformd t, vec3d v, vec3d* ret) { *ret = wp::transform_vector(t, v); } -WP_API void builtin_transform_vector_mat44h_vec3h(mat44h m, vec3h v, vec3h* ret) { *ret = wp::transform_vector(m, v); } -WP_API void builtin_transform_vector_mat44f_vec3f(mat44f m, vec3f v, vec3f* ret) { *ret = wp::transform_vector(m, v); } -WP_API void builtin_transform_vector_mat44d_vec3d(mat44d m, vec3d v, vec3d* ret) { *ret = wp::transform_vector(m, v); } -WP_API void builtin_transform_inverse_transformh(transformh t, transformh* ret) { *ret = wp::transform_inverse(t); } -WP_API void builtin_transform_inverse_transformf(transformf t, transformf* ret) { *ret = wp::transform_inverse(t); } -WP_API void builtin_transform_inverse_transformd(transformd t, transformd* ret) { *ret = wp::transform_inverse(t); } -WP_API void builtin_spatial_dot_spatial_vectorh_spatial_vectorh(spatial_vectorh a, spatial_vectorh b, float16* ret) { *ret = wp::spatial_dot(a, b); } -WP_API void builtin_spatial_dot_spatial_vectorf_spatial_vectorf(spatial_vectorf a, spatial_vectorf b, float32* ret) { *ret = wp::spatial_dot(a, b); } -WP_API void builtin_spatial_dot_spatial_vectord_spatial_vectord(spatial_vectord a, spatial_vectord b, float64* ret) { *ret = wp::spatial_dot(a, b); } -WP_API void builtin_spatial_cross_spatial_vectorh_spatial_vectorh(spatial_vectorh a, spatial_vectorh b, spatial_vectorh* ret) { *ret = wp::spatial_cross(a, b); } -WP_API void builtin_spatial_cross_spatial_vectorf_spatial_vectorf(spatial_vectorf a, spatial_vectorf b, spatial_vectorf* ret) { *ret = wp::spatial_cross(a, b); } -WP_API void builtin_spatial_cross_spatial_vectord_spatial_vectord(spatial_vectord a, spatial_vectord b, spatial_vectord* ret) { *ret = wp::spatial_cross(a, b); } -WP_API void builtin_spatial_cross_dual_spatial_vectorh_spatial_vectorh(spatial_vectorh a, spatial_vectorh b, spatial_vectorh* ret) { *ret = wp::spatial_cross_dual(a, b); } -WP_API void builtin_spatial_cross_dual_spatial_vectorf_spatial_vectorf(spatial_vectorf a, spatial_vectorf b, spatial_vectorf* ret) { *ret = wp::spatial_cross_dual(a, b); } -WP_API void builtin_spatial_cross_dual_spatial_vectord_spatial_vectord(spatial_vectord a, spatial_vectord b, spatial_vectord* ret) { *ret = wp::spatial_cross_dual(a, b); } -WP_API void builtin_spatial_top_spatial_vectorh(spatial_vectorh a, vec3h* ret) { *ret = wp::spatial_top(a); } -WP_API void builtin_spatial_top_spatial_vectorf(spatial_vectorf a, vec3f* ret) { *ret = wp::spatial_top(a); } -WP_API void builtin_spatial_top_spatial_vectord(spatial_vectord a, vec3d* ret) { *ret = wp::spatial_top(a); } -WP_API void builtin_spatial_bottom_spatial_vectorh(spatial_vectorh a, vec3h* ret) { *ret = wp::spatial_bottom(a); } -WP_API void builtin_spatial_bottom_spatial_vectorf(spatial_vectorf a, vec3f* ret) { *ret = wp::spatial_bottom(a); } -WP_API void builtin_spatial_bottom_spatial_vectord(spatial_vectord a, vec3d* ret) { *ret = wp::spatial_bottom(a); } -WP_API void builtin_bvh_query_aabb_uint64_vec3f_vec3f(uint64 id, vec3f lower, vec3f upper, bvh_query_t* ret) { *ret = wp::bvh_query_aabb(id, lower, upper); } -WP_API void builtin_bvh_query_ray_uint64_vec3f_vec3f(uint64 id, vec3f start, vec3f dir, bvh_query_t* ret) { *ret = wp::bvh_query_ray(id, start, dir); } +WP_API void builtin_transform_get_translation_transformh(transformh& t, vec3h* ret) { *ret = wp::transform_get_translation(t); } +WP_API void builtin_transform_get_translation_transformf(transformf& t, vec3f* ret) { *ret = wp::transform_get_translation(t); } +WP_API void builtin_transform_get_translation_transformd(transformd& t, vec3d* ret) { *ret = wp::transform_get_translation(t); } +WP_API void builtin_transform_get_rotation_transformh(transformh& t, quath* ret) { *ret = wp::transform_get_rotation(t); } +WP_API void builtin_transform_get_rotation_transformf(transformf& t, quatf* ret) { *ret = wp::transform_get_rotation(t); } +WP_API void builtin_transform_get_rotation_transformd(transformd& t, quatd* ret) { *ret = wp::transform_get_rotation(t); } +WP_API void builtin_transform_multiply_transformh_transformh(transformh& a, transformh& b, transformh* ret) { *ret = wp::transform_multiply(a, b); } +WP_API void builtin_transform_multiply_transformf_transformf(transformf& a, transformf& b, transformf* ret) { *ret = wp::transform_multiply(a, b); } +WP_API void builtin_transform_multiply_transformd_transformd(transformd& a, transformd& b, transformd* ret) { *ret = wp::transform_multiply(a, b); } +WP_API void builtin_transform_point_transformh_vec3h(transformh& t, vec3h& p, vec3h* ret) { *ret = wp::transform_point(t, p); } +WP_API void builtin_transform_point_transformf_vec3f(transformf& t, vec3f& p, vec3f* ret) { *ret = wp::transform_point(t, p); } +WP_API void builtin_transform_point_transformd_vec3d(transformd& t, vec3d& p, vec3d* ret) { *ret = wp::transform_point(t, p); } +WP_API void builtin_transform_point_mat44h_vec3h(mat44h& m, vec3h& p, vec3h* ret) { *ret = wp::transform_point(m, p); } +WP_API void builtin_transform_point_mat44f_vec3f(mat44f& m, vec3f& p, vec3f* ret) { *ret = wp::transform_point(m, p); } +WP_API void builtin_transform_point_mat44d_vec3d(mat44d& m, vec3d& p, vec3d* ret) { *ret = wp::transform_point(m, p); } +WP_API void builtin_transform_vector_transformh_vec3h(transformh& t, vec3h& v, vec3h* ret) { *ret = wp::transform_vector(t, v); } +WP_API void builtin_transform_vector_transformf_vec3f(transformf& t, vec3f& v, vec3f* ret) { *ret = wp::transform_vector(t, v); } +WP_API void builtin_transform_vector_transformd_vec3d(transformd& t, vec3d& v, vec3d* ret) { *ret = wp::transform_vector(t, v); } +WP_API void builtin_transform_vector_mat44h_vec3h(mat44h& m, vec3h& v, vec3h* ret) { *ret = wp::transform_vector(m, v); } +WP_API void builtin_transform_vector_mat44f_vec3f(mat44f& m, vec3f& v, vec3f* ret) { *ret = wp::transform_vector(m, v); } +WP_API void builtin_transform_vector_mat44d_vec3d(mat44d& m, vec3d& v, vec3d* ret) { *ret = wp::transform_vector(m, v); } +WP_API void builtin_transform_inverse_transformh(transformh& t, transformh* ret) { *ret = wp::transform_inverse(t); } +WP_API void builtin_transform_inverse_transformf(transformf& t, transformf* ret) { *ret = wp::transform_inverse(t); } +WP_API void builtin_transform_inverse_transformd(transformd& t, transformd* ret) { *ret = wp::transform_inverse(t); } +WP_API void builtin_spatial_dot_spatial_vectorh_spatial_vectorh(spatial_vectorh& a, spatial_vectorh& b, float16* ret) { *ret = wp::spatial_dot(a, b); } +WP_API void builtin_spatial_dot_spatial_vectorf_spatial_vectorf(spatial_vectorf& a, spatial_vectorf& b, float32* ret) { *ret = wp::spatial_dot(a, b); } +WP_API void builtin_spatial_dot_spatial_vectord_spatial_vectord(spatial_vectord& a, spatial_vectord& b, float64* ret) { *ret = wp::spatial_dot(a, b); } +WP_API void builtin_spatial_cross_spatial_vectorh_spatial_vectorh(spatial_vectorh& a, spatial_vectorh& b, spatial_vectorh* ret) { *ret = wp::spatial_cross(a, b); } +WP_API void builtin_spatial_cross_spatial_vectorf_spatial_vectorf(spatial_vectorf& a, spatial_vectorf& b, spatial_vectorf* ret) { *ret = wp::spatial_cross(a, b); } +WP_API void builtin_spatial_cross_spatial_vectord_spatial_vectord(spatial_vectord& a, spatial_vectord& b, spatial_vectord* ret) { *ret = wp::spatial_cross(a, b); } +WP_API void builtin_spatial_cross_dual_spatial_vectorh_spatial_vectorh(spatial_vectorh& a, spatial_vectorh& b, spatial_vectorh* ret) { *ret = wp::spatial_cross_dual(a, b); } +WP_API void builtin_spatial_cross_dual_spatial_vectorf_spatial_vectorf(spatial_vectorf& a, spatial_vectorf& b, spatial_vectorf* ret) { *ret = wp::spatial_cross_dual(a, b); } +WP_API void builtin_spatial_cross_dual_spatial_vectord_spatial_vectord(spatial_vectord& a, spatial_vectord& b, spatial_vectord* ret) { *ret = wp::spatial_cross_dual(a, b); } +WP_API void builtin_spatial_top_spatial_vectorh(spatial_vectorh& a, vec3h* ret) { *ret = wp::spatial_top(a); } +WP_API void builtin_spatial_top_spatial_vectorf(spatial_vectorf& a, vec3f* ret) { *ret = wp::spatial_top(a); } +WP_API void builtin_spatial_top_spatial_vectord(spatial_vectord& a, vec3d* ret) { *ret = wp::spatial_top(a); } +WP_API void builtin_spatial_bottom_spatial_vectorh(spatial_vectorh& a, vec3h* ret) { *ret = wp::spatial_bottom(a); } +WP_API void builtin_spatial_bottom_spatial_vectorf(spatial_vectorf& a, vec3f* ret) { *ret = wp::spatial_bottom(a); } +WP_API void builtin_spatial_bottom_spatial_vectord(spatial_vectord& a, vec3d* ret) { *ret = wp::spatial_bottom(a); } +WP_API void builtin_bvh_query_aabb_uint64_vec3f_vec3f(uint64 id, vec3f& lower, vec3f& upper, bvh_query_t* ret) { *ret = wp::bvh_query_aabb(id, lower, upper); } +WP_API void builtin_bvh_query_ray_uint64_vec3f_vec3f(uint64 id, vec3f& start, vec3f& dir, bvh_query_t* ret) { *ret = wp::bvh_query_ray(id, start, dir); } WP_API void builtin_bvh_query_next_bvh_query_t_int32(bvh_query_t query, int32 index, bool* ret) { *ret = wp::bvh_query_next(query, index); } -WP_API void builtin_mesh_query_point_uint64_vec3f_float32_float32_int32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_point(id, point, max_dist, inside, face, bary_u, bary_v); } -WP_API void builtin_mesh_query_point_uint64_vec3f_float32(uint64 id, vec3f point, float32 max_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_point(id, point, max_dist); } -WP_API void builtin_mesh_query_point_no_sign_uint64_vec3f_float32_int32_float32_float32(uint64 id, vec3f point, float32 max_dist, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_point_no_sign(id, point, max_dist, face, bary_u, bary_v); } -WP_API void builtin_mesh_query_point_no_sign_uint64_vec3f_float32(uint64 id, vec3f point, float32 max_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_no_sign(id, point, max_dist); } -WP_API void builtin_mesh_query_furthest_point_no_sign_uint64_vec3f_float32_int32_float32_float32(uint64 id, vec3f point, float32 min_dist, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_furthest_point_no_sign(id, point, min_dist, face, bary_u, bary_v); } -WP_API void builtin_mesh_query_furthest_point_no_sign_uint64_vec3f_float32(uint64 id, vec3f point, float32 min_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_furthest_point_no_sign(id, point, min_dist); } -WP_API void builtin_mesh_query_point_sign_normal_uint64_vec3f_float32_float32_int32_float32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, float32 epsilon, bool* ret) { *ret = wp::mesh_query_point_sign_normal(id, point, max_dist, inside, face, bary_u, bary_v, epsilon); } -WP_API void builtin_mesh_query_point_sign_normal_uint64_vec3f_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 epsilon, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_sign_normal(id, point, max_dist, epsilon); } -WP_API void builtin_mesh_query_point_sign_winding_number_uint64_vec3f_float32_float32_int32_float32_float32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, float32 accuracy, float32 threshold, bool* ret) { *ret = wp::mesh_query_point_sign_winding_number(id, point, max_dist, inside, face, bary_u, bary_v, accuracy, threshold); } -WP_API void builtin_mesh_query_point_sign_winding_number_uint64_vec3f_float32_float32_float32(uint64 id, vec3f point, float32 max_dist, float32 accuracy, float32 threshold, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_sign_winding_number(id, point, max_dist, accuracy, threshold); } -WP_API void builtin_mesh_query_ray_uint64_vec3f_vec3f_float32_float32_float32_float32_float32_vec3f_int32(uint64 id, vec3f start, vec3f dir, float32 max_t, float32 t, float32 bary_u, float32 bary_v, float32 sign, vec3f normal, int32 face, bool* ret) { *ret = wp::mesh_query_ray(id, start, dir, max_t, t, bary_u, bary_v, sign, normal, face); } -WP_API void builtin_mesh_query_ray_uint64_vec3f_vec3f_float32(uint64 id, vec3f start, vec3f dir, float32 max_t, mesh_query_ray_t* ret) { *ret = wp::mesh_query_ray(id, start, dir, max_t); } -WP_API void builtin_mesh_query_aabb_uint64_vec3f_vec3f(uint64 id, vec3f lower, vec3f upper, mesh_query_aabb_t* ret) { *ret = wp::mesh_query_aabb(id, lower, upper); } +WP_API void builtin_mesh_query_point_uint64_vec3f_float32_float32_int32_float32_float32(uint64 id, vec3f& point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_point(id, point, max_dist, inside, face, bary_u, bary_v); } +WP_API void builtin_mesh_query_point_uint64_vec3f_float32(uint64 id, vec3f& point, float32 max_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_point(id, point, max_dist); } +WP_API void builtin_mesh_query_point_no_sign_uint64_vec3f_float32_int32_float32_float32(uint64 id, vec3f& point, float32 max_dist, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_point_no_sign(id, point, max_dist, face, bary_u, bary_v); } +WP_API void builtin_mesh_query_point_no_sign_uint64_vec3f_float32(uint64 id, vec3f& point, float32 max_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_no_sign(id, point, max_dist); } +WP_API void builtin_mesh_query_furthest_point_no_sign_uint64_vec3f_float32_int32_float32_float32(uint64 id, vec3f& point, float32 min_dist, int32 face, float32 bary_u, float32 bary_v, bool* ret) { *ret = wp::mesh_query_furthest_point_no_sign(id, point, min_dist, face, bary_u, bary_v); } +WP_API void builtin_mesh_query_furthest_point_no_sign_uint64_vec3f_float32(uint64 id, vec3f& point, float32 min_dist, mesh_query_point_t* ret) { *ret = wp::mesh_query_furthest_point_no_sign(id, point, min_dist); } +WP_API void builtin_mesh_query_point_sign_normal_uint64_vec3f_float32_float32_int32_float32_float32_float32(uint64 id, vec3f& point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, float32 epsilon, bool* ret) { *ret = wp::mesh_query_point_sign_normal(id, point, max_dist, inside, face, bary_u, bary_v, epsilon); } +WP_API void builtin_mesh_query_point_sign_normal_uint64_vec3f_float32_float32(uint64 id, vec3f& point, float32 max_dist, float32 epsilon, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_sign_normal(id, point, max_dist, epsilon); } +WP_API void builtin_mesh_query_point_sign_winding_number_uint64_vec3f_float32_float32_int32_float32_float32_float32_float32(uint64 id, vec3f& point, float32 max_dist, float32 inside, int32 face, float32 bary_u, float32 bary_v, float32 accuracy, float32 threshold, bool* ret) { *ret = wp::mesh_query_point_sign_winding_number(id, point, max_dist, inside, face, bary_u, bary_v, accuracy, threshold); } +WP_API void builtin_mesh_query_point_sign_winding_number_uint64_vec3f_float32_float32_float32(uint64 id, vec3f& point, float32 max_dist, float32 accuracy, float32 threshold, mesh_query_point_t* ret) { *ret = wp::mesh_query_point_sign_winding_number(id, point, max_dist, accuracy, threshold); } +WP_API void builtin_mesh_query_ray_uint64_vec3f_vec3f_float32_float32_float32_float32_float32_vec3f_int32(uint64 id, vec3f& start, vec3f& dir, float32 max_t, float32 t, float32 bary_u, float32 bary_v, float32 sign, vec3f& normal, int32 face, bool* ret) { *ret = wp::mesh_query_ray(id, start, dir, max_t, t, bary_u, bary_v, sign, normal, face); } +WP_API void builtin_mesh_query_ray_uint64_vec3f_vec3f_float32(uint64 id, vec3f& start, vec3f& dir, float32 max_t, mesh_query_ray_t* ret) { *ret = wp::mesh_query_ray(id, start, dir, max_t); } +WP_API void builtin_mesh_query_aabb_uint64_vec3f_vec3f(uint64 id, vec3f& lower, vec3f& upper, mesh_query_aabb_t* ret) { *ret = wp::mesh_query_aabb(id, lower, upper); } WP_API void builtin_mesh_query_aabb_next_mesh_query_aabb_t_int32(mesh_query_aabb_t query, int32 index, bool* ret) { *ret = wp::mesh_query_aabb_next(query, index); } WP_API void builtin_mesh_eval_position_uint64_int32_float32_float32(uint64 id, int32 face, float32 bary_u, float32 bary_v, vec3f* ret) { *ret = wp::mesh_eval_position(id, face, bary_u, bary_v); } WP_API void builtin_mesh_eval_velocity_uint64_int32_float32_float32(uint64 id, int32 face, float32 bary_u, float32 bary_v, vec3f* ret) { *ret = wp::mesh_eval_velocity(id, face, bary_u, bary_v); } -WP_API void builtin_hash_grid_query_uint64_vec3f_float32(uint64 id, vec3f point, float32 max_dist, hash_grid_query_t* ret) { *ret = wp::hash_grid_query(id, point, max_dist); } +WP_API void builtin_hash_grid_query_uint64_vec3f_float32(uint64 id, vec3f& point, float32 max_dist, hash_grid_query_t* ret) { *ret = wp::hash_grid_query(id, point, max_dist); } WP_API void builtin_hash_grid_query_next_hash_grid_query_t_int32(hash_grid_query_t query, int32 index, bool* ret) { *ret = wp::hash_grid_query_next(query, index); } WP_API void builtin_hash_grid_point_id_uint64_int32(uint64 id, int32 index, int* ret) { *ret = wp::hash_grid_point_id(id, index); } -WP_API void builtin_intersect_tri_tri_vec3f_vec3f_vec3f_vec3f_vec3f_vec3f(vec3f v0, vec3f v1, vec3f v2, vec3f u0, vec3f u1, vec3f u2, int* ret) { *ret = wp::intersect_tri_tri(v0, v1, v2, u0, u1, u2); } +WP_API void builtin_intersect_tri_tri_vec3f_vec3f_vec3f_vec3f_vec3f_vec3f(vec3f& v0, vec3f& v1, vec3f& v2, vec3f& u0, vec3f& u1, vec3f& u2, int* ret) { *ret = wp::intersect_tri_tri(v0, v1, v2, u0, u1, u2); } WP_API void builtin_mesh_get_uint64(uint64 id, Mesh* ret) { *ret = wp::mesh_get(id); } WP_API void builtin_mesh_eval_face_normal_uint64_int32(uint64 id, int32 face, vec3f* ret) { *ret = wp::mesh_eval_face_normal(id, face); } WP_API void builtin_mesh_get_point_uint64_int32(uint64 id, int32 index, vec3f* ret) { *ret = wp::mesh_get_point(id, index); } WP_API void builtin_mesh_get_velocity_uint64_int32(uint64 id, int32 index, vec3f* ret) { *ret = wp::mesh_get_velocity(id, index); } WP_API void builtin_mesh_get_index_uint64_int32(uint64 id, int32 index, int* ret) { *ret = wp::mesh_get_index(id, index); } -WP_API void builtin_closest_point_edge_edge_vec3f_vec3f_vec3f_vec3f_float32(vec3f p1, vec3f q1, vec3f p2, vec3f q2, float32 epsilon, vec3f* ret) { *ret = wp::closest_point_edge_edge(p1, q1, p2, q2, epsilon); } +WP_API void builtin_closest_point_edge_edge_vec3f_vec3f_vec3f_vec3f_float32(vec3f& p1, vec3f& q1, vec3f& p2, vec3f& q2, float32 epsilon, vec3f* ret) { *ret = wp::closest_point_edge_edge(p1, q1, p2, q2, epsilon); } WP_API void builtin_iter_next_range_t(range_t range, int* ret) { *ret = wp::iter_next(range); } WP_API void builtin_iter_next_hash_grid_query_t(hash_grid_query_t query, int* ret) { *ret = wp::iter_next(query); } WP_API void builtin_iter_next_mesh_query_aabb_t(mesh_query_aabb_t query, int* ret) { *ret = wp::iter_next(query); } -WP_API void builtin_volume_sample_f_uint64_vec3f_int32(uint64 id, vec3f uvw, int32 sampling_mode, float* ret) { *ret = wp::volume_sample_f(id, uvw, sampling_mode); } -WP_API void builtin_volume_sample_grad_f_uint64_vec3f_int32_vec3f(uint64 id, vec3f uvw, int32 sampling_mode, vec3f grad, float* ret) { *ret = wp::volume_sample_grad_f(id, uvw, sampling_mode, grad); } +WP_API void builtin_volume_sample_f_uint64_vec3f_int32(uint64 id, vec3f& uvw, int32 sampling_mode, float* ret) { *ret = wp::volume_sample_f(id, uvw, sampling_mode); } +WP_API void builtin_volume_sample_grad_f_uint64_vec3f_int32_vec3f(uint64 id, vec3f& uvw, int32 sampling_mode, vec3f& grad, float* ret) { *ret = wp::volume_sample_grad_f(id, uvw, sampling_mode, grad); } WP_API void builtin_volume_lookup_f_uint64_int32_int32_int32(uint64 id, int32 i, int32 j, int32 k, float* ret) { *ret = wp::volume_lookup_f(id, i, j, k); } -WP_API void builtin_volume_sample_v_uint64_vec3f_int32(uint64 id, vec3f uvw, int32 sampling_mode, vec3f* ret) { *ret = wp::volume_sample_v(id, uvw, sampling_mode); } +WP_API void builtin_volume_sample_v_uint64_vec3f_int32(uint64 id, vec3f& uvw, int32 sampling_mode, vec3f* ret) { *ret = wp::volume_sample_v(id, uvw, sampling_mode); } WP_API void builtin_volume_lookup_v_uint64_int32_int32_int32(uint64 id, int32 i, int32 j, int32 k, vec3f* ret) { *ret = wp::volume_lookup_v(id, i, j, k); } -WP_API void builtin_volume_sample_i_uint64_vec3f(uint64 id, vec3f uvw, int* ret) { *ret = wp::volume_sample_i(id, uvw); } +WP_API void builtin_volume_sample_i_uint64_vec3f(uint64 id, vec3f& uvw, int* ret) { *ret = wp::volume_sample_i(id, uvw); } WP_API void builtin_volume_lookup_i_uint64_int32_int32_int32(uint64 id, int32 i, int32 j, int32 k, int* ret) { *ret = wp::volume_lookup_i(id, i, j, k); } -WP_API void builtin_volume_index_to_world_uint64_vec3f(uint64 id, vec3f uvw, vec3f* ret) { *ret = wp::volume_index_to_world(id, uvw); } -WP_API void builtin_volume_world_to_index_uint64_vec3f(uint64 id, vec3f xyz, vec3f* ret) { *ret = wp::volume_world_to_index(id, xyz); } -WP_API void builtin_volume_index_to_world_dir_uint64_vec3f(uint64 id, vec3f uvw, vec3f* ret) { *ret = wp::volume_index_to_world_dir(id, uvw); } -WP_API void builtin_volume_world_to_index_dir_uint64_vec3f(uint64 id, vec3f xyz, vec3f* ret) { *ret = wp::volume_world_to_index_dir(id, xyz); } +WP_API void builtin_volume_index_to_world_uint64_vec3f(uint64 id, vec3f& uvw, vec3f* ret) { *ret = wp::volume_index_to_world(id, uvw); } +WP_API void builtin_volume_world_to_index_uint64_vec3f(uint64 id, vec3f& xyz, vec3f* ret) { *ret = wp::volume_world_to_index(id, xyz); } +WP_API void builtin_volume_index_to_world_dir_uint64_vec3f(uint64 id, vec3f& uvw, vec3f* ret) { *ret = wp::volume_index_to_world_dir(id, uvw); } +WP_API void builtin_volume_world_to_index_dir_uint64_vec3f(uint64 id, vec3f& xyz, vec3f* ret) { *ret = wp::volume_world_to_index_dir(id, xyz); } WP_API void builtin_rand_init_int32(int32 seed, uint32* ret) { *ret = wp::rand_init(seed); } WP_API void builtin_rand_init_int32_int32(int32 seed, int32 offset, uint32* ret) { *ret = wp::rand_init(seed, offset); } WP_API void builtin_randi_uint32(uint32 state, int* ret) { *ret = wp::randi(state); } @@ -804,116 +804,116 @@ WP_API void builtin_sample_unit_square_uint32(uint32 state, vec2f* ret) { *ret = WP_API void builtin_sample_unit_cube_uint32(uint32 state, vec3f* ret) { *ret = wp::sample_unit_cube(state); } WP_API void builtin_poisson_uint32_float32(uint32 state, float32 lam, uint32* ret) { *ret = wp::poisson(state, lam); } WP_API void builtin_noise_uint32_float32(uint32 state, float32 x, float* ret) { *ret = wp::noise(state, x); } -WP_API void builtin_noise_uint32_vec2f(uint32 state, vec2f xy, float* ret) { *ret = wp::noise(state, xy); } -WP_API void builtin_noise_uint32_vec3f(uint32 state, vec3f xyz, float* ret) { *ret = wp::noise(state, xyz); } -WP_API void builtin_noise_uint32_vec4f(uint32 state, vec4f xyzt, float* ret) { *ret = wp::noise(state, xyzt); } +WP_API void builtin_noise_uint32_vec2f(uint32 state, vec2f& xy, float* ret) { *ret = wp::noise(state, xy); } +WP_API void builtin_noise_uint32_vec3f(uint32 state, vec3f& xyz, float* ret) { *ret = wp::noise(state, xyz); } +WP_API void builtin_noise_uint32_vec4f(uint32 state, vec4f& xyzt, float* ret) { *ret = wp::noise(state, xyzt); } WP_API void builtin_pnoise_uint32_float32_int32(uint32 state, float32 x, int32 px, float* ret) { *ret = wp::pnoise(state, x, px); } -WP_API void builtin_pnoise_uint32_vec2f_int32_int32(uint32 state, vec2f xy, int32 px, int32 py, float* ret) { *ret = wp::pnoise(state, xy, px, py); } -WP_API void builtin_pnoise_uint32_vec3f_int32_int32_int32(uint32 state, vec3f xyz, int32 px, int32 py, int32 pz, float* ret) { *ret = wp::pnoise(state, xyz, px, py, pz); } -WP_API void builtin_pnoise_uint32_vec4f_int32_int32_int32_int32(uint32 state, vec4f xyzt, int32 px, int32 py, int32 pz, int32 pt, float* ret) { *ret = wp::pnoise(state, xyzt, px, py, pz, pt); } -WP_API void builtin_curlnoise_uint32_vec2f_uint32_float32_float32(uint32 state, vec2f xy, uint32 octaves, float32 lacunarity, float32 gain, vec2f* ret) { *ret = wp::curlnoise(state, xy, octaves, lacunarity, gain); } -WP_API void builtin_curlnoise_uint32_vec3f_uint32_float32_float32(uint32 state, vec3f xyz, uint32 octaves, float32 lacunarity, float32 gain, vec3f* ret) { *ret = wp::curlnoise(state, xyz, octaves, lacunarity, gain); } -WP_API void builtin_curlnoise_uint32_vec4f_uint32_float32_float32(uint32 state, vec4f xyzt, uint32 octaves, float32 lacunarity, float32 gain, vec3f* ret) { *ret = wp::curlnoise(state, xyzt, octaves, lacunarity, gain); } -WP_API void builtin_extract_vec2h_int32(vec2h a, int32 i, float16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3h_int32(vec3h a, int32 i, float16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4h_int32(vec4h a, int32 i, float16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_spatial_vectorh_int32(spatial_vectorh a, int32 i, float16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2f_int32(vec2f a, int32 i, float32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3f_int32(vec3f a, int32 i, float32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4f_int32(vec4f a, int32 i, float32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_spatial_vectorf_int32(spatial_vectorf a, int32 i, float32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2d_int32(vec2d a, int32 i, float64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3d_int32(vec3d a, int32 i, float64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4d_int32(vec4d a, int32 i, float64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_spatial_vectord_int32(spatial_vectord a, int32 i, float64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2s_int32(vec2s a, int32 i, int16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3s_int32(vec3s a, int32 i, int16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4s_int32(vec4s a, int32 i, int16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2i_int32(vec2i a, int32 i, int32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3i_int32(vec3i a, int32 i, int32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4i_int32(vec4i a, int32 i, int32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2l_int32(vec2l a, int32 i, int64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3l_int32(vec3l a, int32 i, int64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4l_int32(vec4l a, int32 i, int64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2b_int32(vec2b a, int32 i, int8* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3b_int32(vec3b a, int32 i, int8* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4b_int32(vec4b a, int32 i, int8* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2us_int32(vec2us a, int32 i, uint16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3us_int32(vec3us a, int32 i, uint16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4us_int32(vec4us a, int32 i, uint16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2ui_int32(vec2ui a, int32 i, uint32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3ui_int32(vec3ui a, int32 i, uint32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4ui_int32(vec4ui a, int32 i, uint32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2ul_int32(vec2ul a, int32 i, uint64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3ul_int32(vec3ul a, int32 i, uint64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4ul_int32(vec4ul a, int32 i, uint64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec2ub_int32(vec2ub a, int32 i, uint8* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec3ub_int32(vec3ub a, int32 i, uint8* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_vec4ub_int32(vec4ub a, int32 i, uint8* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_quath_int32(quath a, int32 i, float16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_quatf_int32(quatf a, int32 i, float32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_quatd_int32(quatd a, int32 i, float64* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat22h_int32(mat22h a, int32 i, vec2h* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat33h_int32(mat33h a, int32 i, vec3h* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat44h_int32(mat44h a, int32 i, vec4h* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_spatial_matrixh_int32(spatial_matrixh a, int32 i, spatial_vectorh* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat22f_int32(mat22f a, int32 i, vec2f* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat33f_int32(mat33f a, int32 i, vec3f* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat44f_int32(mat44f a, int32 i, vec4f* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_spatial_matrixf_int32(spatial_matrixf a, int32 i, spatial_vectorf* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat22d_int32(mat22d a, int32 i, vec2d* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat33d_int32(mat33d a, int32 i, vec3d* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat44d_int32(mat44d a, int32 i, vec4d* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_spatial_matrixd_int32(spatial_matrixd a, int32 i, spatial_vectord* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_mat22h_int32_int32(mat22h a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat33h_int32_int32(mat33h a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat44h_int32_int32(mat44h a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_spatial_matrixh_int32_int32(spatial_matrixh a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat22f_int32_int32(mat22f a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat33f_int32_int32(mat33f a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat44f_int32_int32(mat44f a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_spatial_matrixf_int32_int32(spatial_matrixf a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat22d_int32_int32(mat22d a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat33d_int32_int32(mat33d a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_mat44d_int32_int32(mat44d a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_spatial_matrixd_int32_int32(spatial_matrixd a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } -WP_API void builtin_extract_transformh_int32(transformh a, int32 i, float16* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_transformf_int32(transformf a, int32 i, float32* ret) { *ret = wp::extract(a, i); } -WP_API void builtin_extract_transformd_int32(transformd a, int32 i, float64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_pnoise_uint32_vec2f_int32_int32(uint32 state, vec2f& xy, int32 px, int32 py, float* ret) { *ret = wp::pnoise(state, xy, px, py); } +WP_API void builtin_pnoise_uint32_vec3f_int32_int32_int32(uint32 state, vec3f& xyz, int32 px, int32 py, int32 pz, float* ret) { *ret = wp::pnoise(state, xyz, px, py, pz); } +WP_API void builtin_pnoise_uint32_vec4f_int32_int32_int32_int32(uint32 state, vec4f& xyzt, int32 px, int32 py, int32 pz, int32 pt, float* ret) { *ret = wp::pnoise(state, xyzt, px, py, pz, pt); } +WP_API void builtin_curlnoise_uint32_vec2f_uint32_float32_float32(uint32 state, vec2f& xy, uint32 octaves, float32 lacunarity, float32 gain, vec2f* ret) { *ret = wp::curlnoise(state, xy, octaves, lacunarity, gain); } +WP_API void builtin_curlnoise_uint32_vec3f_uint32_float32_float32(uint32 state, vec3f& xyz, uint32 octaves, float32 lacunarity, float32 gain, vec3f* ret) { *ret = wp::curlnoise(state, xyz, octaves, lacunarity, gain); } +WP_API void builtin_curlnoise_uint32_vec4f_uint32_float32_float32(uint32 state, vec4f& xyzt, uint32 octaves, float32 lacunarity, float32 gain, vec3f* ret) { *ret = wp::curlnoise(state, xyzt, octaves, lacunarity, gain); } +WP_API void builtin_extract_vec2h_int32(vec2h& a, int32 i, float16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3h_int32(vec3h& a, int32 i, float16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4h_int32(vec4h& a, int32 i, float16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_spatial_vectorh_int32(spatial_vectorh& a, int32 i, float16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2f_int32(vec2f& a, int32 i, float32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3f_int32(vec3f& a, int32 i, float32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4f_int32(vec4f& a, int32 i, float32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_spatial_vectorf_int32(spatial_vectorf& a, int32 i, float32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2d_int32(vec2d& a, int32 i, float64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3d_int32(vec3d& a, int32 i, float64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4d_int32(vec4d& a, int32 i, float64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_spatial_vectord_int32(spatial_vectord& a, int32 i, float64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2s_int32(vec2s& a, int32 i, int16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3s_int32(vec3s& a, int32 i, int16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4s_int32(vec4s& a, int32 i, int16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2i_int32(vec2i& a, int32 i, int32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3i_int32(vec3i& a, int32 i, int32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4i_int32(vec4i& a, int32 i, int32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2l_int32(vec2l& a, int32 i, int64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3l_int32(vec3l& a, int32 i, int64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4l_int32(vec4l& a, int32 i, int64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2b_int32(vec2b& a, int32 i, int8* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3b_int32(vec3b& a, int32 i, int8* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4b_int32(vec4b& a, int32 i, int8* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2us_int32(vec2us& a, int32 i, uint16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3us_int32(vec3us& a, int32 i, uint16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4us_int32(vec4us& a, int32 i, uint16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2ui_int32(vec2ui& a, int32 i, uint32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3ui_int32(vec3ui& a, int32 i, uint32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4ui_int32(vec4ui& a, int32 i, uint32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2ul_int32(vec2ul& a, int32 i, uint64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3ul_int32(vec3ul& a, int32 i, uint64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4ul_int32(vec4ul& a, int32 i, uint64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec2ub_int32(vec2ub& a, int32 i, uint8* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec3ub_int32(vec3ub& a, int32 i, uint8* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_vec4ub_int32(vec4ub& a, int32 i, uint8* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_quath_int32(quath& a, int32 i, float16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_quatf_int32(quatf& a, int32 i, float32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_quatd_int32(quatd& a, int32 i, float64* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat22h_int32(mat22h& a, int32 i, vec2h* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat33h_int32(mat33h& a, int32 i, vec3h* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat44h_int32(mat44h& a, int32 i, vec4h* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_spatial_matrixh_int32(spatial_matrixh& a, int32 i, spatial_vectorh* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat22f_int32(mat22f& a, int32 i, vec2f* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat33f_int32(mat33f& a, int32 i, vec3f* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat44f_int32(mat44f& a, int32 i, vec4f* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_spatial_matrixf_int32(spatial_matrixf& a, int32 i, spatial_vectorf* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat22d_int32(mat22d& a, int32 i, vec2d* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat33d_int32(mat33d& a, int32 i, vec3d* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat44d_int32(mat44d& a, int32 i, vec4d* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_spatial_matrixd_int32(spatial_matrixd& a, int32 i, spatial_vectord* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_mat22h_int32_int32(mat22h& a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat33h_int32_int32(mat33h& a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat44h_int32_int32(mat44h& a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_spatial_matrixh_int32_int32(spatial_matrixh& a, int32 i, int32 j, float16* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat22f_int32_int32(mat22f& a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat33f_int32_int32(mat33f& a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat44f_int32_int32(mat44f& a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_spatial_matrixf_int32_int32(spatial_matrixf& a, int32 i, int32 j, float32* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat22d_int32_int32(mat22d& a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat33d_int32_int32(mat33d& a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_mat44d_int32_int32(mat44d& a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_spatial_matrixd_int32_int32(spatial_matrixd& a, int32 i, int32 j, float64* ret) { *ret = wp::extract(a, i, j); } +WP_API void builtin_extract_transformh_int32(transformh& a, int32 i, float16* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_transformf_int32(transformf& a, int32 i, float32* ret) { *ret = wp::extract(a, i); } +WP_API void builtin_extract_transformd_int32(transformd& a, int32 i, float64* ret) { *ret = wp::extract(a, i); } WP_API void builtin_extract_shape_t_int32(shape_t s, int32 i, int* ret) { *ret = wp::extract(s, i); } WP_API void builtin_lerp_float16_float16_float16(float16 a, float16 b, float16 t, float16* ret) { *ret = wp::lerp(a, b, t); } WP_API void builtin_lerp_float32_float32_float32(float32 a, float32 b, float32 t, float32* ret) { *ret = wp::lerp(a, b, t); } WP_API void builtin_lerp_float64_float64_float64(float64 a, float64 b, float64 t, float64* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec2h_vec2h_float16(vec2h a, vec2h b, float16 t, vec2h* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec3h_vec3h_float16(vec3h a, vec3h b, float16 t, vec3h* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec4h_vec4h_float16(vec4h a, vec4h b, float16 t, vec4h* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_spatial_vectorh_spatial_vectorh_float16(spatial_vectorh a, spatial_vectorh b, float16 t, spatial_vectorh* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec2f_vec2f_float32(vec2f a, vec2f b, float32 t, vec2f* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec3f_vec3f_float32(vec3f a, vec3f b, float32 t, vec3f* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec4f_vec4f_float32(vec4f a, vec4f b, float32 t, vec4f* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_spatial_vectorf_spatial_vectorf_float32(spatial_vectorf a, spatial_vectorf b, float32 t, spatial_vectorf* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec2d_vec2d_float64(vec2d a, vec2d b, float64 t, vec2d* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec3d_vec3d_float64(vec3d a, vec3d b, float64 t, vec3d* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_vec4d_vec4d_float64(vec4d a, vec4d b, float64 t, vec4d* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_spatial_vectord_spatial_vectord_float64(spatial_vectord a, spatial_vectord b, float64 t, spatial_vectord* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat22h_mat22h_float16(mat22h a, mat22h b, float16 t, mat22h* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat33h_mat33h_float16(mat33h a, mat33h b, float16 t, mat33h* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat44h_mat44h_float16(mat44h a, mat44h b, float16 t, mat44h* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_spatial_matrixh_spatial_matrixh_float16(spatial_matrixh a, spatial_matrixh b, float16 t, spatial_matrixh* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat22f_mat22f_float32(mat22f a, mat22f b, float32 t, mat22f* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat33f_mat33f_float32(mat33f a, mat33f b, float32 t, mat33f* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat44f_mat44f_float32(mat44f a, mat44f b, float32 t, mat44f* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_spatial_matrixf_spatial_matrixf_float32(spatial_matrixf a, spatial_matrixf b, float32 t, spatial_matrixf* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat22d_mat22d_float64(mat22d a, mat22d b, float64 t, mat22d* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat33d_mat33d_float64(mat33d a, mat33d b, float64 t, mat33d* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_mat44d_mat44d_float64(mat44d a, mat44d b, float64 t, mat44d* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_spatial_matrixd_spatial_matrixd_float64(spatial_matrixd a, spatial_matrixd b, float64 t, spatial_matrixd* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_quath_quath_float16(quath a, quath b, float16 t, quath* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_quatf_quatf_float32(quatf a, quatf b, float32 t, quatf* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_quatd_quatd_float64(quatd a, quatd b, float64 t, quatd* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_transformh_transformh_float16(transformh a, transformh b, float16 t, transformh* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_transformf_transformf_float32(transformf a, transformf b, float32 t, transformf* ret) { *ret = wp::lerp(a, b, t); } -WP_API void builtin_lerp_transformd_transformd_float64(transformd a, transformd b, float64 t, transformd* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec2h_vec2h_float16(vec2h& a, vec2h& b, float16 t, vec2h* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec3h_vec3h_float16(vec3h& a, vec3h& b, float16 t, vec3h* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec4h_vec4h_float16(vec4h& a, vec4h& b, float16 t, vec4h* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_spatial_vectorh_spatial_vectorh_float16(spatial_vectorh& a, spatial_vectorh& b, float16 t, spatial_vectorh* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec2f_vec2f_float32(vec2f& a, vec2f& b, float32 t, vec2f* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec3f_vec3f_float32(vec3f& a, vec3f& b, float32 t, vec3f* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec4f_vec4f_float32(vec4f& a, vec4f& b, float32 t, vec4f* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_spatial_vectorf_spatial_vectorf_float32(spatial_vectorf& a, spatial_vectorf& b, float32 t, spatial_vectorf* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec2d_vec2d_float64(vec2d& a, vec2d& b, float64 t, vec2d* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec3d_vec3d_float64(vec3d& a, vec3d& b, float64 t, vec3d* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_vec4d_vec4d_float64(vec4d& a, vec4d& b, float64 t, vec4d* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_spatial_vectord_spatial_vectord_float64(spatial_vectord& a, spatial_vectord& b, float64 t, spatial_vectord* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat22h_mat22h_float16(mat22h& a, mat22h& b, float16 t, mat22h* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat33h_mat33h_float16(mat33h& a, mat33h& b, float16 t, mat33h* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat44h_mat44h_float16(mat44h& a, mat44h& b, float16 t, mat44h* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_spatial_matrixh_spatial_matrixh_float16(spatial_matrixh& a, spatial_matrixh& b, float16 t, spatial_matrixh* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat22f_mat22f_float32(mat22f& a, mat22f& b, float32 t, mat22f* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat33f_mat33f_float32(mat33f& a, mat33f& b, float32 t, mat33f* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat44f_mat44f_float32(mat44f& a, mat44f& b, float32 t, mat44f* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_spatial_matrixf_spatial_matrixf_float32(spatial_matrixf& a, spatial_matrixf& b, float32 t, spatial_matrixf* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat22d_mat22d_float64(mat22d& a, mat22d& b, float64 t, mat22d* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat33d_mat33d_float64(mat33d& a, mat33d& b, float64 t, mat33d* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_mat44d_mat44d_float64(mat44d& a, mat44d& b, float64 t, mat44d* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_spatial_matrixd_spatial_matrixd_float64(spatial_matrixd& a, spatial_matrixd& b, float64 t, spatial_matrixd* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_quath_quath_float16(quath& a, quath& b, float16 t, quath* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_quatf_quatf_float32(quatf& a, quatf& b, float32 t, quatf* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_quatd_quatd_float64(quatd& a, quatd& b, float64 t, quatd* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_transformh_transformh_float16(transformh& a, transformh& b, float16 t, transformh* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_transformf_transformf_float32(transformf& a, transformf& b, float32 t, transformf* ret) { *ret = wp::lerp(a, b, t); } +WP_API void builtin_lerp_transformd_transformd_float64(transformd& a, transformd& b, float64 t, transformd* ret) { *ret = wp::lerp(a, b, t); } WP_API void builtin_smoothstep_float16_float16_float16(float16 edge0, float16 edge1, float16 x, float16* ret) { *ret = wp::smoothstep(edge0, edge1, x); } WP_API void builtin_smoothstep_float32_float32_float32(float32 edge0, float32 edge1, float32 x, float32* ret) { *ret = wp::smoothstep(edge0, edge1, x); } WP_API void builtin_smoothstep_float64_float64_float64(float64 edge0, float64 edge1, float64 x, float64* ret) { *ret = wp::smoothstep(edge0, edge1, x); } @@ -928,60 +928,60 @@ WP_API void builtin_add_uint16_uint16(uint16 x, uint16 y, uint16* ret) { *ret = WP_API void builtin_add_uint32_uint32(uint32 x, uint32 y, uint32* ret) { *ret = wp::add(x, y); } WP_API void builtin_add_uint64_uint64(uint64 x, uint64 y, uint64* ret) { *ret = wp::add(x, y); } WP_API void builtin_add_uint8_uint8(uint8 x, uint8 y, uint8* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2h_vec2h(vec2h x, vec2h y, vec2h* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3h_vec3h(vec3h x, vec3h y, vec3h* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4h_vec4h(vec4h x, vec4h y, vec4h* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2f_vec2f(vec2f x, vec2f y, vec2f* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3f_vec3f(vec3f x, vec3f y, vec3f* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4f_vec4f(vec4f x, vec4f y, vec4f* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2d_vec2d(vec2d x, vec2d y, vec2d* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3d_vec3d(vec3d x, vec3d y, vec3d* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4d_vec4d(vec4d x, vec4d y, vec4d* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2s_vec2s(vec2s x, vec2s y, vec2s* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3s_vec3s(vec3s x, vec3s y, vec3s* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4s_vec4s(vec4s x, vec4s y, vec4s* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2i_vec2i(vec2i x, vec2i y, vec2i* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3i_vec3i(vec3i x, vec3i y, vec3i* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4i_vec4i(vec4i x, vec4i y, vec4i* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2l_vec2l(vec2l x, vec2l y, vec2l* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3l_vec3l(vec3l x, vec3l y, vec3l* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4l_vec4l(vec4l x, vec4l y, vec4l* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2b_vec2b(vec2b x, vec2b y, vec2b* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3b_vec3b(vec3b x, vec3b y, vec3b* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4b_vec4b(vec4b x, vec4b y, vec4b* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2us_vec2us(vec2us x, vec2us y, vec2us* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3us_vec3us(vec3us x, vec3us y, vec3us* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4us_vec4us(vec4us x, vec4us y, vec4us* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2ui_vec2ui(vec2ui x, vec2ui y, vec2ui* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3ui_vec3ui(vec3ui x, vec3ui y, vec3ui* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4ui_vec4ui(vec4ui x, vec4ui y, vec4ui* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2ul_vec2ul(vec2ul x, vec2ul y, vec2ul* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3ul_vec3ul(vec3ul x, vec3ul y, vec3ul* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4ul_vec4ul(vec4ul x, vec4ul y, vec4ul* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec2ub_vec2ub(vec2ub x, vec2ub y, vec2ub* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec3ub_vec3ub(vec3ub x, vec3ub y, vec3ub* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_vec4ub_vec4ub(vec4ub x, vec4ub y, vec4ub* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_quath_quath(quath x, quath y, quath* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_quatf_quatf(quatf x, quatf y, quatf* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_quatd_quatd(quatd x, quatd y, quatd* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat22h_mat22h(mat22h x, mat22h y, mat22h* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat33h_mat33h(mat33h x, mat33h y, mat33h* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat44h_mat44h(mat44h x, mat44h y, mat44h* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_spatial_matrixh_spatial_matrixh(spatial_matrixh x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat22f_mat22f(mat22f x, mat22f y, mat22f* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat33f_mat33f(mat33f x, mat33f y, mat33f* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat44f_mat44f(mat44f x, mat44f y, mat44f* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_spatial_matrixf_spatial_matrixf(spatial_matrixf x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat22d_mat22d(mat22d x, mat22d y, mat22d* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat33d_mat33d(mat33d x, mat33d y, mat33d* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_mat44d_mat44d(mat44d x, mat44d y, mat44d* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_spatial_matrixd_spatial_matrixd(spatial_matrixd x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_transformh_transformh(transformh x, transformh y, transformh* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_transformf_transformf(transformf x, transformf y, transformf* ret) { *ret = wp::add(x, y); } -WP_API void builtin_add_transformd_transformd(transformd x, transformd y, transformd* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2h_vec2h(vec2h& x, vec2h& y, vec2h* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3h_vec3h(vec3h& x, vec3h& y, vec3h* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4h_vec4h(vec4h& x, vec4h& y, vec4h* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2f_vec2f(vec2f& x, vec2f& y, vec2f* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3f_vec3f(vec3f& x, vec3f& y, vec3f* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4f_vec4f(vec4f& x, vec4f& y, vec4f* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2d_vec2d(vec2d& x, vec2d& y, vec2d* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3d_vec3d(vec3d& x, vec3d& y, vec3d* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4d_vec4d(vec4d& x, vec4d& y, vec4d* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2s_vec2s(vec2s& x, vec2s& y, vec2s* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3s_vec3s(vec3s& x, vec3s& y, vec3s* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4s_vec4s(vec4s& x, vec4s& y, vec4s* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2i_vec2i(vec2i& x, vec2i& y, vec2i* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3i_vec3i(vec3i& x, vec3i& y, vec3i* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4i_vec4i(vec4i& x, vec4i& y, vec4i* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2l_vec2l(vec2l& x, vec2l& y, vec2l* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3l_vec3l(vec3l& x, vec3l& y, vec3l* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4l_vec4l(vec4l& x, vec4l& y, vec4l* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2b_vec2b(vec2b& x, vec2b& y, vec2b* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3b_vec3b(vec3b& x, vec3b& y, vec3b* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4b_vec4b(vec4b& x, vec4b& y, vec4b* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2us_vec2us(vec2us& x, vec2us& y, vec2us* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3us_vec3us(vec3us& x, vec3us& y, vec3us* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4us_vec4us(vec4us& x, vec4us& y, vec4us* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2ui_vec2ui(vec2ui& x, vec2ui& y, vec2ui* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3ui_vec3ui(vec3ui& x, vec3ui& y, vec3ui* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4ui_vec4ui(vec4ui& x, vec4ui& y, vec4ui* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2ul_vec2ul(vec2ul& x, vec2ul& y, vec2ul* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3ul_vec3ul(vec3ul& x, vec3ul& y, vec3ul* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4ul_vec4ul(vec4ul& x, vec4ul& y, vec4ul* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec2ub_vec2ub(vec2ub& x, vec2ub& y, vec2ub* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec3ub_vec3ub(vec3ub& x, vec3ub& y, vec3ub* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_vec4ub_vec4ub(vec4ub& x, vec4ub& y, vec4ub* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_quath_quath(quath& x, quath& y, quath* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_quatf_quatf(quatf& x, quatf& y, quatf* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_quatd_quatd(quatd& x, quatd& y, quatd* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat22h_mat22h(mat22h& x, mat22h& y, mat22h* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat33h_mat33h(mat33h& x, mat33h& y, mat33h* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat44h_mat44h(mat44h& x, mat44h& y, mat44h* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_spatial_matrixh_spatial_matrixh(spatial_matrixh& x, spatial_matrixh& y, spatial_matrixh* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat22f_mat22f(mat22f& x, mat22f& y, mat22f* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat33f_mat33f(mat33f& x, mat33f& y, mat33f* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat44f_mat44f(mat44f& x, mat44f& y, mat44f* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_spatial_matrixf_spatial_matrixf(spatial_matrixf& x, spatial_matrixf& y, spatial_matrixf* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat22d_mat22d(mat22d& x, mat22d& y, mat22d* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat33d_mat33d(mat33d& x, mat33d& y, mat33d* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_mat44d_mat44d(mat44d& x, mat44d& y, mat44d* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_spatial_matrixd_spatial_matrixd(spatial_matrixd& x, spatial_matrixd& y, spatial_matrixd* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_transformh_transformh(transformh& x, transformh& y, transformh* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_transformf_transformf(transformf& x, transformf& y, transformf* ret) { *ret = wp::add(x, y); } +WP_API void builtin_add_transformd_transformd(transformd& x, transformd& y, transformd* ret) { *ret = wp::add(x, y); } WP_API void builtin_sub_float16_float16(float16 x, float16 y, float16* ret) { *ret = wp::sub(x, y); } WP_API void builtin_sub_float32_float32(float32 x, float32 y, float32* ret) { *ret = wp::sub(x, y); } WP_API void builtin_sub_float64_float64(float64 x, float64 y, float64* ret) { *ret = wp::sub(x, y); } @@ -993,60 +993,60 @@ WP_API void builtin_sub_uint16_uint16(uint16 x, uint16 y, uint16* ret) { *ret = WP_API void builtin_sub_uint32_uint32(uint32 x, uint32 y, uint32* ret) { *ret = wp::sub(x, y); } WP_API void builtin_sub_uint64_uint64(uint64 x, uint64 y, uint64* ret) { *ret = wp::sub(x, y); } WP_API void builtin_sub_uint8_uint8(uint8 x, uint8 y, uint8* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2h_vec2h(vec2h x, vec2h y, vec2h* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3h_vec3h(vec3h x, vec3h y, vec3h* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4h_vec4h(vec4h x, vec4h y, vec4h* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_spatial_vectorh_spatial_vectorh(spatial_vectorh x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2f_vec2f(vec2f x, vec2f y, vec2f* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3f_vec3f(vec3f x, vec3f y, vec3f* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4f_vec4f(vec4f x, vec4f y, vec4f* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_spatial_vectorf_spatial_vectorf(spatial_vectorf x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2d_vec2d(vec2d x, vec2d y, vec2d* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3d_vec3d(vec3d x, vec3d y, vec3d* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4d_vec4d(vec4d x, vec4d y, vec4d* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_spatial_vectord_spatial_vectord(spatial_vectord x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2s_vec2s(vec2s x, vec2s y, vec2s* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3s_vec3s(vec3s x, vec3s y, vec3s* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4s_vec4s(vec4s x, vec4s y, vec4s* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2i_vec2i(vec2i x, vec2i y, vec2i* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3i_vec3i(vec3i x, vec3i y, vec3i* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4i_vec4i(vec4i x, vec4i y, vec4i* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2l_vec2l(vec2l x, vec2l y, vec2l* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3l_vec3l(vec3l x, vec3l y, vec3l* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4l_vec4l(vec4l x, vec4l y, vec4l* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2b_vec2b(vec2b x, vec2b y, vec2b* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3b_vec3b(vec3b x, vec3b y, vec3b* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4b_vec4b(vec4b x, vec4b y, vec4b* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2us_vec2us(vec2us x, vec2us y, vec2us* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3us_vec3us(vec3us x, vec3us y, vec3us* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4us_vec4us(vec4us x, vec4us y, vec4us* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2ui_vec2ui(vec2ui x, vec2ui y, vec2ui* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3ui_vec3ui(vec3ui x, vec3ui y, vec3ui* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4ui_vec4ui(vec4ui x, vec4ui y, vec4ui* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2ul_vec2ul(vec2ul x, vec2ul y, vec2ul* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3ul_vec3ul(vec3ul x, vec3ul y, vec3ul* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4ul_vec4ul(vec4ul x, vec4ul y, vec4ul* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec2ub_vec2ub(vec2ub x, vec2ub y, vec2ub* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec3ub_vec3ub(vec3ub x, vec3ub y, vec3ub* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_vec4ub_vec4ub(vec4ub x, vec4ub y, vec4ub* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat22h_mat22h(mat22h x, mat22h y, mat22h* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat33h_mat33h(mat33h x, mat33h y, mat33h* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat44h_mat44h(mat44h x, mat44h y, mat44h* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_spatial_matrixh_spatial_matrixh(spatial_matrixh x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat22f_mat22f(mat22f x, mat22f y, mat22f* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat33f_mat33f(mat33f x, mat33f y, mat33f* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat44f_mat44f(mat44f x, mat44f y, mat44f* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_spatial_matrixf_spatial_matrixf(spatial_matrixf x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat22d_mat22d(mat22d x, mat22d y, mat22d* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat33d_mat33d(mat33d x, mat33d y, mat33d* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_mat44d_mat44d(mat44d x, mat44d y, mat44d* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_spatial_matrixd_spatial_matrixd(spatial_matrixd x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_quath_quath(quath x, quath y, quath* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_quatf_quatf(quatf x, quatf y, quatf* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_quatd_quatd(quatd x, quatd y, quatd* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_transformh_transformh(transformh x, transformh y, transformh* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_transformf_transformf(transformf x, transformf y, transformf* ret) { *ret = wp::sub(x, y); } -WP_API void builtin_sub_transformd_transformd(transformd x, transformd y, transformd* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2h_vec2h(vec2h& x, vec2h& y, vec2h* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3h_vec3h(vec3h& x, vec3h& y, vec3h* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4h_vec4h(vec4h& x, vec4h& y, vec4h* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_spatial_vectorh_spatial_vectorh(spatial_vectorh& x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2f_vec2f(vec2f& x, vec2f& y, vec2f* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3f_vec3f(vec3f& x, vec3f& y, vec3f* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4f_vec4f(vec4f& x, vec4f& y, vec4f* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_spatial_vectorf_spatial_vectorf(spatial_vectorf& x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2d_vec2d(vec2d& x, vec2d& y, vec2d* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3d_vec3d(vec3d& x, vec3d& y, vec3d* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4d_vec4d(vec4d& x, vec4d& y, vec4d* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_spatial_vectord_spatial_vectord(spatial_vectord& x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2s_vec2s(vec2s& x, vec2s& y, vec2s* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3s_vec3s(vec3s& x, vec3s& y, vec3s* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4s_vec4s(vec4s& x, vec4s& y, vec4s* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2i_vec2i(vec2i& x, vec2i& y, vec2i* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3i_vec3i(vec3i& x, vec3i& y, vec3i* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4i_vec4i(vec4i& x, vec4i& y, vec4i* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2l_vec2l(vec2l& x, vec2l& y, vec2l* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3l_vec3l(vec3l& x, vec3l& y, vec3l* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4l_vec4l(vec4l& x, vec4l& y, vec4l* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2b_vec2b(vec2b& x, vec2b& y, vec2b* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3b_vec3b(vec3b& x, vec3b& y, vec3b* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4b_vec4b(vec4b& x, vec4b& y, vec4b* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2us_vec2us(vec2us& x, vec2us& y, vec2us* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3us_vec3us(vec3us& x, vec3us& y, vec3us* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4us_vec4us(vec4us& x, vec4us& y, vec4us* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2ui_vec2ui(vec2ui& x, vec2ui& y, vec2ui* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3ui_vec3ui(vec3ui& x, vec3ui& y, vec3ui* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4ui_vec4ui(vec4ui& x, vec4ui& y, vec4ui* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2ul_vec2ul(vec2ul& x, vec2ul& y, vec2ul* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3ul_vec3ul(vec3ul& x, vec3ul& y, vec3ul* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4ul_vec4ul(vec4ul& x, vec4ul& y, vec4ul* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec2ub_vec2ub(vec2ub& x, vec2ub& y, vec2ub* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec3ub_vec3ub(vec3ub& x, vec3ub& y, vec3ub* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_vec4ub_vec4ub(vec4ub& x, vec4ub& y, vec4ub* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat22h_mat22h(mat22h& x, mat22h& y, mat22h* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat33h_mat33h(mat33h& x, mat33h& y, mat33h* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat44h_mat44h(mat44h& x, mat44h& y, mat44h* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_spatial_matrixh_spatial_matrixh(spatial_matrixh& x, spatial_matrixh& y, spatial_matrixh* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat22f_mat22f(mat22f& x, mat22f& y, mat22f* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat33f_mat33f(mat33f& x, mat33f& y, mat33f* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat44f_mat44f(mat44f& x, mat44f& y, mat44f* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_spatial_matrixf_spatial_matrixf(spatial_matrixf& x, spatial_matrixf& y, spatial_matrixf* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat22d_mat22d(mat22d& x, mat22d& y, mat22d* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat33d_mat33d(mat33d& x, mat33d& y, mat33d* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_mat44d_mat44d(mat44d& x, mat44d& y, mat44d* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_spatial_matrixd_spatial_matrixd(spatial_matrixd& x, spatial_matrixd& y, spatial_matrixd* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_quath_quath(quath& x, quath& y, quath* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_quatf_quatf(quatf& x, quatf& y, quatf* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_quatd_quatd(quatd& x, quatd& y, quatd* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_transformh_transformh(transformh& x, transformh& y, transformh* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_transformf_transformf(transformf& x, transformf& y, transformf* ret) { *ret = wp::sub(x, y); } +WP_API void builtin_sub_transformd_transformd(transformd& x, transformd& y, transformd* ret) { *ret = wp::sub(x, y); } WP_API void builtin_bit_and_int16_int16(int16 x, int16 y, int16* ret) { *ret = wp::bit_and(x, y); } WP_API void builtin_bit_and_int32_int32(int32 x, int32 y, int32* ret) { *ret = wp::bit_and(x, y); } WP_API void builtin_bit_and_int64_int64(int64 x, int64 y, int64* ret) { *ret = wp::bit_and(x, y); } @@ -1106,156 +1106,156 @@ WP_API void builtin_mul_uint16_uint16(uint16 x, uint16 y, uint16* ret) { *ret = WP_API void builtin_mul_uint32_uint32(uint32 x, uint32 y, uint32* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mul_uint64_uint64(uint64 x, uint64 y, uint64* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mul_uint8_uint8(uint8 x, uint8 y, uint8* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2h_float16(vec2h x, float16 y, vec2h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3h_float16(vec3h x, float16 y, vec3h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4h_float16(vec4h x, float16 y, vec4h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_vectorh_float16(spatial_vectorh x, float16 y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2f_float32(vec2f x, float32 y, vec2f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3f_float32(vec3f x, float32 y, vec3f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4f_float32(vec4f x, float32 y, vec4f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_vectorf_float32(spatial_vectorf x, float32 y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2d_float64(vec2d x, float64 y, vec2d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3d_float64(vec3d x, float64 y, vec3d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4d_float64(vec4d x, float64 y, vec4d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_vectord_float64(spatial_vectord x, float64 y, spatial_vectord* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2s_int16(vec2s x, int16 y, vec2s* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3s_int16(vec3s x, int16 y, vec3s* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4s_int16(vec4s x, int16 y, vec4s* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2i_int32(vec2i x, int32 y, vec2i* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3i_int32(vec3i x, int32 y, vec3i* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4i_int32(vec4i x, int32 y, vec4i* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2l_int64(vec2l x, int64 y, vec2l* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3l_int64(vec3l x, int64 y, vec3l* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4l_int64(vec4l x, int64 y, vec4l* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2b_int8(vec2b x, int8 y, vec2b* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3b_int8(vec3b x, int8 y, vec3b* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4b_int8(vec4b x, int8 y, vec4b* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2us_uint16(vec2us x, uint16 y, vec2us* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3us_uint16(vec3us x, uint16 y, vec3us* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4us_uint16(vec4us x, uint16 y, vec4us* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2ui_uint32(vec2ui x, uint32 y, vec2ui* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3ui_uint32(vec3ui x, uint32 y, vec3ui* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4ui_uint32(vec4ui x, uint32 y, vec4ui* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2ul_uint64(vec2ul x, uint64 y, vec2ul* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3ul_uint64(vec3ul x, uint64 y, vec3ul* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4ul_uint64(vec4ul x, uint64 y, vec4ul* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2ub_uint8(vec2ub x, uint8 y, vec2ub* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3ub_uint8(vec3ub x, uint8 y, vec3ub* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4ub_uint8(vec4ub x, uint8 y, vec4ub* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_vec2h(float16 x, vec2h y, vec2h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_vec3h(float16 x, vec3h y, vec3h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_vec4h(float16 x, vec4h y, vec4h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_spatial_vectorh(float16 x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_vec2f(float32 x, vec2f y, vec2f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_vec3f(float32 x, vec3f y, vec3f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_vec4f(float32 x, vec4f y, vec4f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_spatial_vectorf(float32 x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_vec2d(float64 x, vec2d y, vec2d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_vec3d(float64 x, vec3d y, vec3d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_vec4d(float64 x, vec4d y, vec4d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_spatial_vectord(float64 x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int16_vec2s(int16 x, vec2s y, vec2s* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int16_vec3s(int16 x, vec3s y, vec3s* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int16_vec4s(int16 x, vec4s y, vec4s* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int32_vec2i(int32 x, vec2i y, vec2i* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int32_vec3i(int32 x, vec3i y, vec3i* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int32_vec4i(int32 x, vec4i y, vec4i* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int64_vec2l(int64 x, vec2l y, vec2l* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int64_vec3l(int64 x, vec3l y, vec3l* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int64_vec4l(int64 x, vec4l y, vec4l* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int8_vec2b(int8 x, vec2b y, vec2b* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int8_vec3b(int8 x, vec3b y, vec3b* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_int8_vec4b(int8 x, vec4b y, vec4b* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint16_vec2us(uint16 x, vec2us y, vec2us* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint16_vec3us(uint16 x, vec3us y, vec3us* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint16_vec4us(uint16 x, vec4us y, vec4us* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint32_vec2ui(uint32 x, vec2ui y, vec2ui* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint32_vec3ui(uint32 x, vec3ui y, vec3ui* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint32_vec4ui(uint32 x, vec4ui y, vec4ui* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint64_vec2ul(uint64 x, vec2ul y, vec2ul* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint64_vec3ul(uint64 x, vec3ul y, vec3ul* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint64_vec4ul(uint64 x, vec4ul y, vec4ul* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint8_vec2ub(uint8 x, vec2ub y, vec2ub* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint8_vec3ub(uint8 x, vec3ub y, vec3ub* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_uint8_vec4ub(uint8 x, vec4ub y, vec4ub* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_quath_float16(quath x, float16 y, quath* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_quatf_float32(quatf x, float32 y, quatf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_quatd_float64(quatd x, float64 y, quatd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_quath(float16 x, quath y, quath* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_quatf(float32 x, quatf y, quatf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_quatd(float64 x, quatd y, quatd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_quath_quath(quath x, quath y, quath* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_quatf_quatf(quatf x, quatf y, quatf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_quatd_quatd(quatd x, quatd y, quatd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_mat22h(float16 x, mat22h y, mat22h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_mat33h(float16 x, mat33h y, mat33h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_mat44h(float16 x, mat44h y, mat44h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_spatial_matrixh(float16 x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_mat22f(float32 x, mat22f y, mat22f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_mat33f(float32 x, mat33f y, mat33f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_mat44f(float32 x, mat44f y, mat44f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_spatial_matrixf(float32 x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_mat22d(float64 x, mat22d y, mat22d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_mat33d(float64 x, mat33d y, mat33d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_mat44d(float64 x, mat44d y, mat44d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_spatial_matrixd(float64 x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22h_float16(mat22h x, float16 y, mat22h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33h_float16(mat33h x, float16 y, mat33h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44h_float16(mat44h x, float16 y, mat44h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixh_float16(spatial_matrixh x, float16 y, spatial_matrixh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22f_float32(mat22f x, float32 y, mat22f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33f_float32(mat33f x, float32 y, mat33f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44f_float32(mat44f x, float32 y, mat44f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixf_float32(spatial_matrixf x, float32 y, spatial_matrixf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22d_float64(mat22d x, float64 y, mat22d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33d_float64(mat33d x, float64 y, mat33d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44d_float64(mat44d x, float64 y, mat44d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixd_float64(spatial_matrixd x, float64 y, spatial_matrixd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22h_vec2h(mat22h x, vec2h y, vec2h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33h_vec3h(mat33h x, vec3h y, vec3h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44h_vec4h(mat44h x, vec4h y, vec4h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixh_spatial_vectorh(spatial_matrixh x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22f_vec2f(mat22f x, vec2f y, vec2f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33f_vec3f(mat33f x, vec3f y, vec3f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44f_vec4f(mat44f x, vec4f y, vec4f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixf_spatial_vectorf(spatial_matrixf x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22d_vec2d(mat22d x, vec2d y, vec2d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33d_vec3d(mat33d x, vec3d y, vec3d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44d_vec4d(mat44d x, vec4d y, vec4d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixd_spatial_vectord(spatial_matrixd x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2h_mat22h(vec2h x, mat22h y, vec2h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3h_mat33h(vec3h x, mat33h y, vec3h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4h_mat44h(vec4h x, mat44h y, vec4h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_vectorh_spatial_matrixh(spatial_vectorh x, spatial_matrixh y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2f_mat22f(vec2f x, mat22f y, vec2f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3f_mat33f(vec3f x, mat33f y, vec3f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4f_mat44f(vec4f x, mat44f y, vec4f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_vectorf_spatial_matrixf(spatial_vectorf x, spatial_matrixf y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec2d_mat22d(vec2d x, mat22d y, vec2d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec3d_mat33d(vec3d x, mat33d y, vec3d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_vec4d_mat44d(vec4d x, mat44d y, vec4d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_vectord_spatial_matrixd(spatial_vectord x, spatial_matrixd y, spatial_vectord* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22h_mat22h(mat22h x, mat22h y, mat22h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33h_mat33h(mat33h x, mat33h y, mat33h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44h_mat44h(mat44h x, mat44h y, mat44h* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixh_spatial_matrixh(spatial_matrixh x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22f_mat22f(mat22f x, mat22f y, mat22f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33f_mat33f(mat33f x, mat33f y, mat33f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44f_mat44f(mat44f x, mat44f y, mat44f* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixf_spatial_matrixf(spatial_matrixf x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat22d_mat22d(mat22d x, mat22d y, mat22d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat33d_mat33d(mat33d x, mat33d y, mat33d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_mat44d_mat44d(mat44d x, mat44d y, mat44d* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_spatial_matrixd_spatial_matrixd(spatial_matrixd x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_transformh_transformh(transformh x, transformh y, transformh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_transformf_transformf(transformf x, transformf y, transformf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_transformd_transformd(transformd x, transformd y, transformd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float16_transformh(float16 x, transformh y, transformh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float32_transformf(float32 x, transformf y, transformf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_float64_transformd(float64 x, transformd y, transformd* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_transformh_float16(transformh x, float16 y, transformh* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_transformf_float32(transformf x, float32 y, transformf* ret) { *ret = wp::mul(x, y); } -WP_API void builtin_mul_transformd_float64(transformd x, float64 y, transformd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2h_float16(vec2h& x, float16 y, vec2h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3h_float16(vec3h& x, float16 y, vec3h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4h_float16(vec4h& x, float16 y, vec4h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectorh_float16(spatial_vectorh& x, float16 y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2f_float32(vec2f& x, float32 y, vec2f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3f_float32(vec3f& x, float32 y, vec3f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4f_float32(vec4f& x, float32 y, vec4f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectorf_float32(spatial_vectorf& x, float32 y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2d_float64(vec2d& x, float64 y, vec2d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3d_float64(vec3d& x, float64 y, vec3d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4d_float64(vec4d& x, float64 y, vec4d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectord_float64(spatial_vectord& x, float64 y, spatial_vectord* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2s_int16(vec2s& x, int16 y, vec2s* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3s_int16(vec3s& x, int16 y, vec3s* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4s_int16(vec4s& x, int16 y, vec4s* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2i_int32(vec2i& x, int32 y, vec2i* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3i_int32(vec3i& x, int32 y, vec3i* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4i_int32(vec4i& x, int32 y, vec4i* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2l_int64(vec2l& x, int64 y, vec2l* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3l_int64(vec3l& x, int64 y, vec3l* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4l_int64(vec4l& x, int64 y, vec4l* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2b_int8(vec2b& x, int8 y, vec2b* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3b_int8(vec3b& x, int8 y, vec3b* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4b_int8(vec4b& x, int8 y, vec4b* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2us_uint16(vec2us& x, uint16 y, vec2us* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3us_uint16(vec3us& x, uint16 y, vec3us* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4us_uint16(vec4us& x, uint16 y, vec4us* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2ui_uint32(vec2ui& x, uint32 y, vec2ui* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3ui_uint32(vec3ui& x, uint32 y, vec3ui* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4ui_uint32(vec4ui& x, uint32 y, vec4ui* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2ul_uint64(vec2ul& x, uint64 y, vec2ul* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3ul_uint64(vec3ul& x, uint64 y, vec3ul* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4ul_uint64(vec4ul& x, uint64 y, vec4ul* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2ub_uint8(vec2ub& x, uint8 y, vec2ub* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3ub_uint8(vec3ub& x, uint8 y, vec3ub* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4ub_uint8(vec4ub& x, uint8 y, vec4ub* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_vec2h(float16 x, vec2h& y, vec2h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_vec3h(float16 x, vec3h& y, vec3h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_vec4h(float16 x, vec4h& y, vec4h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_spatial_vectorh(float16 x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_vec2f(float32 x, vec2f& y, vec2f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_vec3f(float32 x, vec3f& y, vec3f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_vec4f(float32 x, vec4f& y, vec4f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_spatial_vectorf(float32 x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_vec2d(float64 x, vec2d& y, vec2d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_vec3d(float64 x, vec3d& y, vec3d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_vec4d(float64 x, vec4d& y, vec4d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_spatial_vectord(float64 x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int16_vec2s(int16 x, vec2s& y, vec2s* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int16_vec3s(int16 x, vec3s& y, vec3s* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int16_vec4s(int16 x, vec4s& y, vec4s* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int32_vec2i(int32 x, vec2i& y, vec2i* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int32_vec3i(int32 x, vec3i& y, vec3i* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int32_vec4i(int32 x, vec4i& y, vec4i* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int64_vec2l(int64 x, vec2l& y, vec2l* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int64_vec3l(int64 x, vec3l& y, vec3l* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int64_vec4l(int64 x, vec4l& y, vec4l* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int8_vec2b(int8 x, vec2b& y, vec2b* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int8_vec3b(int8 x, vec3b& y, vec3b* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_int8_vec4b(int8 x, vec4b& y, vec4b* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint16_vec2us(uint16 x, vec2us& y, vec2us* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint16_vec3us(uint16 x, vec3us& y, vec3us* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint16_vec4us(uint16 x, vec4us& y, vec4us* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint32_vec2ui(uint32 x, vec2ui& y, vec2ui* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint32_vec3ui(uint32 x, vec3ui& y, vec3ui* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint32_vec4ui(uint32 x, vec4ui& y, vec4ui* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint64_vec2ul(uint64 x, vec2ul& y, vec2ul* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint64_vec3ul(uint64 x, vec3ul& y, vec3ul* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint64_vec4ul(uint64 x, vec4ul& y, vec4ul* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint8_vec2ub(uint8 x, vec2ub& y, vec2ub* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint8_vec3ub(uint8 x, vec3ub& y, vec3ub* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_uint8_vec4ub(uint8 x, vec4ub& y, vec4ub* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_quath_float16(quath& x, float16 y, quath* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_quatf_float32(quatf& x, float32 y, quatf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_quatd_float64(quatd& x, float64 y, quatd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_quath(float16 x, quath& y, quath* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_quatf(float32 x, quatf& y, quatf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_quatd(float64 x, quatd& y, quatd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_quath_quath(quath& x, quath& y, quath* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_quatf_quatf(quatf& x, quatf& y, quatf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_quatd_quatd(quatd& x, quatd& y, quatd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_mat22h(float16 x, mat22h& y, mat22h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_mat33h(float16 x, mat33h& y, mat33h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_mat44h(float16 x, mat44h& y, mat44h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_spatial_matrixh(float16 x, spatial_matrixh& y, spatial_matrixh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_mat22f(float32 x, mat22f& y, mat22f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_mat33f(float32 x, mat33f& y, mat33f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_mat44f(float32 x, mat44f& y, mat44f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_spatial_matrixf(float32 x, spatial_matrixf& y, spatial_matrixf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_mat22d(float64 x, mat22d& y, mat22d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_mat33d(float64 x, mat33d& y, mat33d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_mat44d(float64 x, mat44d& y, mat44d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_spatial_matrixd(float64 x, spatial_matrixd& y, spatial_matrixd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22h_float16(mat22h& x, float16 y, mat22h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33h_float16(mat33h& x, float16 y, mat33h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44h_float16(mat44h& x, float16 y, mat44h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixh_float16(spatial_matrixh& x, float16 y, spatial_matrixh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22f_float32(mat22f& x, float32 y, mat22f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33f_float32(mat33f& x, float32 y, mat33f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44f_float32(mat44f& x, float32 y, mat44f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixf_float32(spatial_matrixf& x, float32 y, spatial_matrixf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22d_float64(mat22d& x, float64 y, mat22d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33d_float64(mat33d& x, float64 y, mat33d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44d_float64(mat44d& x, float64 y, mat44d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixd_float64(spatial_matrixd& x, float64 y, spatial_matrixd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22h_vec2h(mat22h& x, vec2h& y, vec2h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33h_vec3h(mat33h& x, vec3h& y, vec3h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44h_vec4h(mat44h& x, vec4h& y, vec4h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixh_spatial_vectorh(spatial_matrixh& x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22f_vec2f(mat22f& x, vec2f& y, vec2f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33f_vec3f(mat33f& x, vec3f& y, vec3f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44f_vec4f(mat44f& x, vec4f& y, vec4f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixf_spatial_vectorf(spatial_matrixf& x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22d_vec2d(mat22d& x, vec2d& y, vec2d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33d_vec3d(mat33d& x, vec3d& y, vec3d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44d_vec4d(mat44d& x, vec4d& y, vec4d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixd_spatial_vectord(spatial_matrixd& x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2h_mat22h(vec2h& x, mat22h& y, vec2h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3h_mat33h(vec3h& x, mat33h& y, vec3h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4h_mat44h(vec4h& x, mat44h& y, vec4h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectorh_spatial_matrixh(spatial_vectorh& x, spatial_matrixh& y, spatial_vectorh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2f_mat22f(vec2f& x, mat22f& y, vec2f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3f_mat33f(vec3f& x, mat33f& y, vec3f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4f_mat44f(vec4f& x, mat44f& y, vec4f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectorf_spatial_matrixf(spatial_vectorf& x, spatial_matrixf& y, spatial_vectorf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec2d_mat22d(vec2d& x, mat22d& y, vec2d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec3d_mat33d(vec3d& x, mat33d& y, vec3d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_vec4d_mat44d(vec4d& x, mat44d& y, vec4d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_vectord_spatial_matrixd(spatial_vectord& x, spatial_matrixd& y, spatial_vectord* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22h_mat22h(mat22h& x, mat22h& y, mat22h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33h_mat33h(mat33h& x, mat33h& y, mat33h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44h_mat44h(mat44h& x, mat44h& y, mat44h* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixh_spatial_matrixh(spatial_matrixh& x, spatial_matrixh& y, spatial_matrixh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22f_mat22f(mat22f& x, mat22f& y, mat22f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33f_mat33f(mat33f& x, mat33f& y, mat33f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44f_mat44f(mat44f& x, mat44f& y, mat44f* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixf_spatial_matrixf(spatial_matrixf& x, spatial_matrixf& y, spatial_matrixf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat22d_mat22d(mat22d& x, mat22d& y, mat22d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat33d_mat33d(mat33d& x, mat33d& y, mat33d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_mat44d_mat44d(mat44d& x, mat44d& y, mat44d* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_spatial_matrixd_spatial_matrixd(spatial_matrixd& x, spatial_matrixd& y, spatial_matrixd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_transformh_transformh(transformh& x, transformh& y, transformh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_transformf_transformf(transformf& x, transformf& y, transformf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_transformd_transformd(transformd& x, transformd& y, transformd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float16_transformh(float16 x, transformh& y, transformh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float32_transformf(float32 x, transformf& y, transformf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_float64_transformd(float64 x, transformd& y, transformd* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_transformh_float16(transformh& x, float16 y, transformh* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_transformf_float32(transformf& x, float32 y, transformf* ret) { *ret = wp::mul(x, y); } +WP_API void builtin_mul_transformd_float64(transformd& x, float64 y, transformd* ret) { *ret = wp::mul(x, y); } WP_API void builtin_mod_float16_float16(float16 x, float16 y, float16* ret) { *ret = wp::mod(x, y); } WP_API void builtin_mod_float32_float32(float32 x, float32 y, float32* ret) { *ret = wp::mod(x, y); } WP_API void builtin_mod_float64_float64(float64 x, float64 y, float64* ret) { *ret = wp::mod(x, y); } @@ -1278,108 +1278,108 @@ WP_API void builtin_div_uint16_uint16(uint16 x, uint16 y, uint16* ret) { *ret = WP_API void builtin_div_uint32_uint32(uint32 x, uint32 y, uint32* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_uint64_uint64(uint64 x, uint64 y, uint64* ret) { *ret = wp::div(x, y); } WP_API void builtin_div_uint8_uint8(uint8 x, uint8 y, uint8* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2h_float16(vec2h x, float16 y, vec2h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3h_float16(vec3h x, float16 y, vec3h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4h_float16(vec4h x, float16 y, vec4h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_spatial_vectorh_float16(spatial_vectorh x, float16 y, spatial_vectorh* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2f_float32(vec2f x, float32 y, vec2f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3f_float32(vec3f x, float32 y, vec3f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4f_float32(vec4f x, float32 y, vec4f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_spatial_vectorf_float32(spatial_vectorf x, float32 y, spatial_vectorf* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2d_float64(vec2d x, float64 y, vec2d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3d_float64(vec3d x, float64 y, vec3d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4d_float64(vec4d x, float64 y, vec4d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_spatial_vectord_float64(spatial_vectord x, float64 y, spatial_vectord* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2s_int16(vec2s x, int16 y, vec2s* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3s_int16(vec3s x, int16 y, vec3s* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4s_int16(vec4s x, int16 y, vec4s* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2i_int32(vec2i x, int32 y, vec2i* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3i_int32(vec3i x, int32 y, vec3i* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4i_int32(vec4i x, int32 y, vec4i* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2l_int64(vec2l x, int64 y, vec2l* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3l_int64(vec3l x, int64 y, vec3l* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4l_int64(vec4l x, int64 y, vec4l* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2b_int8(vec2b x, int8 y, vec2b* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3b_int8(vec3b x, int8 y, vec3b* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4b_int8(vec4b x, int8 y, vec4b* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2us_uint16(vec2us x, uint16 y, vec2us* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3us_uint16(vec3us x, uint16 y, vec3us* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4us_uint16(vec4us x, uint16 y, vec4us* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2ui_uint32(vec2ui x, uint32 y, vec2ui* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3ui_uint32(vec3ui x, uint32 y, vec3ui* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4ui_uint32(vec4ui x, uint32 y, vec4ui* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2ul_uint64(vec2ul x, uint64 y, vec2ul* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3ul_uint64(vec3ul x, uint64 y, vec3ul* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4ul_uint64(vec4ul x, uint64 y, vec4ul* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec2ub_uint8(vec2ub x, uint8 y, vec2ub* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec3ub_uint8(vec3ub x, uint8 y, vec3ub* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_vec4ub_uint8(vec4ub x, uint8 y, vec4ub* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_vec2h(float16 x, vec2h y, vec2h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_vec3h(float16 x, vec3h y, vec3h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_vec4h(float16 x, vec4h y, vec4h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_spatial_vectorh(float16 x, spatial_vectorh y, spatial_vectorh* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_vec2f(float32 x, vec2f y, vec2f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_vec3f(float32 x, vec3f y, vec3f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_vec4f(float32 x, vec4f y, vec4f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_spatial_vectorf(float32 x, spatial_vectorf y, spatial_vectorf* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_vec2d(float64 x, vec2d y, vec2d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_vec3d(float64 x, vec3d y, vec3d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_vec4d(float64 x, vec4d y, vec4d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_spatial_vectord(float64 x, spatial_vectord y, spatial_vectord* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int16_vec2s(int16 x, vec2s y, vec2s* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int16_vec3s(int16 x, vec3s y, vec3s* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int16_vec4s(int16 x, vec4s y, vec4s* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int32_vec2i(int32 x, vec2i y, vec2i* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int32_vec3i(int32 x, vec3i y, vec3i* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int32_vec4i(int32 x, vec4i y, vec4i* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int64_vec2l(int64 x, vec2l y, vec2l* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int64_vec3l(int64 x, vec3l y, vec3l* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int64_vec4l(int64 x, vec4l y, vec4l* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int8_vec2b(int8 x, vec2b y, vec2b* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int8_vec3b(int8 x, vec3b y, vec3b* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_int8_vec4b(int8 x, vec4b y, vec4b* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint16_vec2us(uint16 x, vec2us y, vec2us* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint16_vec3us(uint16 x, vec3us y, vec3us* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint16_vec4us(uint16 x, vec4us y, vec4us* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint32_vec2ui(uint32 x, vec2ui y, vec2ui* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint32_vec3ui(uint32 x, vec3ui y, vec3ui* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint32_vec4ui(uint32 x, vec4ui y, vec4ui* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint64_vec2ul(uint64 x, vec2ul y, vec2ul* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint64_vec3ul(uint64 x, vec3ul y, vec3ul* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint64_vec4ul(uint64 x, vec4ul y, vec4ul* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint8_vec2ub(uint8 x, vec2ub y, vec2ub* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint8_vec3ub(uint8 x, vec3ub y, vec3ub* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_uint8_vec4ub(uint8 x, vec4ub y, vec4ub* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat22h_float16(mat22h x, float16 y, mat22h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat33h_float16(mat33h x, float16 y, mat33h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat44h_float16(mat44h x, float16 y, mat44h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_spatial_matrixh_float16(spatial_matrixh x, float16 y, spatial_matrixh* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat22f_float32(mat22f x, float32 y, mat22f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat33f_float32(mat33f x, float32 y, mat33f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat44f_float32(mat44f x, float32 y, mat44f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_spatial_matrixf_float32(spatial_matrixf x, float32 y, spatial_matrixf* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat22d_float64(mat22d x, float64 y, mat22d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat33d_float64(mat33d x, float64 y, mat33d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_mat44d_float64(mat44d x, float64 y, mat44d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_spatial_matrixd_float64(spatial_matrixd x, float64 y, spatial_matrixd* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_mat22h(float16 x, mat22h y, mat22h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_mat33h(float16 x, mat33h y, mat33h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_mat44h(float16 x, mat44h y, mat44h* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_spatial_matrixh(float16 x, spatial_matrixh y, spatial_matrixh* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_mat22f(float32 x, mat22f y, mat22f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_mat33f(float32 x, mat33f y, mat33f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_mat44f(float32 x, mat44f y, mat44f* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_spatial_matrixf(float32 x, spatial_matrixf y, spatial_matrixf* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_mat22d(float64 x, mat22d y, mat22d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_mat33d(float64 x, mat33d y, mat33d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_mat44d(float64 x, mat44d y, mat44d* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_spatial_matrixd(float64 x, spatial_matrixd y, spatial_matrixd* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_quath_float16(quath x, float16 y, quath* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_quatf_float32(quatf x, float32 y, quatf* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_quatd_float64(quatd x, float64 y, quatd* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float16_quath(float16 x, quath y, quath* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float32_quatf(float32 x, quatf y, quatf* ret) { *ret = wp::div(x, y); } -WP_API void builtin_div_float64_quatd(float64 x, quatd y, quatd* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2h_float16(vec2h& x, float16 y, vec2h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3h_float16(vec3h& x, float16 y, vec3h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4h_float16(vec4h& x, float16 y, vec4h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_spatial_vectorh_float16(spatial_vectorh& x, float16 y, spatial_vectorh* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2f_float32(vec2f& x, float32 y, vec2f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3f_float32(vec3f& x, float32 y, vec3f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4f_float32(vec4f& x, float32 y, vec4f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_spatial_vectorf_float32(spatial_vectorf& x, float32 y, spatial_vectorf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2d_float64(vec2d& x, float64 y, vec2d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3d_float64(vec3d& x, float64 y, vec3d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4d_float64(vec4d& x, float64 y, vec4d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_spatial_vectord_float64(spatial_vectord& x, float64 y, spatial_vectord* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2s_int16(vec2s& x, int16 y, vec2s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3s_int16(vec3s& x, int16 y, vec3s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4s_int16(vec4s& x, int16 y, vec4s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2i_int32(vec2i& x, int32 y, vec2i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3i_int32(vec3i& x, int32 y, vec3i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4i_int32(vec4i& x, int32 y, vec4i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2l_int64(vec2l& x, int64 y, vec2l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3l_int64(vec3l& x, int64 y, vec3l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4l_int64(vec4l& x, int64 y, vec4l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2b_int8(vec2b& x, int8 y, vec2b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3b_int8(vec3b& x, int8 y, vec3b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4b_int8(vec4b& x, int8 y, vec4b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2us_uint16(vec2us& x, uint16 y, vec2us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3us_uint16(vec3us& x, uint16 y, vec3us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4us_uint16(vec4us& x, uint16 y, vec4us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2ui_uint32(vec2ui& x, uint32 y, vec2ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3ui_uint32(vec3ui& x, uint32 y, vec3ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4ui_uint32(vec4ui& x, uint32 y, vec4ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2ul_uint64(vec2ul& x, uint64 y, vec2ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3ul_uint64(vec3ul& x, uint64 y, vec3ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4ul_uint64(vec4ul& x, uint64 y, vec4ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec2ub_uint8(vec2ub& x, uint8 y, vec2ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec3ub_uint8(vec3ub& x, uint8 y, vec3ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_vec4ub_uint8(vec4ub& x, uint8 y, vec4ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_vec2h(float16 x, vec2h& y, vec2h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_vec3h(float16 x, vec3h& y, vec3h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_vec4h(float16 x, vec4h& y, vec4h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_spatial_vectorh(float16 x, spatial_vectorh& y, spatial_vectorh* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_vec2f(float32 x, vec2f& y, vec2f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_vec3f(float32 x, vec3f& y, vec3f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_vec4f(float32 x, vec4f& y, vec4f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_spatial_vectorf(float32 x, spatial_vectorf& y, spatial_vectorf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_vec2d(float64 x, vec2d& y, vec2d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_vec3d(float64 x, vec3d& y, vec3d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_vec4d(float64 x, vec4d& y, vec4d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_spatial_vectord(float64 x, spatial_vectord& y, spatial_vectord* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int16_vec2s(int16 x, vec2s& y, vec2s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int16_vec3s(int16 x, vec3s& y, vec3s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int16_vec4s(int16 x, vec4s& y, vec4s* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int32_vec2i(int32 x, vec2i& y, vec2i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int32_vec3i(int32 x, vec3i& y, vec3i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int32_vec4i(int32 x, vec4i& y, vec4i* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int64_vec2l(int64 x, vec2l& y, vec2l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int64_vec3l(int64 x, vec3l& y, vec3l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int64_vec4l(int64 x, vec4l& y, vec4l* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int8_vec2b(int8 x, vec2b& y, vec2b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int8_vec3b(int8 x, vec3b& y, vec3b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_int8_vec4b(int8 x, vec4b& y, vec4b* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint16_vec2us(uint16 x, vec2us& y, vec2us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint16_vec3us(uint16 x, vec3us& y, vec3us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint16_vec4us(uint16 x, vec4us& y, vec4us* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint32_vec2ui(uint32 x, vec2ui& y, vec2ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint32_vec3ui(uint32 x, vec3ui& y, vec3ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint32_vec4ui(uint32 x, vec4ui& y, vec4ui* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint64_vec2ul(uint64 x, vec2ul& y, vec2ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint64_vec3ul(uint64 x, vec3ul& y, vec3ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint64_vec4ul(uint64 x, vec4ul& y, vec4ul* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint8_vec2ub(uint8 x, vec2ub& y, vec2ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint8_vec3ub(uint8 x, vec3ub& y, vec3ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_uint8_vec4ub(uint8 x, vec4ub& y, vec4ub* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat22h_float16(mat22h& x, float16 y, mat22h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat33h_float16(mat33h& x, float16 y, mat33h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat44h_float16(mat44h& x, float16 y, mat44h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_spatial_matrixh_float16(spatial_matrixh& x, float16 y, spatial_matrixh* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat22f_float32(mat22f& x, float32 y, mat22f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat33f_float32(mat33f& x, float32 y, mat33f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat44f_float32(mat44f& x, float32 y, mat44f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_spatial_matrixf_float32(spatial_matrixf& x, float32 y, spatial_matrixf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat22d_float64(mat22d& x, float64 y, mat22d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat33d_float64(mat33d& x, float64 y, mat33d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_mat44d_float64(mat44d& x, float64 y, mat44d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_spatial_matrixd_float64(spatial_matrixd& x, float64 y, spatial_matrixd* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_mat22h(float16 x, mat22h& y, mat22h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_mat33h(float16 x, mat33h& y, mat33h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_mat44h(float16 x, mat44h& y, mat44h* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_spatial_matrixh(float16 x, spatial_matrixh& y, spatial_matrixh* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_mat22f(float32 x, mat22f& y, mat22f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_mat33f(float32 x, mat33f& y, mat33f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_mat44f(float32 x, mat44f& y, mat44f* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_spatial_matrixf(float32 x, spatial_matrixf& y, spatial_matrixf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_mat22d(float64 x, mat22d& y, mat22d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_mat33d(float64 x, mat33d& y, mat33d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_mat44d(float64 x, mat44d& y, mat44d* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_spatial_matrixd(float64 x, spatial_matrixd& y, spatial_matrixd* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_quath_float16(quath& x, float16 y, quath* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_quatf_float32(quatf& x, float32 y, quatf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_quatd_float64(quatd& x, float64 y, quatd* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float16_quath(float16 x, quath& y, quath* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float32_quatf(float32 x, quatf& y, quatf* ret) { *ret = wp::div(x, y); } +WP_API void builtin_div_float64_quatd(float64 x, quatd& y, quatd* ret) { *ret = wp::div(x, y); } WP_API void builtin_floordiv_float16_float16(float16 x, float16 y, float16* ret) { *ret = wp::floordiv(x, y); } WP_API void builtin_floordiv_float32_float32(float32 x, float32 y, float32* ret) { *ret = wp::floordiv(x, y); } WP_API void builtin_floordiv_float64_float64(float64 x, float64 y, float64* ret) { *ret = wp::floordiv(x, y); } @@ -1402,57 +1402,57 @@ WP_API void builtin_pos_uint16(uint16 x, uint16* ret) { *ret = wp::pos(x); } WP_API void builtin_pos_uint32(uint32 x, uint32* ret) { *ret = wp::pos(x); } WP_API void builtin_pos_uint64(uint64 x, uint64* ret) { *ret = wp::pos(x); } WP_API void builtin_pos_uint8(uint8 x, uint8* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2h(vec2h x, vec2h* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3h(vec3h x, vec3h* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4h(vec4h x, vec4h* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_spatial_vectorh(spatial_vectorh x, spatial_vectorh* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2f(vec2f x, vec2f* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3f(vec3f x, vec3f* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4f(vec4f x, vec4f* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_spatial_vectorf(spatial_vectorf x, spatial_vectorf* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2d(vec2d x, vec2d* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3d(vec3d x, vec3d* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4d(vec4d x, vec4d* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_spatial_vectord(spatial_vectord x, spatial_vectord* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2s(vec2s x, vec2s* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3s(vec3s x, vec3s* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4s(vec4s x, vec4s* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2i(vec2i x, vec2i* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3i(vec3i x, vec3i* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4i(vec4i x, vec4i* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2l(vec2l x, vec2l* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3l(vec3l x, vec3l* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4l(vec4l x, vec4l* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2b(vec2b x, vec2b* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3b(vec3b x, vec3b* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4b(vec4b x, vec4b* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2us(vec2us x, vec2us* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3us(vec3us x, vec3us* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4us(vec4us x, vec4us* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2ui(vec2ui x, vec2ui* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3ui(vec3ui x, vec3ui* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4ui(vec4ui x, vec4ui* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2ul(vec2ul x, vec2ul* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3ul(vec3ul x, vec3ul* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4ul(vec4ul x, vec4ul* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec2ub(vec2ub x, vec2ub* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec3ub(vec3ub x, vec3ub* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_vec4ub(vec4ub x, vec4ub* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_quath(quath x, quath* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_quatf(quatf x, quatf* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_quatd(quatd x, quatd* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat22h(mat22h x, mat22h* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat33h(mat33h x, mat33h* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat44h(mat44h x, mat44h* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_spatial_matrixh(spatial_matrixh x, spatial_matrixh* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat22f(mat22f x, mat22f* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat33f(mat33f x, mat33f* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat44f(mat44f x, mat44f* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_spatial_matrixf(spatial_matrixf x, spatial_matrixf* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat22d(mat22d x, mat22d* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat33d(mat33d x, mat33d* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_mat44d(mat44d x, mat44d* ret) { *ret = wp::pos(x); } -WP_API void builtin_pos_spatial_matrixd(spatial_matrixd x, spatial_matrixd* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2h(vec2h& x, vec2h* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3h(vec3h& x, vec3h* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4h(vec4h& x, vec4h* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_spatial_vectorh(spatial_vectorh& x, spatial_vectorh* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2f(vec2f& x, vec2f* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3f(vec3f& x, vec3f* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4f(vec4f& x, vec4f* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_spatial_vectorf(spatial_vectorf& x, spatial_vectorf* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2d(vec2d& x, vec2d* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3d(vec3d& x, vec3d* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4d(vec4d& x, vec4d* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_spatial_vectord(spatial_vectord& x, spatial_vectord* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2s(vec2s& x, vec2s* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3s(vec3s& x, vec3s* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4s(vec4s& x, vec4s* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2i(vec2i& x, vec2i* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3i(vec3i& x, vec3i* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4i(vec4i& x, vec4i* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2l(vec2l& x, vec2l* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3l(vec3l& x, vec3l* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4l(vec4l& x, vec4l* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2b(vec2b& x, vec2b* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3b(vec3b& x, vec3b* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4b(vec4b& x, vec4b* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2us(vec2us& x, vec2us* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3us(vec3us& x, vec3us* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4us(vec4us& x, vec4us* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2ui(vec2ui& x, vec2ui* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3ui(vec3ui& x, vec3ui* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4ui(vec4ui& x, vec4ui* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2ul(vec2ul& x, vec2ul* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3ul(vec3ul& x, vec3ul* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4ul(vec4ul& x, vec4ul* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec2ub(vec2ub& x, vec2ub* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec3ub(vec3ub& x, vec3ub* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_vec4ub(vec4ub& x, vec4ub* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_quath(quath& x, quath* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_quatf(quatf& x, quatf* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_quatd(quatd& x, quatd* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat22h(mat22h& x, mat22h* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat33h(mat33h& x, mat33h* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat44h(mat44h& x, mat44h* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_spatial_matrixh(spatial_matrixh& x, spatial_matrixh* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat22f(mat22f& x, mat22f* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat33f(mat33f& x, mat33f* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat44f(mat44f& x, mat44f* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_spatial_matrixf(spatial_matrixf& x, spatial_matrixf* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat22d(mat22d& x, mat22d* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat33d(mat33d& x, mat33d* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_mat44d(mat44d& x, mat44d* ret) { *ret = wp::pos(x); } +WP_API void builtin_pos_spatial_matrixd(spatial_matrixd& x, spatial_matrixd* ret) { *ret = wp::pos(x); } WP_API void builtin_neg_float16(float16 x, float16* ret) { *ret = wp::neg(x); } WP_API void builtin_neg_float32(float32 x, float32* ret) { *ret = wp::neg(x); } WP_API void builtin_neg_float64(float64 x, float64* ret) { *ret = wp::neg(x); } @@ -1464,57 +1464,57 @@ WP_API void builtin_neg_uint16(uint16 x, uint16* ret) { *ret = wp::neg(x); } WP_API void builtin_neg_uint32(uint32 x, uint32* ret) { *ret = wp::neg(x); } WP_API void builtin_neg_uint64(uint64 x, uint64* ret) { *ret = wp::neg(x); } WP_API void builtin_neg_uint8(uint8 x, uint8* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2h(vec2h x, vec2h* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3h(vec3h x, vec3h* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4h(vec4h x, vec4h* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_spatial_vectorh(spatial_vectorh x, spatial_vectorh* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2f(vec2f x, vec2f* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3f(vec3f x, vec3f* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4f(vec4f x, vec4f* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_spatial_vectorf(spatial_vectorf x, spatial_vectorf* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2d(vec2d x, vec2d* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3d(vec3d x, vec3d* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4d(vec4d x, vec4d* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_spatial_vectord(spatial_vectord x, spatial_vectord* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2s(vec2s x, vec2s* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3s(vec3s x, vec3s* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4s(vec4s x, vec4s* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2i(vec2i x, vec2i* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3i(vec3i x, vec3i* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4i(vec4i x, vec4i* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2l(vec2l x, vec2l* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3l(vec3l x, vec3l* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4l(vec4l x, vec4l* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2b(vec2b x, vec2b* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3b(vec3b x, vec3b* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4b(vec4b x, vec4b* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2us(vec2us x, vec2us* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3us(vec3us x, vec3us* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4us(vec4us x, vec4us* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2ui(vec2ui x, vec2ui* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3ui(vec3ui x, vec3ui* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4ui(vec4ui x, vec4ui* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2ul(vec2ul x, vec2ul* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3ul(vec3ul x, vec3ul* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4ul(vec4ul x, vec4ul* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec2ub(vec2ub x, vec2ub* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec3ub(vec3ub x, vec3ub* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_vec4ub(vec4ub x, vec4ub* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_quath(quath x, quath* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_quatf(quatf x, quatf* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_quatd(quatd x, quatd* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat22h(mat22h x, mat22h* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat33h(mat33h x, mat33h* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat44h(mat44h x, mat44h* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_spatial_matrixh(spatial_matrixh x, spatial_matrixh* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat22f(mat22f x, mat22f* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat33f(mat33f x, mat33f* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat44f(mat44f x, mat44f* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_spatial_matrixf(spatial_matrixf x, spatial_matrixf* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat22d(mat22d x, mat22d* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat33d(mat33d x, mat33d* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_mat44d(mat44d x, mat44d* ret) { *ret = wp::neg(x); } -WP_API void builtin_neg_spatial_matrixd(spatial_matrixd x, spatial_matrixd* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2h(vec2h& x, vec2h* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3h(vec3h& x, vec3h* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4h(vec4h& x, vec4h* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_spatial_vectorh(spatial_vectorh& x, spatial_vectorh* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2f(vec2f& x, vec2f* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3f(vec3f& x, vec3f* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4f(vec4f& x, vec4f* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_spatial_vectorf(spatial_vectorf& x, spatial_vectorf* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2d(vec2d& x, vec2d* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3d(vec3d& x, vec3d* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4d(vec4d& x, vec4d* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_spatial_vectord(spatial_vectord& x, spatial_vectord* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2s(vec2s& x, vec2s* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3s(vec3s& x, vec3s* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4s(vec4s& x, vec4s* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2i(vec2i& x, vec2i* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3i(vec3i& x, vec3i* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4i(vec4i& x, vec4i* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2l(vec2l& x, vec2l* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3l(vec3l& x, vec3l* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4l(vec4l& x, vec4l* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2b(vec2b& x, vec2b* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3b(vec3b& x, vec3b* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4b(vec4b& x, vec4b* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2us(vec2us& x, vec2us* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3us(vec3us& x, vec3us* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4us(vec4us& x, vec4us* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2ui(vec2ui& x, vec2ui* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3ui(vec3ui& x, vec3ui* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4ui(vec4ui& x, vec4ui* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2ul(vec2ul& x, vec2ul* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3ul(vec3ul& x, vec3ul* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4ul(vec4ul& x, vec4ul* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec2ub(vec2ub& x, vec2ub* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec3ub(vec3ub& x, vec3ub* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_vec4ub(vec4ub& x, vec4ub* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_quath(quath& x, quath* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_quatf(quatf& x, quatf* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_quatd(quatd& x, quatd* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat22h(mat22h& x, mat22h* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat33h(mat33h& x, mat33h* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat44h(mat44h& x, mat44h* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_spatial_matrixh(spatial_matrixh& x, spatial_matrixh* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat22f(mat22f& x, mat22f* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat33f(mat33f& x, mat33f* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat44f(mat44f& x, mat44f* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_spatial_matrixf(spatial_matrixf& x, spatial_matrixf* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat22d(mat22d& x, mat22d* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat33d(mat33d& x, mat33d* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_mat44d(mat44d& x, mat44d* ret) { *ret = wp::neg(x); } +WP_API void builtin_neg_spatial_matrixd(spatial_matrixd& x, spatial_matrixd* ret) { *ret = wp::neg(x); } WP_API void builtin_unot_bool(bool b, bool* ret) { *ret = wp::unot(b); } WP_API void builtin_unot_int8(int8 b, bool* ret) { *ret = wp::unot(b); } WP_API void builtin_unot_uint8(uint8 b, bool* ret) { *ret = wp::unot(b); } From 060e5f860ac23cedf656228b3d2f5ca1f8c5d725 Mon Sep 17 00:00:00 2001 From: Christopher Crouzet Date: Mon, 18 Dec 2023 11:46:02 +1300 Subject: [PATCH 41/50] Update the repository URL --- .teamcity/settings.kts | 2 +- PACKAGE-INFO.yaml | 6 +++--- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/.teamcity/settings.kts b/.teamcity/settings.kts index 61211edf1..94d1d4c66 100644 --- a/.teamcity/settings.kts +++ b/.teamcity/settings.kts @@ -42,7 +42,7 @@ project { object GitlabMasterWarp : GitVcsRoot({ name = "gitlab-master-warp" - url = "ssh://git@gitlab-master.nvidia.com:12051/mmacklin/warp.git" + url = "ssh://git@gitlab-master.nvidia.com:12051/omniverse/warp.git" branch = "refs/heads/tc" branchSpec = """ +:refs/heads/WARForTeamCityNotFillingParamsUnlessThereIsABranchSpecDefined diff --git a/PACKAGE-INFO.yaml b/PACKAGE-INFO.yaml index 8df6f24db..fa9860079 100644 --- a/PACKAGE-INFO.yaml +++ b/PACKAGE-INFO.yaml @@ -1,6 +1,6 @@ Package : warp -Description : -Maintainers : +Description : +Maintainers : SWIPAT NvBug : -Repository : https://gitlab-master.nvidia.com/mmacklin/warp +Repository : https://gitlab-master.nvidia.com/omniverse/warp License Type : NVIDIA From 9ae387756329f4cc20b528bd65bc6d7d5478176c Mon Sep 17 00:00:00 2001 From: Zach Corse Date: Sun, 17 Dec 2023 18:54:17 -0800 Subject: [PATCH 42/50] matmul adjoints now accumulate --- warp/tests/test_matmul.py | 30 +++++++++ warp/types.py | 129 +++++++++++++------------------------- warp/utils.py | 14 +++++ 3 files changed, 86 insertions(+), 87 deletions(-) diff --git a/warp/tests/test_matmul.py b/warp/tests/test_matmul.py index 27b404485..225770b12 100644 --- a/warp/tests/test_matmul.py +++ b/warp/tests/test_matmul.py @@ -331,6 +331,7 @@ def test_tape(test, device): tape.backward(loss=loss) A_grad = A.grad.numpy() + tape.reset() # test adjoint D.grad = wp.array2d(np.ones((m, n)), dtype=float, device=device) @@ -420,6 +421,34 @@ def test_large_batch_count(test, device): assert np.array_equal(adj_C_np, C.grad.numpy()) +def test_adjoint_accumulation(test, device): + a_np = np.ones(shape=(2,3)) + b_np = np.ones(shape=(3,2)) + c_np = np.zeros(shape=(2,2)) + d_np = np.zeros(shape=(2,2)) + + a_wp = wp.from_numpy(a_np, dtype=float, requires_grad=True) + b_wp = wp.from_numpy(b_np, dtype=float, requires_grad=True) + c_wp = wp.from_numpy(c_np, dtype=float, requires_grad=True) + d1_wp = wp.from_numpy(d_np, dtype=float, requires_grad=True) + d2_wp = wp.from_numpy(d_np, dtype=float, requires_grad=True) + + tape = wp.Tape() + + with tape: + wp.matmul(a_wp, b_wp, c_wp, d1_wp, alpha=1.0, beta=1.0) + wp.matmul(a_wp, b_wp, d1_wp, d2_wp, alpha=1.0, beta=1.0) + + d_grad = wp.zeros_like(d2_wp) + d_grad.fill_(1.) + grads = {d2_wp : d_grad} + tape.backward(grads=grads) + + assert np.array_equal(a_wp.grad.numpy(), 4.0 * np.ones(shape=(2,3))) + assert np.array_equal(b_wp.grad.numpy(), 4.0 * np.ones(shape=(3,2))) + assert np.array_equal(c_wp.grad.numpy(), np.ones(shape=(2,2))) + + def register(parent): devices = [d for d in get_test_devices()] @@ -437,6 +466,7 @@ class TestMatmul(parent): add_function_test(TestMatmul, "test_tape", test_tape, devices=devices) add_function_test(TestMatmul, "test_operator", test_operator, devices=devices) add_function_test(TestMatmul, "test_large_batch_count", test_large_batch_count, devices=devices) + add_function_test(TestMatmul, "test_adjoint_accumulation", test_adjoint_accumulation, devices=devices) else: print("Skipping matmul tests because CUTLASS is not supported in this build") diff --git a/warp/types.py b/warp/types.py index 3e056174b..d396780b6 100644 --- a/warp/types.py +++ b/warp/types.py @@ -3221,9 +3221,9 @@ def adj_matmul( # cpu fallback if no cuda devices found if device == "cpu": - adj_a.assign(alpha * np.matmul(adj_d.numpy(), b.numpy().transpose())) - adj_b.assign(alpha * (a.numpy().transpose() @ adj_d.numpy())) - adj_c.assign(beta * adj_d.numpy()) + adj_a.assign(alpha * np.matmul(adj_d.numpy(), b.numpy().transpose()) + adj_a.numpy()) + adj_b.assign(alpha * (a.numpy().transpose() @ adj_d.numpy()) + adj_b.numpy()) + adj_c.assign(beta * adj_d.numpy() + adj_c.numpy()) return cc = device.arch @@ -3238,10 +3238,10 @@ def adj_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(adj_d.ptr), ctypes.c_void_p(b.ptr), - ctypes.c_void_p(a.ptr), + ctypes.c_void_p(adj_a.ptr), ctypes.c_void_p(adj_a.ptr), alpha, - 0.0, + 1.0, True, b.is_transposed, allow_tf32x3_arith, @@ -3258,10 +3258,10 @@ def adj_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(b.ptr), ctypes.c_void_p(adj_d.ptr), - ctypes.c_void_p(a.ptr), + ctypes.c_void_p(adj_a.ptr), ctypes.c_void_p(adj_a.ptr), alpha, - 0.0, + 1.0, not b.is_transposed, False, allow_tf32x3_arith, @@ -3280,10 +3280,10 @@ def adj_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(a.ptr), ctypes.c_void_p(adj_d.ptr), - ctypes.c_void_p(b.ptr), + ctypes.c_void_p(adj_b.ptr), ctypes.c_void_p(adj_b.ptr), alpha, - 0.0, + 1.0, a.is_transposed, True, allow_tf32x3_arith, @@ -3300,10 +3300,10 @@ def adj_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(adj_d.ptr), ctypes.c_void_p(a.ptr), - ctypes.c_void_p(b.ptr), + ctypes.c_void_p(adj_b.ptr), ctypes.c_void_p(adj_b.ptr), alpha, - 0.0, + 1.0, False, not a.is_transposed, allow_tf32x3_arith, @@ -3313,25 +3313,13 @@ def adj_matmul( raise RuntimeError("adj_matmul failed.") # adj_c - ret = runtime.core.cutlass_gemm( - cc, - m, - n, - k, - type_typestr(a.dtype).encode(), - ctypes.c_void_p(a.ptr), - ctypes.c_void_p(b.ptr), - ctypes.c_void_p(adj_d.ptr), - ctypes.c_void_p(adj_c.ptr), - 0.0, - beta, - not a.is_transposed, - not b.is_transposed, - allow_tf32x3_arith, - 1, + warp.launch( + kernel=warp.utils.add_kernel_2d, + dim=adj_c.shape, + inputs=[adj_c, adj_d, adj_d.dtype(beta)], + device=device, + record_tape=False ) - if not ret: - raise RuntimeError("adj_matmul failed.") def batched_matmul( @@ -3540,9 +3528,9 @@ def adj_batched_matmul( # cpu fallback if no cuda devices found if device == "cpu": - adj_a.assign(alpha * np.matmul(adj_d.numpy(), b.numpy().transpose((0, 2, 1)))) - adj_b.assign(alpha * np.matmul(a.numpy().transpose((0, 2, 1)), adj_d.numpy())) - adj_c.assign(beta * adj_d.numpy()) + adj_a.assign(alpha * np.matmul(adj_d.numpy(), b.numpy().transpose((0, 2, 1))) + adj_a.numpy()) + adj_b.assign(alpha * np.matmul(a.numpy().transpose((0, 2, 1)), adj_d.numpy()) + adj_b.numpy()) + adj_c.assign(beta * adj_d.numpy() + adj_c.numpy()) return # handle case in which batch_count exceeds max_batch_count, which is a CUDA array size maximum @@ -3566,10 +3554,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(adj_d[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(b[idx_start:idx_end,:,:].ptr), - ctypes.c_void_p(a[idx_start:idx_end,:,:].ptr), + ctypes.c_void_p(adj_a[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(adj_a[idx_start:idx_end,:,:].ptr), alpha, - 0.0, + 1.0, True, b.is_transposed, allow_tf32x3_arith, @@ -3586,10 +3574,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(b[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(adj_d[idx_start:idx_end,:,:].ptr), - ctypes.c_void_p(a[idx_start:idx_end,:,:].ptr), + ctypes.c_void_p(adj_a[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(adj_a[idx_start:idx_end,:,:].ptr), alpha, - 0.0, + 1.0, not b.is_transposed, False, allow_tf32x3_arith, @@ -3608,10 +3596,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(a[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(adj_d[idx_start:idx_end,:,:].ptr), - ctypes.c_void_p(b[idx_start:idx_end,:,:].ptr), + ctypes.c_void_p(adj_b[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(adj_b[idx_start:idx_end,:,:].ptr), alpha, - 0.0, + 1.0, a.is_transposed, True, allow_tf32x3_arith, @@ -3628,10 +3616,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(adj_d[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(a[idx_start:idx_end,:,:].ptr), - ctypes.c_void_p(b[idx_start:idx_end,:,:].ptr), + ctypes.c_void_p(adj_b[idx_start:idx_end,:,:].ptr), ctypes.c_void_p(adj_b[idx_start:idx_end,:,:].ptr), alpha, - 0.0, + 1.0, False, not a.is_transposed, allow_tf32x3_arith, @@ -3639,27 +3627,6 @@ def adj_batched_matmul( ) if not ret: raise RuntimeError("adj_matmul failed.") - - # adj_c - ret = runtime.core.cutlass_gemm( - cc, - m, - n, - k, - type_typestr(a.dtype).encode(), - ctypes.c_void_p(a[idx_start:idx_end,:,:].ptr), - ctypes.c_void_p(b[idx_start:idx_end,:,:].ptr), - ctypes.c_void_p(adj_d[idx_start:idx_end,:,:].ptr), - ctypes.c_void_p(adj_c[idx_start:idx_end,:,:].ptr), - 0.0, - beta, - not a.is_transposed, - not b.is_transposed, - allow_tf32x3_arith, - max_batch_count, - ) - if not ret: - raise RuntimeError("adj_batched_matmul failed.") idx_start = iters * max_batch_count @@ -3673,10 +3640,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(adj_d[idx_start:,:,:].ptr), ctypes.c_void_p(b[idx_start:,:,:].ptr), - ctypes.c_void_p(a[idx_start:,:,:].ptr), + ctypes.c_void_p(adj_a[idx_start:,:,:].ptr), ctypes.c_void_p(adj_a[idx_start:,:,:].ptr), alpha, - 0.0, + 1.0, True, b.is_transposed, allow_tf32x3_arith, @@ -3693,10 +3660,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(b[idx_start:,:,:].ptr), ctypes.c_void_p(adj_d[idx_start:,:,:].ptr), - ctypes.c_void_p(a[idx_start:,:,:].ptr), + ctypes.c_void_p(adj_a[idx_start:,:,:].ptr), ctypes.c_void_p(adj_a[idx_start:,:,:].ptr), alpha, - 0.0, + 1.0, not b.is_transposed, False, allow_tf32x3_arith, @@ -3715,10 +3682,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(a[idx_start:,:,:].ptr), ctypes.c_void_p(adj_d[idx_start:,:,:].ptr), - ctypes.c_void_p(b[idx_start:,:,:].ptr), + ctypes.c_void_p(adj_b[idx_start:,:,:].ptr), ctypes.c_void_p(adj_b[idx_start:,:,:].ptr), alpha, - 0.0, + 1.0, a.is_transposed, True, allow_tf32x3_arith, @@ -3735,10 +3702,10 @@ def adj_batched_matmul( type_typestr(a.dtype).encode(), ctypes.c_void_p(adj_d[idx_start:,:,:].ptr), ctypes.c_void_p(a[idx_start:,:,:].ptr), - ctypes.c_void_p(b[idx_start:,:,:].ptr), + ctypes.c_void_p(adj_b[idx_start:,:,:].ptr), ctypes.c_void_p(adj_b[idx_start:,:,:].ptr), alpha, - 0.0, + 1.0, False, not a.is_transposed, allow_tf32x3_arith, @@ -3748,25 +3715,13 @@ def adj_batched_matmul( raise RuntimeError("adj_matmul failed.") # adj_c - ret = runtime.core.cutlass_gemm( - cc, - m, - n, - k, - type_typestr(a.dtype).encode(), - ctypes.c_void_p(a[idx_start:,:,:].ptr), - ctypes.c_void_p(b[idx_start:,:,:].ptr), - ctypes.c_void_p(adj_d[idx_start:,:,:].ptr), - ctypes.c_void_p(adj_c[idx_start:,:,:].ptr), - 0.0, - beta, - not a.is_transposed, - not b.is_transposed, - allow_tf32x3_arith, - remainder, + warp.launch( + kernel=warp.utils.add_kernel_3d, + dim=adj_c.shape, + inputs=[adj_c, adj_d, adj_d.dtype(beta)], + device=device, + record_tape=False ) - if not ret: - raise RuntimeError("adj_batched_matmul failed.") class HashGrid: def __init__(self, dim_x, dim_y, dim_z, device=None): diff --git a/warp/utils.py b/warp/utils.py index e38c14326..1ce30d52c 100644 --- a/warp/utils.py +++ b/warp/utils.py @@ -666,3 +666,17 @@ def __exit__(self, exc_type, exc_value, traceback): print("{}{} took {:.2f} ms".format(indent, self.name, self.elapsed)) ScopedTimer.indent -= 1 + + +# helper kernels for adj_matmul +@wp.kernel +def add_kernel_2d(x: wp.array2d(dtype=Any), acc: wp.array2d(dtype=Any), beta: Any): + i, j = wp.tid() + + x[i,j] = x[i,j] + beta * acc[i,j] + +@wp.kernel +def add_kernel_3d(x: wp.array3d(dtype=Any), acc: wp.array3d(dtype=Any), beta: Any): + i, j, k = wp.tid() + + x[i,j,k] = x[i,j,k] + beta * acc[i,j,k] From 647fd35c5303f038558cb6b4b8543deaff8ceac5 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Fri, 15 Dec 2023 21:30:52 -0500 Subject: [PATCH 43/50] Support building pip wheels for Linux AArch64 Previously we relied solely on the extension of the `warp/bin/` libraries to determine the wheel's binary distribution platform. This no longer works since Linux builds for x86-64 and AArch64 both use the `.so` extension. Instead this change relies on the libraries to be placed in a subdirectory of `warp/bin/` which indicates one of (currently) four platforms: - windows-x86_64 - linux-x86_64 - linux-aarch64 - macos-universal CD systems are responsible for putting the libraries in these subdirectories. Creating a wheel from a local build is still supported, by assuming the wheel's architecture should match the system's architecture. --- PACKAGING.md | 7 +++-- setup.py | 89 ++++++++++++++++++++++++++++++++++++++-------------- 2 files changed, 70 insertions(+), 26 deletions(-) diff --git a/PACKAGING.md b/PACKAGING.md index 10ef78bd2..db64ff7e6 100644 --- a/PACKAGING.md +++ b/PACKAGING.md @@ -73,9 +73,10 @@ Release Steps: 3) Run ```bash - python -m build --wheel -C--build-option=-Pwindows && - python -m build --wheel -C--build-option=-Plinux && - python -m build --wheel -C--build-option=-Pmacos + python -m build --wheel -C--build-option=-Pwindows-x86_64 && + python -m build --wheel -C--build-option=-Plinux-x86_64 && + python -m build --wheel -C--build-option=-Plinux-aarch64 && + python -m build --wheel -C--build-option=-Pmacos-universal ``` 4) Run `python -m twine upload dist/*` diff --git a/setup.py b/setup.py index b3897edf0..9a80c2dc1 100644 --- a/setup.py +++ b/setup.py @@ -1,6 +1,8 @@ import argparse import os import shutil +import pathlib +import platform from typing import NamedTuple import setuptools @@ -10,46 +12,80 @@ # ourselves because when bdist_wheel runs it's too late to select a subset of libraries for package_data. parser = argparse.ArgumentParser() parser.add_argument("command") -parser.add_argument("--platform", "-P", type=str, default="", help="Wheel platform: windows|linux|macos") +parser.add_argument( + "--platform", "-P", type=str, default="", help="Wheel platform: windows|linux|macos-x86_64|aarch64|universal" +) args = parser.parse_known_args()[0] +# return a canonical machine architecture string +# - "x86_64" for x86-64, aka. AMD64, aka. x64 +# - "aarch64" for AArch64, aka. ARM64 +def machine_architecture() -> str: + machine = platform.machine() + if machine == "x86_64" or machine == "AMD64": + return "x86_64" + if machine == "aarch64" or machine == "arm64": + return "aarch64" + raise RuntimeError(f"Unrecognized machine architecture {machine}") + + class Platform(NamedTuple): - name: str + os: str + arch: str fancy_name: str extension: str tag: str + def name(self) -> str: + return self.os + "-" + self.arch + platforms = [ - Platform("windows", "Windows", ".dll", "win_amd64"), - Platform("linux", "Linux", ".so", "manylinux2014_x86_64"), - Platform("macos", "macOS", ".dylib", "macosx_10_13_universal2"), + Platform("windows", "x86_64", "Windows x86-64", ".dll", "win_amd64"), + Platform("linux", "x86_64", "Linux x86-64", ".so", "manylinux2014_x86_64"), + Platform("linux", "aarch64", "Linux AArch64", ".so", "manylinux2014_aarch64"), + Platform("macos", "universal", "macOS universal", ".dylib", "macosx_10_13_universal2"), ] -# Determine supported platforms of warp/bin libraries based on their extension -def detect_warp_platforms(): - detected_platforms = set() - for filename in os.listdir("warp/bin"): - for p in platforms: - if os.path.splitext(filename)[1] == p.extension: - detected_platforms.add(p) +class Library(NamedTuple): + file: str + directory: str + platform: Platform + - if len(detected_platforms) == 0: +# Enumerate warp/bin libraries +def detect_warp_libraries(): + detected_libraries = set() + warp_bin = pathlib.Path("warp/bin") + for file in warp_bin.rglob("*.*"): + for p in platforms: + if os.path.splitext(file.name)[1] == p.extension: + # If this is a local build, assume we want a wheel for this machine's architecture + if file.parent.name == "bin" and (p.arch == machine_architecture() or p.arch == "universal"): + detected_libraries.add(Library(file.name, "bin/", p)) + else: + # Excpect libraries to be in a subdirectory named after the wheel platform + platform_name = p.name() + if file.parent.name == platform_name: + detected_libraries.add(Library(file.name, "bin/" + platform_name + "/", p)) + + if len(detected_libraries) == 0: raise Exception("No libraries found in warp/bin. Please run build_lib.py first.") - return detected_platforms + return detected_libraries -detected_platforms = detect_warp_platforms() +detected_libraries = detect_warp_libraries() +detected_platforms = set([lib.platform for lib in detected_libraries]) wheel_platform = None # The one platform for which we're building a wheel if args.command == "bdist_wheel": if args.platform != "": for p in platforms: - if args.platform == p.name or args.platform == p.fancy_name: + if args.platform == p.name(): wheel_platform = p print(f"Platform argument specified for building {p.fancy_name} wheel") break @@ -64,7 +100,9 @@ def detect_warp_platforms(): if wheel_platform is None: if len(detected_platforms) > 1: print("Libraries for multiple platforms were detected. Picking the first one.") - print("Run `python -m build --wheel -C--build-option=-P[windows|linux|macos]` to select a specific one.") + print( + "Run `python -m build --wheel -C--build-option=-P[windows|linux|macos]-[x86_64|aarch64|universal]` to select a specific one." + ) wheel_platform = next(iter(detected_platforms)) print("Creating Warp wheel for " + wheel_platform.fancy_name) @@ -77,7 +115,7 @@ class WarpBDistWheel(bdist_wheel): # Even though we parse the platform argument ourselves, we need to declare it here as well so # setuptools.Command can validate the command line options. user_options = bdist_wheel.user_options + [ - ("platform=", "P", "Wheel platform: windows|linux|macos"), + ("platform=", "P", "Wheel platform: windows|linux|macos-x86_64|aarch64|universal"), ] def initialize_options(self): @@ -109,17 +147,22 @@ def has_ext_modules(self): return True -def get_warp_libraries(extension): +def get_warp_libraries(platform): libraries = [] - for filename in os.listdir("warp/bin"): - if os.path.splitext(filename)[1] == extension: - libraries.append("bin/" + filename) + for library in detected_libraries: + if library.platform == platform: + src = "warp/" + library.directory + library.file + dst = "warp/bin/" + library.file + if src != dst: + shutil.copyfile(src, dst) + + libraries.append("bin/" + library.file) return libraries if wheel_platform is not None: - warp_binary_libraries = get_warp_libraries(wheel_platform.extension) + warp_binary_libraries = get_warp_libraries(wheel_platform) else: warp_binary_libraries = [] # Not needed during egg_info command From 72072ef2368887e1e2ccd563cb2b31802236f656 Mon Sep 17 00:00:00 2001 From: Nicolas Capens Date: Thu, 14 Dec 2023 16:22:27 -0500 Subject: [PATCH 44/50] Build CUDA static code for Jetson into warp.so `warp.so` contains compiled versions of `warp/native/warp.cu` for each supported GPU architecture. Add the ones for Tegra/Jetson when we're on an AArch64 Linux system. --- warp/build_dll.py | 13 ++++++++----- 1 file changed, 8 insertions(+), 5 deletions(-) diff --git a/warp/build_dll.py b/warp/build_dll.py index 60e54325e..65d8c9df5 100644 --- a/warp/build_dll.py +++ b/warp/build_dll.py @@ -182,12 +182,15 @@ def build_dll_for_arch(dll_path, cpp_paths, cu_path, libs, mode, arch, verify_fp "-gencode=arch=compute_75,code=sm_75", # Turing "-gencode=arch=compute_80,code=sm_80", # Ampere "-gencode=arch=compute_86,code=sm_86", - # SASS for supported mobile architectures (e.g. Tegra/Jetson) - # "-gencode=arch=compute_53,code=sm_53", - # "-gencode=arch=compute_62,code=sm_62", - # "-gencode=arch=compute_72,code=sm_72", - # "-gencode=arch=compute_87,code=sm_87", ] + if arch == "arm64" and sys.platform() == "linux": + gencode_opts += [ + # SASS for supported mobile architectures (e.g. Tegra/Jetson) + "-gencode=arch=compute_53,code=sm_53", # X1 + "-gencode=arch=compute_62,code=sm_62", # X2 + "-gencode=arch=compute_72,code=sm_72", # Xavier + "-gencode=arch=compute_87,code=sm_87", # Orin + ] # support for Ada and Hopper is available with CUDA Toolkit 11.8+ if ctk_version >= (11, 8): From 089bb3d4e9ca160e290465656ecaa8ce9c6ee8e5 Mon Sep 17 00:00:00 2001 From: Eric Shi Date: Tue, 19 Dec 2023 13:42:21 -0800 Subject: [PATCH 45/50] Add parallel testing runner --- CHANGELOG.md | 2 +- docs/debugging.rst | 2 +- examples/example_dem.py | 54 +- examples/example_diffray.py | 16 +- examples/example_fluid.py | 10 +- examples/example_mesh_intersect.py | 5 +- examples/example_sim_cartpole.py | 10 +- examples/example_sim_cloth.py | 36 +- examples/example_sim_grad_bounce.py | 15 +- examples/example_sim_grad_cloth.py | 15 +- examples/example_sim_quadruped.py | 9 +- examples/example_sim_rigid_chain.py | 9 +- examples/example_sim_rigid_contact.py | 9 +- examples/example_sim_trajopt.py | 3 +- examples/fem/example_diffusion_mgpu.py | 34 +- .../omni/warp/core/tests/test_ext.py | 156 +- pyproject.toml | 10 +- tools/ci/testing/test-linux-aarch64/test.sh | 2 +- tools/ci/testing/test-linux-x86_64/test.sh | 23 +- tools/ci/testing/test-windows-x86_64/test.bat | 5 +- warp/config.py | 2 + warp/context.py | 5 +- warp/tests/__main__.py | 9 +- ...ass_kernel.py => aux_test_class_kernel.py} | 10 +- ...my.py => aux_test_compile_consts_dummy.py} | 0 ..._test_conditional_unequal_types_kernels.py | 21 + ...est_dependent.py => aux_test_dependent.py} | 4 +- ...est_reference.py => aux_test_reference.py} | 2 +- ...nce.py => aux_test_reference_reference.py} | 0 .../{test_square.py => aux_test_square.py} | 0 warp/tests/aux_test_unresolved_func.py | 14 + warp/tests/aux_test_unresolved_symbol.py | 14 + ...t_kinematics.py => disabled_kinematics.py} | 22 +- warp/tests/run_coverage_serial.py | 31 + warp/tests/test_adam.py | 24 +- warp/tests/test_all.py | 241 -- warp/tests/test_arithmetic.py | 79 +- warp/tests/test_array.py | 94 +- warp/tests/test_array_reduce.py | 44 +- warp/tests/test_atomic.py | 34 +- warp/tests/test_bool.py | 27 +- warp/tests/test_builtins_resolution.py | 1706 ++++----- warp/tests/test_bvh.py | 21 +- warp/tests/test_closest_point_edge_edge.py | 110 +- warp/tests/test_codegen.py | 278 +- warp/tests/test_compile_consts.py | 32 +- warp/tests/test_conditional.py | 62 +- .../test_conditional_unequal_types_kernels.py | 14 - warp/tests/test_copy.py | 21 +- warp/tests/test_coverage.py | 38 - warp/tests/test_ctypes.py | 160 +- warp/tests/test_dense.py | 34 +- warp/tests/test_devices.py | 69 +- warp/tests/test_dlpack.py | 149 +- warp/tests/test_examples.py | 313 +- warp/tests/test_fabricarray.py | 36 +- warp/tests/test_fast_math.py | 25 +- warp/tests/test_fem.py | 68 +- warp/tests/test_fp16.py | 34 +- warp/tests/test_func.py | 371 +- warp/tests/test_generics.py | 146 +- warp/tests/test_grad.py | 66 +- warp/tests/test_grad_customs.py | 16 +- warp/tests/test_hash_grid.py | 16 +- warp/tests/test_import.py | 32 +- warp/tests/test_indexedarray.py | 40 +- warp/tests/test_intersect.py | 24 +- warp/tests/test_large.py | 36 +- warp/tests/test_launch.py | 31 +- warp/tests/test_lerp.py | 126 +- warp/tests/test_lvalue.py | 71 +- warp/tests/test_marching_cubes.py | 22 +- warp/tests/test_mat.py | 3409 ++--------------- warp/tests/test_mat_lite.py | 21 +- warp/tests/test_mat_scalar_ops.py | 2889 ++++++++++++++ warp/tests/test_math.py | 21 +- warp/tests/test_matmul.py | 176 +- warp/tests/test_matmul_lite.py | 169 +- warp/tests/test_mesh.py | 67 +- warp/tests/test_mesh_query_aabb.py | 43 +- warp/tests/test_mesh_query_point.py | 34 +- warp/tests/test_mesh_query_ray.py | 30 +- warp/tests/test_mlp.py | 17 +- warp/tests/test_model.py | 182 +- warp/tests/test_modules_lite.py | 40 +- warp/tests/test_multigpu.py | 201 +- warp/tests/test_noise.py | 22 +- warp/tests/test_operators.py | 35 +- warp/tests/test_options.py | 21 +- warp/tests/test_pinned.py | 34 +- warp/tests/test_print.py | 36 +- warp/tests/test_quat.py | 187 +- warp/tests/test_rand.py | 25 +- warp/tests/test_reload.py | 59 +- warp/tests/test_rounding.py | 17 +- warp/tests/test_runlength_encode.py | 211 +- warp/tests/test_smoothstep.py | 17 +- warp/tests/test_snippet.py | 35 +- warp/tests/test_sparse.py | 59 +- warp/tests/test_spatial.py | 353 +- warp/tests/test_streams.py | 207 +- warp/tests/test_struct.py | 165 +- warp/tests/test_tape.py | 28 +- warp/tests/test_torch.py | 175 +- warp/tests/test_transient_module.py | 21 +- warp/tests/test_types.py | 730 ++-- warp/tests/test_unresolved_func.py | 7 - warp/tests/test_unresolved_symbol.py | 7 - warp/tests/test_utils.py | 435 ++- warp/tests/test_vec.py | 2308 +---------- warp/tests/test_vec_lite.py | 19 +- warp/tests/test_vec_scalar_ops.py | 2099 ++++++++++ warp/tests/test_volume.py | 773 ++-- warp/tests/test_volume_write.py | 257 +- warp/tests/unittest_serial.py | 35 + warp/tests/unittest_suites.py | 291 ++ .../tests/{test_base.py => unittest_utils.py} | 163 +- .../{test_misc.py => unused_test_misc.py} | 18 +- .../{test_debug.py => walkthough_debug.py} | 17 +- warp/thirdparty/unittest_parallel.py | 313 +- 120 files changed, 11044 insertions(+), 10703 deletions(-) rename warp/tests/{test_class_kernel.py => aux_test_class_kernel.py} (54%) rename warp/tests/{test_compile_consts_dummy.py => aux_test_compile_consts_dummy.py} (100%) create mode 100644 warp/tests/aux_test_conditional_unequal_types_kernels.py rename warp/tests/{test_dependent.py => aux_test_dependent.py} (85%) rename warp/tests/{test_reference.py => aux_test_reference.py} (72%) rename warp/tests/{test_reference_reference.py => aux_test_reference_reference.py} (100%) rename warp/tests/{test_square.py => aux_test_square.py} (100%) create mode 100644 warp/tests/aux_test_unresolved_func.py create mode 100644 warp/tests/aux_test_unresolved_symbol.py rename warp/tests/{test_kinematics.py => disabled_kinematics.py} (94%) create mode 100644 warp/tests/run_coverage_serial.py delete mode 100644 warp/tests/test_all.py delete mode 100644 warp/tests/test_conditional_unequal_types_kernels.py delete mode 100644 warp/tests/test_coverage.py create mode 100644 warp/tests/test_mat_scalar_ops.py delete mode 100644 warp/tests/test_unresolved_func.py delete mode 100644 warp/tests/test_unresolved_symbol.py create mode 100644 warp/tests/test_vec_scalar_ops.py create mode 100644 warp/tests/unittest_serial.py create mode 100644 warp/tests/unittest_suites.py rename warp/tests/{test_base.py => unittest_utils.py} (54%) rename warp/tests/{test_misc.py => unused_test_misc.py} (65%) rename warp/tests/{test_debug.py => walkthough_debug.py} (88%) diff --git a/CHANGELOG.md b/CHANGELOG.md index d98de5de3..53b680d60 100644 --- a/CHANGELOG.md +++ b/CHANGELOG.md @@ -148,7 +148,7 @@ ## [0.9.0] - 2023-06-01 - Add support for in-place modifications to vector, matrix, and struct types inside kernels (will warn during backward pass with `wp.verbose` if using gradients) -- Add support for step-through VSCode debugging of kernel code with standalone LLVM compiler, see `wp.breakpoint()`, and `test_debug.py` +- Add support for step-through VSCode debugging of kernel code with standalone LLVM compiler, see `wp.breakpoint()`, and `walkthrough_debug.py` - Add support for default values on built-in functions - Add support for multi-valued `@wp.func` functions - Add support for `pass`, `continue`, and `break` statements diff --git a/docs/debugging.rst b/docs/debugging.rst index c006bd226..4ce66e0d1 100644 --- a/docs/debugging.rst +++ b/docs/debugging.rst @@ -42,7 +42,7 @@ the debugger should be attached, and a breakpoint inserted into the generated co .. note:: Generated kernel code is not a 1:1 correspondence with the original Python code, but individual operations can still be replayed and variables inspected. -Also see :github:`warp/tests/test_debug.py` for an example of how to debug Warp kernel code running on the CPU. +Also see :github:`warp/tests/walkthrough_debug.py` for an example of how to debug Warp kernel code running on the CPU. Generated Code -------------- diff --git a/examples/example_dem.py b/examples/example_dem.py index 44485c882..250f691e7 100644 --- a/examples/example_dem.py +++ b/examples/example_dem.py @@ -118,6 +118,8 @@ def integrate( class Example: def __init__(self, stage): + self.device = wp.get_device() + self.frame_dt = 1.0 / 60 self.frame_count = 400 @@ -150,32 +152,32 @@ def __init__(self, stage): self.use_graph = wp.get_device().is_cuda if self.use_graph: - wp.capture_begin() - - for _ in range(self.sim_substeps): - with wp.ScopedTimer("forces", active=False): - wp.launch( - kernel=apply_forces, - dim=len(self.x), - inputs=[ - self.grid.id, - self.x, - self.v, - self.f, - self.point_radius, - self.k_contact, - self.k_damp, - self.k_friction, - self.k_mu, - ], - ) - wp.launch( - kernel=integrate, - dim=len(self.x), - inputs=[self.x, self.v, self.f, (0.0, -9.8, 0.0), self.sim_dt, self.inv_mass], - ) - - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + for _ in range(self.sim_substeps): + with wp.ScopedTimer("forces", active=False): + wp.launch( + kernel=apply_forces, + dim=len(self.x), + inputs=[ + self.grid.id, + self.x, + self.v, + self.f, + self.point_radius, + self.k_contact, + self.k_damp, + self.k_friction, + self.k_mu, + ], + ) + wp.launch( + kernel=integrate, + dim=len(self.x), + inputs=[self.x, self.v, self.f, (0.0, -9.8, 0.0), self.sim_dt, self.inv_mass], + ) + finally: + self.graph = wp.capture_end(self.device) def update(self): with wp.ScopedTimer("simulate", active=True): diff --git a/examples/example_diffray.py b/examples/example_diffray.py index c02af5739..bca2c01f7 100644 --- a/examples/example_diffray.py +++ b/examples/example_diffray.py @@ -304,6 +304,8 @@ class Example: """ def __init__(self, stage=None, rot_array=[0.0, 0.0, 0.0, 1.0], verbose=False): + self.device = wp.get_device() + self.verbose = verbose cam_pos = wp.vec3(0.0, 0.75, 7.0) cam_rot = wp.quat(0.0, 0.0, 0.0, 1.0) @@ -416,12 +418,14 @@ def __init__(self, stage=None, rot_array=[0.0, 0.0, 0.0, 1.0], verbose=False): self.loss = wp.zeros(1, dtype=float, requires_grad=True) # capture graph - wp.capture_begin() - self.tape = wp.Tape() - with self.tape: - self.compute_loss() - self.tape.backward(self.loss) - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.tape = wp.Tape() + with self.tape: + self.compute_loss() + self.tape.backward(self.loss) + finally: + self.graph = wp.capture_end(self.device) self.optimizer = SGD( [self.render_mesh.rot], diff --git a/examples/example_fluid.py b/examples/example_fluid.py index 50a046ba0..ddd77edc9 100644 --- a/examples/example_fluid.py +++ b/examples/example_fluid.py @@ -165,6 +165,8 @@ def init(rho: wp.array2d(dtype=float), u: wp.array2d(dtype=wp.vec2), radius: int class Example: def __init__(self, **kwargs): + self.device = wp.get_device() + self.sim_fps = 60.0 self.sim_substeps = 2 self.iterations = 100 @@ -187,9 +189,11 @@ def __init__(self, **kwargs): # capture pressure solve as a CUDA graph if self.device.is_cuda: - wp.capture_begin() - self.pressure_iterations() - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.pressure_iterations() + finally: + self.graph = wp.capture_end(self.device) def update(self): with wp.ScopedTimer("update"): diff --git a/examples/example_mesh_intersect.py b/examples/example_mesh_intersect.py index e5e1b6de9..c399ad9ce 100644 --- a/examples/example_mesh_intersect.py +++ b/examples/example_mesh_intersect.py @@ -85,6 +85,7 @@ class Example: def __init__(self, stage): rng = np.random.default_rng() + self.device = wp.get_device() self.query_count = 1024 self.has_queried = False @@ -117,8 +118,8 @@ def __init__(self, stage): self.array_result = wp.zeros(self.query_count, dtype=int) self.array_xforms = wp.array(self.xforms, dtype=wp.transform) - # force module load (for accurate profiling) - wp.force_load() + # compile and load the module up front (for accurate profiling) + wp.load_module(device=self.device) def update(self): with wp.ScopedTimer("intersect", active=True): diff --git a/examples/example_sim_cartpole.py b/examples/example_sim_cartpole.py index 5c2724d8f..7f1d2779a 100644 --- a/examples/example_sim_cartpole.py +++ b/examples/example_sim_cartpole.py @@ -28,6 +28,8 @@ class Example: def __init__(self, stage=None, num_envs=1, enable_rendering=True, print_timers=True): + self.device = wp.get_device() + builder = wp.sim.ModelBuilder() self.num_envs = num_envs @@ -98,9 +100,11 @@ def __init__(self, stage=None, num_envs=1, enable_rendering=True, print_timers=T if self.use_graph: # create update graph - wp.capture_begin() - self.update() - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.update() + finally: + self.graph = wp.capture_end(self.device) def update(self): with wp.ScopedTimer("simulate", active=True, print=self.print_timers): diff --git a/examples/example_sim_cloth.py b/examples/example_sim_cloth.py index 5ec7dfcf7..40b5982e3 100644 --- a/examples/example_sim_cloth.py +++ b/examples/example_sim_cloth.py @@ -37,19 +37,10 @@ def __str__(self): class Example: - def __init__(self, stage): - self.parser = argparse.ArgumentParser() - self.parser.add_argument( - "--integrator", - help="Type of integrator", - type=IntegratorType, - choices=list(IntegratorType), - default=IntegratorType.EULER, - ) - - args = self.parser.parse_args() + def __init__(self, stage, integrator=IntegratorType.EULER): + self.device = wp.get_device() - self.integrator_type = args.integrator + self.integrator_type = integrator self.sim_width = 64 self.sim_height = 32 @@ -135,9 +126,11 @@ def __init__(self, stage): if self.sim_use_graph: # create update graph - wp.capture_begin() - self.update() - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.update() + finally: + self.graph = wp.capture_end(self.device) def update(self): with wp.ScopedTimer("simulate", dict=self.profiler): @@ -168,9 +161,20 @@ def render(self, is_live=False): if __name__ == "__main__": + parser = argparse.ArgumentParser() + parser.add_argument( + "--integrator", + help="Type of integrator", + type=IntegratorType, + choices=list(IntegratorType), + default=IntegratorType.EULER, + ) + + args = parser.parse_args() + stage_path = os.path.join(os.path.dirname(__file__), "outputs/example_sim_cloth.usd") - example = Example(stage_path) + example = Example(stage_path, integrator=args.integrator) for i in range(example.sim_frames): example.update() diff --git a/examples/example_sim_grad_bounce.py b/examples/example_sim_grad_bounce.py index 526f86742..833f7b6da 100644 --- a/examples/example_sim_grad_bounce.py +++ b/examples/example_sim_grad_bounce.py @@ -45,6 +45,7 @@ def step_kernel(x: wp.array(dtype=wp.vec3), grad: wp.array(dtype=wp.vec3), alpha class Example: def __init__(self, stage=None, enable_rendering=True, profile=False, adapter=None, verbose=False): + self.device = wp.get_device() self.verbose = verbose # seconds @@ -106,12 +107,14 @@ def __init__(self, stage=None, enable_rendering=True, profile=False, adapter=Non self.renderer = wp.sim.render.SimRenderer(self.model, stage, scaling=1.0) # capture forward/backward passes - wp.capture_begin() - self.tape = wp.Tape() - with self.tape: - self.compute_loss() - self.tape.backward(self.loss) - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.tape = wp.Tape() + with self.tape: + self.compute_loss() + self.tape.backward(self.loss) + finally: + self.graph = wp.capture_end(self.device) def compute_loss(self): # run control loop diff --git a/examples/example_sim_grad_cloth.py b/examples/example_sim_grad_cloth.py index d0afb6905..694461c0a 100644 --- a/examples/example_sim_grad_cloth.py +++ b/examples/example_sim_grad_cloth.py @@ -53,6 +53,7 @@ def step_kernel(x: wp.array(dtype=wp.vec3), grad: wp.array(dtype=wp.vec3), alpha class Example: def __init__(self, stage, profile=False, adapter=None, verbose=False): + self.device = wp.get_device() self.verbose = verbose # seconds @@ -115,12 +116,14 @@ def __init__(self, stage, profile=False, adapter=None, verbose=False): self.renderer = wp.sim.render.SimRenderer(self.model, stage, scaling=4.0) # capture forward/backward passes - wp.capture_begin() - self.tape = wp.Tape() - with self.tape: - self.compute_loss() - self.tape.backward(self.loss) - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.tape = wp.Tape() + with self.tape: + self.compute_loss() + self.tape.backward(self.loss) + finally: + self.graph = wp.capture_end(self.device) def compute_loss(self): # run control loop diff --git a/examples/example_sim_quadruped.py b/examples/example_sim_quadruped.py index f0413f40b..9fea24476 100644 --- a/examples/example_sim_quadruped.py +++ b/examples/example_sim_quadruped.py @@ -70,6 +70,7 @@ def compute_env_offsets(num_envs, env_offset=(5.0, 0.0, 5.0), up_axis="Y"): class Example: def __init__(self, stage=None, num_envs=1, enable_rendering=True, print_timers=True): + self.device = wp.get_device() self.num_envs = num_envs articulation_builder = wp.sim.ModelBuilder() wp.sim.parse_urdf( @@ -135,9 +136,11 @@ def __init__(self, stage=None, num_envs=1, enable_rendering=True, print_timers=T if self.use_graph: # create update graph - wp.capture_begin() - self.update() - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.update() + finally: + self.graph = wp.capture_end(self.device) def update(self): with wp.ScopedTimer("simulate", active=True, print=self.print_timers): diff --git a/examples/example_sim_rigid_chain.py b/examples/example_sim_rigid_chain.py index 4309536ca..fd33ec03e 100644 --- a/examples/example_sim_rigid_chain.py +++ b/examples/example_sim_rigid_chain.py @@ -27,6 +27,7 @@ class Example: def __init__(self, stage): + self.device = wp.get_device() self.chain_length = 8 self.chain_width = 1.0 self.chain_types = [ @@ -146,9 +147,11 @@ def __init__(self, stage): if self.use_graph: # create update graph - wp.capture_begin() - self.update() - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.update() + finally: + self.graph = wp.capture_end(self.device) def update(self): with wp.ScopedTimer("simulate", active=True): diff --git a/examples/example_sim_rigid_contact.py b/examples/example_sim_rigid_contact.py index 53450ce12..d3c84917e 100644 --- a/examples/example_sim_rigid_contact.py +++ b/examples/example_sim_rigid_contact.py @@ -28,6 +28,7 @@ class Example: def __init__(self, stage): + self.device = wp.get_device() builder = wp.sim.ModelBuilder() self.sim_time = 0.0 @@ -126,9 +127,11 @@ def __init__(self, stage): if self.use_graph: # create update graph - wp.capture_begin() - self.update() - self.graph = wp.capture_end() + wp.capture_begin(self.device) + try: + self.update() + finally: + self.graph = wp.capture_end(self.device) def load_mesh(self, filename, path): asset_stage = Usd.Stage.Open(filename) diff --git a/examples/example_sim_trajopt.py b/examples/example_sim_trajopt.py index 279fb5f32..d5f832a37 100644 --- a/examples/example_sim_trajopt.py +++ b/examples/example_sim_trajopt.py @@ -16,7 +16,6 @@ import os -import matplotlib.pyplot as plt import numpy as np import warp as wp @@ -194,6 +193,8 @@ def render(self): if __name__ == "__main__": + import matplotlib.pyplot as plt + stage_path = os.path.join(os.path.dirname(__file__), "outputs/example_sim_trajopt.usd") example = Example(stage_path, device=wp.get_preferred_device(), verbose=True) diff --git a/examples/fem/example_diffusion_mgpu.py b/examples/fem/example_diffusion_mgpu.py index 32b6b9fad..5b672d433 100644 --- a/examples/fem/example_diffusion_mgpu.py +++ b/examples/fem/example_diffusion_mgpu.py @@ -6,19 +6,18 @@ import warp as wp import warp.fem as fem - from warp.sparse import bsr_axpy, bsr_mv from warp.utils import array_cast # Import example utilities # Make sure that works both when imported as module and run as standalone file try: - from .example_diffusion import linear_form, diffusion_form from .bsr_utils import bsr_cg + from .example_diffusion import diffusion_form, linear_form from .plot_utils import Plot except ImportError: - from example_diffusion import linear_form, diffusion_form from bsr_utils import bsr_cg + from example_diffusion import diffusion_form, linear_form from plot_utils import Plot @@ -100,14 +99,18 @@ def __init__(self, stage=None, quiet=False): self._quiet = quiet self._geo = fem.Grid2D(res=wp.vec2i(25)) - self._scalar_space = fem.make_polynomial_space(self._geo, degree=3) - self._scalar_field = self._scalar_space.make_field() + + self._main_device = wp.get_device("cuda") + + with wp.ScopedDevice(self._main_device): + self._scalar_space = fem.make_polynomial_space(self._geo, degree=3) + self._scalar_field = self._scalar_space.make_field() self.renderer = Plot(stage) def update(self): devices = wp.get_cuda_devices() - main_device = devices[0] + main_device = self._main_device rhs_vecs = [] res_vecs = [] @@ -141,16 +144,15 @@ def update(self): A.tmp_buf = tmp A.rank_data = (matrices, rhs_vecs, res_vecs, indices) - with wp.ScopedDevice(main_device): - bsr_cg( - A, - x=global_res, - b=glob_rhs, - use_diag_precond=False, - quiet=self._quiet, - mv_routine=mv_routine, - device=main_device, - ) + bsr_cg( + A, + x=global_res, + b=glob_rhs, + use_diag_precond=False, + quiet=self._quiet, + mv_routine=mv_routine, + device=main_device, + ) array_cast(in_array=global_res, out_array=self._scalar_field.dof_values) diff --git a/exts/omni.warp.core/omni/warp/core/tests/test_ext.py b/exts/omni.warp.core/omni/warp/core/tests/test_ext.py index 189d62c4f..46fb22efb 100644 --- a/exts/omni.warp.core/omni/warp/core/tests/test_ext.py +++ b/exts/omni.warp.core/omni/warp/core/tests/test_ext.py @@ -5,117 +5,73 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -"""Tests for the Warp library itself. +"""Tests for the Warp core library in Kit. Only a trimmed down list of tests is run since the full suite is too slow. + +More information about testing in Kit: + https://docs.omniverse.nvidia.com/kit/docs/kit-manual/latest/guide/testing_exts_python.html """ -import omni.kit +import importlib -import warp as wp -import warp.tests.test_array -import warp.tests.test_array_reduce -import warp.tests.test_bvh -import warp.tests.test_codegen -import warp.tests.test_compile_consts -import warp.tests.test_conditional -import warp.tests.test_ctypes -import warp.tests.test_devices -import warp.tests.test_dlpack -import warp.tests.test_fabricarray -import warp.tests.test_func -import warp.tests.test_generics -import warp.tests.test_grad_customs -import warp.tests.test_hash_grid -import warp.tests.test_indexedarray -import warp.tests.test_launch -import warp.tests.test_marching_cubes -import warp.tests.test_mat_lite -import warp.tests.test_math -import warp.tests.test_matmul_lite -import warp.tests.test_mesh -import warp.tests.test_mesh_query_aabb -import warp.tests.test_mesh_query_point -import warp.tests.test_mesh_query_ray -import warp.tests.test_modules_lite -import warp.tests.test_noise -import warp.tests.test_operators -import warp.tests.test_quat -import warp.tests.test_rand -import warp.tests.test_reload -import warp.tests.test_rounding -import warp.tests.test_runlength_encode -import warp.tests.test_sparse -import warp.tests.test_streams -import warp.tests.test_tape -import warp.tests.test_transient_module -import warp.tests.test_types -import warp.tests.test_utils -import warp.tests.test_vec_lite -import warp.tests.test_volume -import warp.tests.test_volume_write +import omni.kit.test -initialized = False +TEST_DESCS = ( + ("test_array", "TestArray"), + ("test_array_reduce", "TestArrayReduce"), + ("test_bvh", "TestBvh"), + ("test_codegen", "TestCodeGen"), + ("test_compile_consts", "TestConstants"), + ("test_conditional", "TestConditional"), + ("test_ctypes", "TestCTypes"), + ("test_devices", "TestDevices"), + ("test_dlpack", "TestDLPack"), + ("test_fabricarray", "TestFabricArray"), + ("test_func", "TestFunc"), + ("test_generics", "TestGenerics"), + ("test_grad_customs", "TestGradCustoms"), + ("test_hash_grid", "TestHashGrid"), + ("test_indexedarray", "TestIndexedArray"), + ("test_launch", "TestLaunch"), + ("test_marching_cubes", "TestMarchingCubes"), + ("test_mat_lite", "TestMatLite"), + ("test_math", "TestMath"), + ("test_matmul_lite", "TestMatmulLite"), + ("test_mesh", "TestMesh"), + ("test_mesh_query_aabb", "TestMeshQueryAABBMethods"), + ("test_mesh_query_point", "TestMeshQueryPoint"), + ("test_mesh_query_ray", "TestMeshQueryRay"), + ("test_modules_lite", "TestModuleLite"), + ("test_noise", "TestNoise"), + ("test_operators", "TestOperators"), + ("test_quat", "TestQuat"), + ("test_rand", "TestRand"), + ("test_reload", "TestReload"), + ("test_rounding", "TestRounding"), + ("test_runlength_encode", "TestRunlengthEncode"), + ("test_sparse", "TestSparse"), + ("test_streams", "TestStreams"), + ("test_tape", "TestTape"), + ("test_transient_module", "TestTransientModule"), + ("test_types", "TestTypes"), + ("test_utils", "TestUtils"), + ("test_vec_lite", "TestVecLite"), + ("test_volume", "TestVolume"), + ("test_volume_write", "TestVolumeWrite"), +) -class BaseTestCase(omni.kit.test.AsyncTestCase): - @classmethod - def setUpClass(cls): - global initialized +test_clss = [] +for module_name, cls_name in TEST_DESCS: + module = importlib.import_module(f"warp.tests.{module_name}") + cls = getattr(module, cls_name) - if not initialized: - # Load all the Warp modules just once. This needs to be done - # within the `setUpClass` method instead of at the module level - # to avoid the reload to be done as soon as this module is imported, - # which might happen when scanning for existing tests without - # actually needing to run these ones. - wp.force_load() - initialized = True + # Change the base class from unittest.TestCase + cls.__bases__ = (omni.kit.test.AsyncTestCase,) + test_clss.append(cls) -test_clss = ( - warp.tests.test_array.register(BaseTestCase), - warp.tests.test_array_reduce.register(BaseTestCase), - warp.tests.test_bvh.register(BaseTestCase), - warp.tests.test_codegen.register(BaseTestCase), - warp.tests.test_compile_consts.register(BaseTestCase), - warp.tests.test_conditional.register(BaseTestCase), - warp.tests.test_ctypes.register(BaseTestCase), - warp.tests.test_devices.register(BaseTestCase), - warp.tests.test_dlpack.register(BaseTestCase), - warp.tests.test_fabricarray.register(BaseTestCase), - warp.tests.test_func.register(BaseTestCase), - warp.tests.test_generics.register(BaseTestCase), - warp.tests.test_grad_customs.register(BaseTestCase), - warp.tests.test_hash_grid.register(BaseTestCase), - warp.tests.test_indexedarray.register(BaseTestCase), - warp.tests.test_launch.register(BaseTestCase), - warp.tests.test_marching_cubes.register(BaseTestCase), - warp.tests.test_mat_lite.register(BaseTestCase), - warp.tests.test_math.register(BaseTestCase), - warp.tests.test_matmul_lite.register(BaseTestCase), - warp.tests.test_mesh.register(BaseTestCase), - warp.tests.test_mesh_query_aabb.register(BaseTestCase), - warp.tests.test_mesh_query_point.register(BaseTestCase), - warp.tests.test_mesh_query_ray.register(BaseTestCase), - warp.tests.test_modules_lite.register(BaseTestCase), - warp.tests.test_noise.register(BaseTestCase), - warp.tests.test_operators.register(BaseTestCase), - warp.tests.test_quat.register(BaseTestCase), - warp.tests.test_rand.register(BaseTestCase), - warp.tests.test_reload.register(BaseTestCase), - warp.tests.test_rounding.register(BaseTestCase), - warp.tests.test_runlength_encode.register(BaseTestCase), - warp.tests.test_sparse.register(BaseTestCase), - warp.tests.test_streams.register(BaseTestCase), - warp.tests.test_tape.register(BaseTestCase), - warp.tests.test_transient_module.register(BaseTestCase), - warp.tests.test_types.register(BaseTestCase), - warp.tests.test_utils.register(BaseTestCase), - warp.tests.test_vec_lite.register(BaseTestCase), - warp.tests.test_volume_write.register(BaseTestCase), - warp.tests.test_volume.register(BaseTestCase) -) # Each test class needs to be defined at the module level to be found by # the test runners. diff --git a/pyproject.toml b/pyproject.toml index 6190136f0..ae3994153 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -30,7 +30,7 @@ Documentation = "https://nvidia.github.io/warp" Changelog = "https://github.com/NVIDIA/warp/blob/main/CHANGELOG.md" [project.optional-dependencies] -dev = ["flake8", "black", "isort", "nvtx", "furo", "sphinx-copybutton"] +dev = ["flake8", "black", "isort", "nvtx", "furo", "sphinx-copybutton", "coverage[toml]"] [tool.setuptools.packages] find = {} @@ -45,3 +45,11 @@ line-length = 120 [tool.isort] profile = "black" skip_gitignore = true + +[tool.coverage.run] +source = ["warp", "warp.sim", "warp.render"] +disable_warnings = ["module-not-measured", "module-not-imported", "no-data-collected", "couldnt-parse"] + +[tool.coverage.report] +exclude_lines = ["pragma: no cover", "@wp", "@warp", "if 0:", "if __name__ == .__main__.:"] +omit =["*/warp/tests/*", "*/warp/fem/*", "appdirs.py", "render_opengl.py", "build_dll.py", "config.py", "stubs.py"] diff --git a/tools/ci/testing/test-linux-aarch64/test.sh b/tools/ci/testing/test-linux-aarch64/test.sh index 44da31bd3..c87575574 100755 --- a/tools/ci/testing/test-linux-aarch64/test.sh +++ b/tools/ci/testing/test-linux-aarch64/test.sh @@ -16,4 +16,4 @@ echo "Installing Warp to Python" $PYTHON -m pip install -e "$SCRIPT_DIR/../../../../." echo "Running tests" -$PYTHON "$SCRIPT_DIR/../../../../warp/tests/test_all.py" +$PYTHON -m warp.tests diff --git a/tools/ci/testing/test-linux-x86_64/test.sh b/tools/ci/testing/test-linux-x86_64/test.sh index c6c9755f8..4ac6c9314 100755 --- a/tools/ci/testing/test-linux-x86_64/test.sh +++ b/tools/ci/testing/test-linux-x86_64/test.sh @@ -5,15 +5,32 @@ SCRIPT_DIR=$(dirname ${BASH_SOURCE}) "$SCRIPT_DIR/../../../../repo.sh" build --fetch-only $@ PYTHON="$SCRIPT_DIR/../../../../_build/target-deps/python/python" +CUDA_BIN="$SCRIPT_DIR/../../../../_build/target-deps/cuda/bin" + +# Make sure ptxas can be run by JAX +export PATH="$CUDA_BIN:$PATH" echo "Installing test dependencies" + +if [ -n "$TEAMCITY_VERSION" ]; then + echo "##teamcity[blockOpened name='Installing test dependencies']" +fi + +$PYTHON -m pip install --upgrade pip $PYTHON -m pip install matplotlib $PYTHON -m pip install usd-core -$PYTHON -m pip install torch --extra-index-url https://download.pytorch.org/whl/cu113 -$PYTHON -m pip install "jax[cuda]" -f https://storage.googleapis.com/jax-releases/jax_cuda_releases.html +$PYTHON -m pip install coverage +if [[ "$OSTYPE" == "linux-gnu" ]]; then + $PYTHON -m pip install torch --extra-index-url https://download.pytorch.org/whl/cu115 + $PYTHON -m pip install --upgrade "jax[cuda]" -f https://storage.googleapis.com/jax-releases/jax_cuda_releases.html +fi + +if [ -n "$TEAMCITY_VERSION" ]; then + echo "##teamcity[blockClosed name='Installing test dependencies']" +fi echo "Installing Warp to Python" $PYTHON -m pip install -e "$SCRIPT_DIR/../../../../." echo "Running tests" -$PYTHON "$SCRIPT_DIR/../../../../warp/tests/test_all.py" +$PYTHON -m warp.tests diff --git a/tools/ci/testing/test-windows-x86_64/test.bat b/tools/ci/testing/test-windows-x86_64/test.bat index ba575a82f..6470f1d2a 100644 --- a/tools/ci/testing/test-windows-x86_64/test.bat +++ b/tools/ci/testing/test-windows-x86_64/test.bat @@ -6,7 +6,8 @@ SET PYTHON="%~dp0..\..\..\..\_build\target-deps\python\python.exe" echo "Installing test dependencies" call %PYTHON% -m pip install matplotlib call %PYTHON% -m pip install usd-core -call %PYTHON% -m pip install torch --extra-index-url https://download.pytorch.org/whl/cu113 +call %PYTHON% -m pip install coverage +call %PYTHON% -m pip install torch --extra-index-url https://download.pytorch.org/whl/cu115 :: According to Jax docs, the pip packages don't work on Windows and may fail silently ::call %PYTHON% -m pip install "jax[cuda]" -f https://storage.googleapis.com/jax-releases/jax_cuda_releases.html @@ -14,4 +15,4 @@ echo "Installing Warp to Python" call %PYTHON% -m pip install -e "%~dp0..\..\..\..\." echo "Running tests" -call %PYTHON% "%~dp0..\..\..\..\warp\tests\test_all.py" +call %PYTHON% -m warp.tests diff --git a/warp/config.py b/warp/config.py index 73bad3dd2..d231b0825 100644 --- a/warp/config.py +++ b/warp/config.py @@ -33,3 +33,5 @@ enable_backward = True # whether to compiler the backward passes of the kernels llvm_cuda = False # use Clang/LLVM instead of NVRTC to compile CUDA + +graph_capture_module_load_default = True # Default value of force_module_load for capture_begin() diff --git a/warp/context.py b/warp/context.py index d196b20f3..6c90780b1 100644 --- a/warp/context.py +++ b/warp/context.py @@ -3778,7 +3778,7 @@ def get_module_options(module: Optional[Any] = None) -> Dict[str, Any]: return get_module(m.__name__).options -def capture_begin(device: Devicelike = None, stream=None, force_module_load=True): +def capture_begin(device: Devicelike = None, stream=None, force_module_load=None): """Begin capture of a CUDA graph Captures all subsequent kernel launches and memory operations on CUDA devices. @@ -3792,6 +3792,9 @@ def capture_begin(device: Devicelike = None, stream=None, force_module_load=True """ + if force_module_load is None: + force_module_load = warp.config.graph_capture_module_load_default + if warp.config.verify_cuda is True: raise RuntimeError("Cannot use CUDA error verification during graph capture") diff --git a/warp/tests/__main__.py b/warp/tests/__main__.py index e331aff81..98f9af5ca 100644 --- a/warp/tests/__main__.py +++ b/warp/tests/__main__.py @@ -1,7 +1,4 @@ -from .test_all import run +from warp.thirdparty.unittest_parallel import main -ret = run() - -import sys - -sys.exit(ret) +if __name__ == "__main__": + main() diff --git a/warp/tests/test_class_kernel.py b/warp/tests/aux_test_class_kernel.py similarity index 54% rename from warp/tests/test_class_kernel.py rename to warp/tests/aux_test_class_kernel.py index 7b251a0e5..0b258fef3 100644 --- a/warp/tests/test_class_kernel.py +++ b/warp/tests/aux_test_class_kernel.py @@ -1,7 +1,15 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +"""Dummy class used in test_reload.py""" + import warp as wp -# dummy class used in test_reload.py class ClassKernelTest: def __init__(self, device): # 3x3 frames in the rest pose: diff --git a/warp/tests/test_compile_consts_dummy.py b/warp/tests/aux_test_compile_consts_dummy.py similarity index 100% rename from warp/tests/test_compile_consts_dummy.py rename to warp/tests/aux_test_compile_consts_dummy.py diff --git a/warp/tests/aux_test_conditional_unequal_types_kernels.py b/warp/tests/aux_test_conditional_unequal_types_kernels.py new file mode 100644 index 000000000..2a843e389 --- /dev/null +++ b/warp/tests/aux_test_conditional_unequal_types_kernels.py @@ -0,0 +1,21 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +"""This file defines a kernel that fails on codegen.py""" + +import warp as wp + + +@wp.kernel +def unequal_types_kernel(): + x = wp.int32(10) + y = 10 + z = True + + # Throws a TypeError + if x == y == z: + pass diff --git a/warp/tests/test_dependent.py b/warp/tests/aux_test_dependent.py similarity index 85% rename from warp/tests/test_dependent.py rename to warp/tests/aux_test_dependent.py index 2df0f05b4..ece37e95e 100644 --- a/warp/tests/test_dependent.py +++ b/warp/tests/aux_test_dependent.py @@ -5,10 +5,10 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# This file is used to test reloading module references. +"""This file is used to test reloading module references.""" import warp as wp -import warp.tests.test_reference as ref +import warp.tests.aux_test_reference as ref wp.init() diff --git a/warp/tests/test_reference.py b/warp/tests/aux_test_reference.py similarity index 72% rename from warp/tests/test_reference.py rename to warp/tests/aux_test_reference.py index 375183272..dbf0f358d 100644 --- a/warp/tests/test_reference.py +++ b/warp/tests/aux_test_reference.py @@ -1,7 +1,7 @@ # This file is used to test reloading module references. import warp as wp -import warp.tests.test_reference_reference as refref +import warp.tests.aux_test_reference_reference as refref wp.init() diff --git a/warp/tests/test_reference_reference.py b/warp/tests/aux_test_reference_reference.py similarity index 100% rename from warp/tests/test_reference_reference.py rename to warp/tests/aux_test_reference_reference.py diff --git a/warp/tests/test_square.py b/warp/tests/aux_test_square.py similarity index 100% rename from warp/tests/test_square.py rename to warp/tests/aux_test_square.py diff --git a/warp/tests/aux_test_unresolved_func.py b/warp/tests/aux_test_unresolved_func.py new file mode 100644 index 000000000..1b9e433f8 --- /dev/null +++ b/warp/tests/aux_test_unresolved_func.py @@ -0,0 +1,14 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +import warp as wp + + +@wp.kernel +def unresolved_func_kernel(): + # this should trigger an exception due to unresolved function + x = wp.missing_func(42) diff --git a/warp/tests/aux_test_unresolved_symbol.py b/warp/tests/aux_test_unresolved_symbol.py new file mode 100644 index 000000000..a81ce4bf5 --- /dev/null +++ b/warp/tests/aux_test_unresolved_symbol.py @@ -0,0 +1,14 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +import warp as wp + + +@wp.kernel +def unresolved_symbol_kernel(): + # this should trigger an exception due to unresolved symbol + x = missing_symbol diff --git a/warp/tests/test_kinematics.py b/warp/tests/disabled_kinematics.py similarity index 94% rename from warp/tests/test_kinematics.py rename to warp/tests/disabled_kinematics.py index 25894cf51..524395398 100644 --- a/warp/tests/test_kinematics.py +++ b/warp/tests/disabled_kinematics.py @@ -5,12 +5,12 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. +import math import unittest import warp as wp import warp.sim -import math -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -221,21 +221,19 @@ def test_fk_ik_complex_joint_mechanism(test, device): check_fk_ik(builder, device) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestGrad(parent): - pass +class TestKinematics(unittest.TestCase): + pass - add_function_test(TestGrad, "test_fk_ik_ant", test_fk_ik_ant, devices=devices) - add_function_test( - TestGrad, "test_fk_ik_complex_joint_mechanism", test_fk_ik_complex_joint_mechanism, devices=devices - ) - return TestGrad +add_function_test(TestKinematics, "test_fk_ik_ant", test_fk_ik_ant, devices=devices) +add_function_test( + TestKinematics, "test_fk_ik_complex_joint_mechanism", test_fk_ik_complex_joint_mechanism, devices=devices +) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/run_coverage_serial.py b/warp/tests/run_coverage_serial.py new file mode 100644 index 000000000..aa5f600ac --- /dev/null +++ b/warp/tests/run_coverage_serial.py @@ -0,0 +1,31 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +"""Serial code-coverage runner + +This script is used to generate code-coverage reports by running Warp tests. +It runs in serial so can take over an hour to finish. To generate a coverage +report in parallel, use the warp/thirdparty./unittest_parallel.py script +instead with the --coverage option, e.g. python -m warp.tests --coverage +""" + +import coverage + +cover = coverage.Coverage(config_file=True, messages=True) + +cover.start() + +with cover.collect(): + import unittest_serial # noqa: E402 + + unittest_serial.run_specified() + +cover.save() + +cover.report() + +cover.html_report(title="Warp Testing Code Coverage Report") diff --git a/warp/tests/test_adam.py b/warp/tests/test_adam.py index 0eb099a47..c104df306 100644 --- a/warp/tests/test_adam.py +++ b/warp/tests/test_adam.py @@ -5,16 +5,14 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path +import unittest + import numpy as np -import math import warp as wp -from warp.tests.test_base import * -import unittest - import warp.optim import warp.sim +from warp.tests.unittest_utils import * wp.init() @@ -142,20 +140,18 @@ def gradient_func(): test.assertLessEqual(v, tol) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestArray(parent): - pass +class TestAdam(unittest.TestCase): + pass - add_function_test(TestArray, "test_adam_solve_float", test_adam_solve_float, devices=devices) - add_function_test(TestArray, "test_adam_solve_vec3", test_adam_solve_vec3, devices=devices) - add_function_test(TestArray, "test_adam_solve_two_inputs", test_adam_solve_two_inputs, devices=devices) - return TestArray +add_function_test(TestAdam, "test_adam_solve_float", test_adam_solve_float, devices=devices) +add_function_test(TestAdam, "test_adam_solve_vec3", test_adam_solve_vec3, devices=devices) +add_function_test(TestAdam, "test_adam_solve_two_inputs", test_adam_solve_two_inputs, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_all.py b/warp/tests/test_all.py deleted file mode 100644 index 812aef902..000000000 --- a/warp/tests/test_all.py +++ /dev/null @@ -1,241 +0,0 @@ -# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. -# NVIDIA CORPORATION and its licensors retain all intellectual property -# and proprietary rights in and to this software, related documentation -# and any modifications thereto. Any use, reproduction, disclosure or -# distribution of this software and related documentation without an express -# license agreement from NVIDIA CORPORATION is strictly prohibited. - -import os -import unittest - -import warp as wp -import warp.tests.test_adam -import warp.tests.test_arithmetic -import warp.tests.test_array -import warp.tests.test_atomic -import warp.tests.test_bool -import warp.tests.test_builtins_resolution -import warp.tests.test_bvh -import warp.tests.test_closest_point_edge_edge -import warp.tests.test_codegen -import warp.tests.test_compile_consts -import warp.tests.test_conditional -import warp.tests.test_copy -import warp.tests.test_ctypes -import warp.tests.test_devices -import warp.tests.test_dlpack -import warp.tests.test_examples -import warp.tests.test_fabricarray -import warp.tests.test_fast_math -import warp.tests.test_fem -import warp.tests.test_fp16 -import warp.tests.test_func -import warp.tests.test_generics -import warp.tests.test_grad -import warp.tests.test_grad_customs -import warp.tests.test_hash_grid -import warp.tests.test_import -import warp.tests.test_indexedarray -import warp.tests.test_intersect -import warp.tests.test_large -import warp.tests.test_launch -import warp.tests.test_lerp -import warp.tests.test_lvalue -import warp.tests.test_mat -import warp.tests.test_math -import warp.tests.test_matmul -import warp.tests.test_mesh -import warp.tests.test_mesh_query_aabb -import warp.tests.test_mesh_query_point -import warp.tests.test_mesh_query_ray -import warp.tests.test_mlp -import warp.tests.test_model -import warp.tests.test_modules_lite -import warp.tests.test_multigpu -import warp.tests.test_noise -import warp.tests.test_operators -import warp.tests.test_options -import warp.tests.test_pinned -import warp.tests.test_print -import warp.tests.test_quat -import warp.tests.test_rand -import warp.tests.test_reload -import warp.tests.test_rounding -import warp.tests.test_smoothstep -import warp.tests.test_snippet -import warp.tests.test_sparse -import warp.tests.test_spatial -import warp.tests.test_streams -import warp.tests.test_struct -import warp.tests.test_tape -import warp.tests.test_torch -import warp.tests.test_transient_module -import warp.tests.test_vec -import warp.tests.test_volume -from warp.tests.test_base import get_test_devices - -# Uncomment to run the tests on all devices -# import warp.tests.test_base -# warp.tests.test_base.test_mode = "all" - - -def register_tests(parent): - tests = [] - - tests.append(warp.tests.test_codegen.register(parent)) - tests.append(warp.tests.test_mesh_query_aabb.register(parent)) - tests.append(warp.tests.test_mesh_query_point.register(parent)) - tests.append(warp.tests.test_mesh_query_ray.register(parent)) - tests.append(warp.tests.test_builtins_resolution.register(parent)) - tests.append(warp.tests.test_bvh.register(parent)) - tests.append(warp.tests.test_conditional.register(parent)) - tests.append(warp.tests.test_operators.register(parent)) - tests.append(warp.tests.test_rounding.register(parent)) - tests.append(warp.tests.test_hash_grid.register(parent)) - tests.append(warp.tests.test_ctypes.register(parent)) - tests.append(warp.tests.test_rand.register(parent)) - tests.append(warp.tests.test_noise.register(parent)) - tests.append(warp.tests.test_tape.register(parent)) - tests.append(warp.tests.test_compile_consts.register(parent)) - tests.append(warp.tests.test_volume.register(parent)) - tests.append(warp.tests.test_mlp.register(parent)) - tests.append(warp.tests.test_grad.register(parent)) - tests.append(warp.tests.test_grad_customs.register(parent)) - tests.append(warp.tests.test_intersect.register(parent)) - tests.append(warp.tests.test_array.register(parent)) - tests.append(warp.tests.test_launch.register(parent)) - tests.append(warp.tests.test_large.register(parent)) - tests.append(warp.tests.test_import.register(parent)) - tests.append(warp.tests.test_func.register(parent)) - tests.append(warp.tests.test_fp16.register(parent)) - tests.append(warp.tests.test_reload.register(parent)) - tests.append(warp.tests.test_struct.register(parent)) - tests.append(warp.tests.test_closest_point_edge_edge.register(parent)) - tests.append(warp.tests.test_multigpu.register(parent)) - tests.append(warp.tests.test_quat.register(parent)) - tests.append(warp.tests.test_atomic.register(parent)) - tests.append(warp.tests.test_adam.register(parent)) - tests.append(warp.tests.test_transient_module.register(parent)) - tests.append(warp.tests.test_lerp.register(parent)) - tests.append(warp.tests.test_smoothstep.register(parent)) - tests.append(warp.tests.test_model.register(parent)) - tests.append(warp.tests.test_fast_math.register(parent)) - tests.append(warp.tests.test_streams.register(parent)) - tests.append(warp.tests.test_torch.register(parent)) - tests.append(warp.tests.test_pinned.register(parent)) - tests.append(warp.tests.test_print.register(parent)) - tests.append(warp.tests.test_matmul.register(parent)) - tests.append(warp.tests.test_options.register(parent)) - tests.append(warp.tests.test_dlpack.register(parent)) - tests.append(warp.tests.test_vec.register(parent)) - tests.append(warp.tests.test_mat.register(parent)) - tests.append(warp.tests.test_arithmetic.register(parent)) - tests.append(warp.tests.test_spatial.register(parent)) - tests.append(warp.tests.test_sparse.register(parent)) - tests.append(warp.tests.test_math.register(parent)) - tests.append(warp.tests.test_generics.register(parent)) - tests.append(warp.tests.test_indexedarray.register(parent)) - tests.append(warp.tests.test_copy.register(parent)) - tests.append(warp.tests.test_mesh.register(parent)) - tests.append(warp.tests.test_fabricarray.register(parent)) - tests.append(warp.tests.test_bool.register(parent)) - tests.append(warp.tests.test_examples.register(parent)) # Needs to be before test_fem for now - tests.append(warp.tests.test_fem.register(parent)) - tests.append(warp.tests.test_lvalue.register(parent)) - tests.append(warp.tests.test_devices.register(parent)) - tests.append(warp.tests.test_modules_lite.register(parent)) - tests.append(warp.tests.test_snippet.register(parent)) - - return tests - - -class TeamCityTestResult(unittest.TextTestResult): - """This class will report each test result to TeamCity""" - - def __init__(self, stream, descriptions, verbosity): - super(TeamCityTestResult, self).__init__(stream, descriptions, verbosity) - - def addSuccess(self, test): - super(TeamCityTestResult, self).addSuccess(test) - self.reportSuccess(test) - - def addError(self, test, err): - super(TeamCityTestResult, self).addError(test, err) - self.reportFailure(test) - - def addFailure(self, test, err): - super(TeamCityTestResult, self).addFailure(test, err) - self.reportFailure(test) - - def addSkip(self, test, reason): - super(TeamCityTestResult, self).addSkip(test, reason) - - def addExpectedFailure(self, test, err): - super(TeamCityTestResult, self).addExpectedFailure(test, err) - self.reportSuccess(test) - - def addUnexpectedSuccess(self, test): - super(TeamCityTestResult, self).addUnexpectedSuccess(test) - self.reportFailure(test) - - def reportSuccess(self, test): - test_id = test.id() - print(f"##teamcity[testStarted name='{test_id}']") - print(f"##teamcity[testFinished name='{test_id}']") - - def reportFailure(self, test): - test_id = test.id() - print(f"##teamcity[testStarted name='{test_id}']") - print(f"##teamcity[testFailed name='{test_id}']") - print(f"##teamcity[testFinished name='{test_id}']") - - -class TeamCityTestRunner(unittest.TextTestRunner): - """Test runner that will report test results to TeamCity if running in TeamCity""" - - def __init__(self, **kwargs): - self.running_in_teamcity = os.environ.get("TEAMCITY_VERSION") is not None - if self.running_in_teamcity: - kwargs["resultclass"] = TeamCityTestResult - super(TeamCityTestRunner, self).__init__(**kwargs) - - def run(self, test, name): - if self.running_in_teamcity: - print(f"##teamcity[testSuiteStarted name='{name}']") - - result = super(TeamCityTestRunner, self).run(test) - - if self.running_in_teamcity: - print(f"##teamcity[testSuiteFinished name='{name}']") - if not result.wasSuccessful(): - print("##teamcity[buildStatus status='FAILURE']") - - return result - - -def run(): - test_suite = unittest.TestSuite() - - tests = register_tests(unittest.TestCase) - - for test in tests: - test_suite.addTest(unittest.defaultTestLoader.loadTestsFromTestCase(test)) - - # force rebuild of all kernels - wp.build.clear_kernel_cache() - - # load all modules - for device in get_test_devices(): - wp.force_load(device) - - runner = TeamCityTestRunner(verbosity=2, failfast=False) - ret = not runner.run(test_suite, "WarpTests").wasSuccessful() - return ret - - -if __name__ == "__main__": - ret = run() - - import sys - - sys.exit(ret) diff --git a/warp/tests/test_arithmetic.py b/warp/tests/test_arithmetic.py index e9b24a326..790219853 100644 --- a/warp/tests/test_arithmetic.py +++ b/warp/tests/test_arithmetic.py @@ -8,8 +8,9 @@ import unittest import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -1040,52 +1041,50 @@ def check_clamp( tape.zero() -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestArithmetic(parent): - pass - # these unary ops only make sense for signed values: - for dtype in np_signed_int_types + np_float_types: - add_function_test_register_kernel( - TestArithmetic, f"test_unary_ops_{dtype.__name__}", test_unary_ops, devices=devices, dtype=dtype - ) +class TestArithmetic(unittest.TestCase): + pass - for dtype in np_float_types: - add_function_test_register_kernel( - TestArithmetic, f"test_special_funcs_{dtype.__name__}", test_special_funcs, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestArithmetic, - f"test_special_funcs_2arg_{dtype.__name__}", - test_special_funcs_2arg, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestArithmetic, f"test_interp_{dtype.__name__}", test_interp, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestArithmetic, f"test_float_to_int_{dtype.__name__}", test_float_to_int, devices=devices, dtype=dtype - ) - for dtype in np_scalar_types: - add_function_test_register_kernel( - TestArithmetic, f"test_clamp_{dtype.__name__}", test_clamp, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestArithmetic, f"test_nonzero_{dtype.__name__}", test_nonzero, devices=devices, dtype=dtype - ) - add_function_test(TestArithmetic, f"test_arrays_{dtype.__name__}", test_arrays, devices=devices, dtype=dtype) - add_function_test_register_kernel( - TestArithmetic, f"test_binary_ops_{dtype.__name__}", test_binary_ops, devices=devices, dtype=dtype - ) +# these unary ops only make sense for signed values: +for dtype in np_signed_int_types + np_float_types: + add_function_test_register_kernel( + TestArithmetic, f"test_unary_ops_{dtype.__name__}", test_unary_ops, devices=devices, dtype=dtype + ) - return TestArithmetic +for dtype in np_float_types: + add_function_test_register_kernel( + TestArithmetic, f"test_special_funcs_{dtype.__name__}", test_special_funcs, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestArithmetic, + f"test_special_funcs_2arg_{dtype.__name__}", + test_special_funcs_2arg, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestArithmetic, f"test_interp_{dtype.__name__}", test_interp, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestArithmetic, f"test_float_to_int_{dtype.__name__}", test_float_to_int, devices=devices, dtype=dtype + ) + +for dtype in np_scalar_types: + add_function_test_register_kernel( + TestArithmetic, f"test_clamp_{dtype.__name__}", test_clamp, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestArithmetic, f"test_nonzero_{dtype.__name__}", test_nonzero, devices=devices, dtype=dtype + ) + add_function_test(TestArithmetic, f"test_arrays_{dtype.__name__}", test_arrays, devices=devices, dtype=dtype) + add_function_test_register_kernel( + TestArithmetic, f"test_binary_ops_{dtype.__name__}", test_binary_ops, devices=devices, dtype=dtype + ) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_array.py b/warp/tests/test_array.py index dd923e324..9085ae282 100644 --- a/warp/tests/test_array.py +++ b/warp/tests/test_array.py @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -2085,55 +2085,53 @@ def test_array_from_numpy(test, device): assert_np_equal(result.numpy(), expected.numpy()) -def register(parent): - devices = get_test_devices() - - class TestArray(parent): - pass - - add_function_test(TestArray, "test_shape", test_shape, devices=devices) - add_function_test(TestArray, "test_flatten", test_flatten, devices=devices) - add_function_test(TestArray, "test_reshape", test_reshape, devices=devices) - add_function_test(TestArray, "test_slicing", test_slicing, devices=devices) - add_function_test(TestArray, "test_transpose", test_transpose, devices=devices) - add_function_test(TestArray, "test_view", test_view, devices=devices) - - add_function_test(TestArray, "test_1d_array", test_1d, devices=devices) - add_function_test(TestArray, "test_2d_array", test_2d, devices=devices) - add_function_test(TestArray, "test_3d_array", test_3d, devices=devices) - add_function_test(TestArray, "test_4d_array", test_4d, devices=devices) - add_function_test(TestArray, "test_4d_array_transposed", test_4d_transposed, devices=devices) - - add_function_test(TestArray, "test_fill_scalar", test_fill_scalar, devices=devices) - add_function_test(TestArray, "test_fill_vector", test_fill_vector, devices=devices) - add_function_test(TestArray, "test_fill_matrix", test_fill_matrix, devices=devices) - add_function_test(TestArray, "test_fill_struct", test_fill_struct, devices=devices) - add_function_test(TestArray, "test_fill_slices", test_fill_slices, devices=devices) - add_function_test(TestArray, "test_full_scalar", test_full_scalar, devices=devices) - add_function_test(TestArray, "test_full_vector", test_full_vector, devices=devices) - add_function_test(TestArray, "test_full_matrix", test_full_matrix, devices=devices) - add_function_test(TestArray, "test_full_struct", test_full_struct, devices=devices) - add_function_test(TestArray, "test_empty_array", test_empty_array, devices=devices) - add_function_test(TestArray, "test_empty_from_numpy", test_empty_from_numpy, devices=devices) - add_function_test(TestArray, "test_empty_from_list", test_empty_from_list, devices=devices) - add_function_test(TestArray, "test_to_list_scalar", test_to_list_scalar, devices=devices) - add_function_test(TestArray, "test_to_list_vector", test_to_list_vector, devices=devices) - add_function_test(TestArray, "test_to_list_matrix", test_to_list_matrix, devices=devices) - add_function_test(TestArray, "test_to_list_struct", test_to_list_struct, devices=devices) - - add_function_test(TestArray, "test_lower_bound", test_lower_bound, devices=devices) - add_function_test(TestArray, "test_round_trip", test_round_trip, devices=devices) - add_function_test(TestArray, "test_array_to_bool", test_array_to_bool, devices=devices) - add_function_test(TestArray, "test_array_of_structs", test_array_of_structs, devices=devices) - add_function_test(TestArray, "test_array_of_structs_grad", test_array_of_structs_grad, devices=devices) - add_function_test(TestArray, "test_array_of_structs_from_numpy", test_array_of_structs_from_numpy, devices=devices) - add_function_test(TestArray, "test_array_of_structs_roundtrip", test_array_of_structs_roundtrip, devices=devices) - add_function_test(TestArray, "test_array_from_numpy", test_array_from_numpy, devices=devices) - - return TestArray +devices = get_test_devices() + + +class TestArray(unittest.TestCase): + pass + + +add_function_test(TestArray, "test_shape", test_shape, devices=devices) +add_function_test(TestArray, "test_flatten", test_flatten, devices=devices) +add_function_test(TestArray, "test_reshape", test_reshape, devices=devices) +add_function_test(TestArray, "test_slicing", test_slicing, devices=devices) +add_function_test(TestArray, "test_transpose", test_transpose, devices=devices) +add_function_test(TestArray, "test_view", test_view, devices=devices) + +add_function_test(TestArray, "test_1d_array", test_1d, devices=devices) +add_function_test(TestArray, "test_2d_array", test_2d, devices=devices) +add_function_test(TestArray, "test_3d_array", test_3d, devices=devices) +add_function_test(TestArray, "test_4d_array", test_4d, devices=devices) +add_function_test(TestArray, "test_4d_array_transposed", test_4d_transposed, devices=devices) + +add_function_test(TestArray, "test_fill_scalar", test_fill_scalar, devices=devices) +add_function_test(TestArray, "test_fill_vector", test_fill_vector, devices=devices) +add_function_test(TestArray, "test_fill_matrix", test_fill_matrix, devices=devices) +add_function_test(TestArray, "test_fill_struct", test_fill_struct, devices=devices) +add_function_test(TestArray, "test_fill_slices", test_fill_slices, devices=devices) +add_function_test(TestArray, "test_full_scalar", test_full_scalar, devices=devices) +add_function_test(TestArray, "test_full_vector", test_full_vector, devices=devices) +add_function_test(TestArray, "test_full_matrix", test_full_matrix, devices=devices) +add_function_test(TestArray, "test_full_struct", test_full_struct, devices=devices) +add_function_test(TestArray, "test_empty_array", test_empty_array, devices=devices) +add_function_test(TestArray, "test_empty_from_numpy", test_empty_from_numpy, devices=devices) +add_function_test(TestArray, "test_empty_from_list", test_empty_from_list, devices=devices) +add_function_test(TestArray, "test_to_list_scalar", test_to_list_scalar, devices=devices) +add_function_test(TestArray, "test_to_list_vector", test_to_list_vector, devices=devices) +add_function_test(TestArray, "test_to_list_matrix", test_to_list_matrix, devices=devices) +add_function_test(TestArray, "test_to_list_struct", test_to_list_struct, devices=devices) + +add_function_test(TestArray, "test_lower_bound", test_lower_bound, devices=devices) +add_function_test(TestArray, "test_round_trip", test_round_trip, devices=devices) +add_function_test(TestArray, "test_array_to_bool", test_array_to_bool, devices=devices) +add_function_test(TestArray, "test_array_of_structs", test_array_of_structs, devices=devices) +add_function_test(TestArray, "test_array_of_structs_grad", test_array_of_structs_grad, devices=devices) +add_function_test(TestArray, "test_array_of_structs_from_numpy", test_array_of_structs_from_numpy, devices=devices) +add_function_test(TestArray, "test_array_of_structs_roundtrip", test_array_of_structs_roundtrip, devices=devices) +add_function_test(TestArray, "test_array_from_numpy", test_array_from_numpy, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_array_reduce.py b/warp/tests/test_array_reduce.py index 73f70dcc3..a299ddf80 100644 --- a/warp/tests/test_array_reduce.py +++ b/warp/tests/test_array_reduce.py @@ -1,9 +1,17 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest + import numpy as np -import warp as wp -from warp.utils import array_sum, array_inner -from warp.tests.test_base import * +import warp as wp +from warp.tests.unittest_utils import * +from warp.utils import array_inner, array_sum wp.init() @@ -118,27 +126,25 @@ def test_array_inner_empty(test, device): assert_np_equal(array_inner(values, values, axis=0).numpy(), np.zeros(3)) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestArraySym(parent): - pass +class TestArrayReduce(unittest.TestCase): + pass - add_function_test(TestArraySym, "test_array_sum_double", make_test_array_sum(wp.float64), devices=devices) - add_function_test(TestArraySym, "test_array_sum_vec3", make_test_array_sum(wp.vec3), devices=devices) - add_function_test(TestArraySym, "test_array_sum_axis_float", make_test_array_sum_axis(wp.float32), devices=devices) - add_function_test(TestArraySym, "test_array_sum_empty", test_array_sum_empty, devices=devices) - add_function_test(TestArraySym, "test_array_inner_double", make_test_array_inner(wp.float64), devices=devices) - add_function_test(TestArraySym, "test_array_inner_vec3", make_test_array_inner(wp.vec3), devices=devices) - add_function_test( - TestArraySym, "test_array_inner_axis_float", make_test_array_inner_axis(wp.float32), devices=devices - ) - add_function_test(TestArraySym, "test_array_inner_empty", test_array_inner_empty, devices=devices) - return TestArraySym +add_function_test(TestArrayReduce, "test_array_sum_double", make_test_array_sum(wp.float64), devices=devices) +add_function_test(TestArrayReduce, "test_array_sum_vec3", make_test_array_sum(wp.vec3), devices=devices) +add_function_test(TestArrayReduce, "test_array_sum_axis_float", make_test_array_sum_axis(wp.float32), devices=devices) +add_function_test(TestArrayReduce, "test_array_sum_empty", test_array_sum_empty, devices=devices) +add_function_test(TestArrayReduce, "test_array_inner_double", make_test_array_inner(wp.float64), devices=devices) +add_function_test(TestArrayReduce, "test_array_inner_vec3", make_test_array_inner(wp.vec3), devices=devices) +add_function_test( + TestArrayReduce, "test_array_inner_axis_float", make_test_array_inner_axis(wp.float32), devices=devices +) +add_function_test(TestArrayReduce, "test_array_inner_empty", test_array_inner_empty, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_atomic.py b/warp/tests/test_atomic.py index 5cba5f746..6a5faccdf 100644 --- a/warp/tests/test_atomic.py +++ b/warp/tests/test_atomic.py @@ -5,14 +5,12 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path +import unittest + import numpy as np -import math import warp as wp -from warp.tests.test_base import * - -import unittest +from warp.tests.unittest_utils import * wp.init() @@ -121,25 +119,23 @@ def test_atomic(test, device): test_atomic_mat44 = make_atomic_test(wp.mat44) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestAtomic(parent): - pass +class TestAtomic(unittest.TestCase): + pass - add_function_test(TestAtomic, "test_atomic_int", test_atomic_int, devices=devices) - add_function_test(TestAtomic, "test_atomic_float", test_atomic_float, devices=devices) - add_function_test(TestAtomic, "test_atomic_vec2", test_atomic_vec2, devices=devices) - add_function_test(TestAtomic, "test_atomic_vec3", test_atomic_vec3, devices=devices) - add_function_test(TestAtomic, "test_atomic_vec4", test_atomic_vec4, devices=devices) - add_function_test(TestAtomic, "test_atomic_mat22", test_atomic_mat22, devices=devices) - add_function_test(TestAtomic, "test_atomic_mat33", test_atomic_mat33, devices=devices) - add_function_test(TestAtomic, "test_atomic_mat44", test_atomic_mat44, devices=devices) - return TestAtomic +add_function_test(TestAtomic, "test_atomic_int", test_atomic_int, devices=devices) +add_function_test(TestAtomic, "test_atomic_float", test_atomic_float, devices=devices) +add_function_test(TestAtomic, "test_atomic_vec2", test_atomic_vec2, devices=devices) +add_function_test(TestAtomic, "test_atomic_vec3", test_atomic_vec3, devices=devices) +add_function_test(TestAtomic, "test_atomic_vec4", test_atomic_vec4, devices=devices) +add_function_test(TestAtomic, "test_atomic_mat22", test_atomic_mat22, devices=devices) +add_function_test(TestAtomic, "test_atomic_mat33", test_atomic_mat33, devices=devices) +add_function_test(TestAtomic, "test_atomic_mat44", test_atomic_mat44, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_bool.py b/warp/tests/test_bool.py index 94c4d1283..848bed5ad 100644 --- a/warp/tests/test_bool.py +++ b/warp/tests/test_bool.py @@ -1,9 +1,16 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -71,24 +78,22 @@ def check_compile_constant(result: wp.array(dtype=wp.bool)): def test_bool_constant(test, device): - compile_constant_value = wp.zeros(1, dtype=wp.bool) - wp.launch(check_compile_constant, 1, inputs=[compile_constant_value]) + compile_constant_value = wp.zeros(1, dtype=wp.bool, device=device) + wp.launch(check_compile_constant, 1, inputs=[compile_constant_value], device=device) test.assertTrue(compile_constant_value.numpy()[0]) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestBool(parent): - pass +class TestBool(unittest.TestCase): + pass - add_function_test(TestBool, "test_bool_identity_ops", test_bool_identity_ops, devices=devices) - add_function_test(TestBool, "test_bool_constant", test_bool_constant, devices=devices) - return TestBool +add_function_test(TestBool, "test_bool_identity_ops", test_bool_identity_ops, devices=devices) +add_function_test(TestBool, "test_bool_constant", test_bool_constant, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_builtins_resolution.py b/warp/tests/test_builtins_resolution.py index bfeb6fa2c..c40902521 100644 --- a/warp/tests/test_builtins_resolution.py +++ b/warp/tests/test_builtins_resolution.py @@ -10,8 +10,7 @@ import numpy as np -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() @@ -42,733 +41,6 @@ def wpm(dtype, dim, values): return tuple(wpv(dtype, values[i * dim : (i + 1) * dim]) for i in range(dim)) -def test_int_arg_overflow(test, device): - value = -1234567890123456789 - - test.assertEqual(wp.invert(wp.int8(value)), 20) - test.assertEqual(wp.invert(wp.int16(value)), -32492) - test.assertEqual(wp.invert(wp.int32(value)), 2112454932) - test.assertEqual(wp.invert(wp.int64(value)), 1234567890123456788) - - test.assertEqual(wp.invert(wp.uint8(value)), 20) - test.assertEqual(wp.invert(wp.uint16(value)), 33044) - test.assertEqual(wp.invert(wp.uint32(value)), 2112454932) - test.assertEqual(wp.invert(wp.uint64(value)), 1234567890123456788) - - test.assertEqual(wp.invert(value), wp.invert(wp.int32(value))) - - -def test_float_arg_precision(test, device): - value = 1.23 - expected = 0.94248880193169748409 - - result = wp.sin(wp.float64(value)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.sin(wp.float32(value)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.sin(wp.float16(value)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - test.assertEqual(wp.sin(value), wp.sin(wp.float32(value))) - - -def test_int_int_args_overflow(test, device): - value = -1234567890 - - test.assertEqual(wp.mul(wp.int8(value), wp.int8(value)), 68) - test.assertEqual(wp.mul(wp.int16(value), wp.int16(value)), -3004) - test.assertEqual(wp.mul(wp.int32(value), wp.int32(value)), 304084036) - test.assertEqual(wp.mul(wp.int64(value), wp.int64(value)), 1524157875019052100) - - test.assertEqual(wp.mul(wp.uint8(value), wp.uint8(value)), 68) - test.assertEqual(wp.mul(wp.uint16(value), wp.uint16(value)), 62532) - test.assertEqual(wp.mul(wp.uint32(value), wp.uint32(value)), 304084036) - test.assertEqual(wp.mul(wp.uint64(value), wp.uint64(value)), 1524157875019052100) - - test.assertEqual(wp.mul(value, value), wp.mul(wp.int32(value), wp.int32(value))) - - -def test_mat22_arg_precision(test, device): - values = (1.23, 2.34, 3.45, 4.56) - values_2d = (values[0:2], values[2:4]) - expected = 5.78999999999999914735 - - result = wp.trace(wp.mat22d(*values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.trace(wp.mat22f(*values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.trace(wp.mat22h(*values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.trace(values), wp.trace(wp.mat22f(*values))) - test.assertEqual(wp.trace(values_2d), wp.trace(wp.mat22f(*values))) - - -def test_mat33_arg_precision(test, device): - values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) - values_2d = (values[0:3], values[3:6], values[6:9]) - expected = 15.91000000000000014211 - - result = wp.trace(wp.mat33d(*values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.trace(wp.mat33f(*values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.trace(wp.mat33h(*values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.trace(values), wp.trace(wp.mat33f(*values))) - test.assertEqual(wp.trace(values_2d), wp.trace(wp.mat33f(*values))) - - -def test_mat44_arg_precision(test, device): - values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01, 10.12, 11.23, 12.34, 13.45, 14.56, 15.67, 16.78) - values_2d = (values[0:4], values[4:8], values[8:12], values[12:16]) - expected = 36.02000000000000312639 - - result = wp.trace(wp.mat44d(*values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.trace(wp.mat44f(*values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.trace(wp.mat44h(*values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.trace(values), wp.trace(wp.mat44f(*values))) - test.assertEqual(wp.trace(values_2d), wp.trace(wp.mat44f(*values))) - - -def test_mat22_mat22_args_precision(test, device): - a_values = (0.12, 1.23, 0.12, 1.23) - a_values_2d = (a_values[0:2], a_values[2:4]) - b_values = (1.23, 0.12, 1.23, 0.12) - b_values_2d = (b_values[0:2], b_values[2:4]) - expected = 0.59039999999999992486 - - result = wp.ddot(wp.mat22d(*a_values), wp.mat22d(*b_values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.ddot(wp.mat22h(*a_values), wp.mat22h(*b_values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) - test.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) - test.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) - test.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) - - -def test_mat33_mat33_args_precision(test, device): - a_values = (0.12, 1.23, 2.34, 0.12, 1.23, 2.34, 0.12, 1.23, 2.34) - a_values_2d = (a_values[0:3], a_values[3:6], a_values[6:9]) - b_values = (2.34, 1.23, 0.12, 2.34, 1.23, 0.12, 2.34, 1.23, 0.12) - b_values_2d = (b_values[0:3], b_values[3:6], b_values[6:9]) - expected = 6.22350000000000047606 - - result = wp.ddot(wp.mat33d(*a_values), wp.mat33d(*b_values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.ddot(wp.mat33h(*a_values), wp.mat33h(*b_values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) - test.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) - test.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) - test.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) - - -def test_mat44_mat44_args(test, device): - a_values = (0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45) - a_values_2d = (a_values[0:4], a_values[4:8], a_values[8:12], a_values[12:16]) - b_values = (3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12) - b_values_2d = (b_values[0:4], b_values[4:8], b_values[8:12], b_values[12:16]) - expected = 26.33760000000000189857 - - result = wp.ddot(wp.mat44d(*a_values), wp.mat44d(*b_values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.ddot(wp.mat44h(*a_values), wp.mat44h(*b_values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) - test.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) - test.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) - test.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) - - -def test_mat22_float_args_precision(test, device): - a_values = (1.23, 2.34, 3.45, 4.56) - a_values_2d = (a_values[0:2], a_values[2:4]) - b_value = 0.12 - expected_00 = 0.14759999999999998122 - expected_01 = 0.28079999999999999405 - expected_10 = 0.41399999999999997913 - expected_11 = 0.54719999999999990870 - - result = wp.mul(wp.mat22d(*a_values), wp.float64(b_value)) - test.assertAlmostEqual(result[0][0], expected_00, places=12) - test.assertAlmostEqual(result[0][1], expected_01, places=12) - test.assertAlmostEqual(result[1][0], expected_10, places=12) - test.assertAlmostEqual(result[1][1], expected_11, places=12) - - result = wp.mul(wp.mat22f(*a_values), wp.float32(b_value)) - test.assertNotAlmostEqual(result[0][0], expected_00, places=12) - test.assertNotAlmostEqual(result[0][1], expected_01, places=12) - test.assertNotAlmostEqual(result[1][0], expected_10, places=12) - test.assertNotAlmostEqual(result[1][1], expected_11, places=12) - test.assertAlmostEqual(result[0][0], expected_00, places=5) - test.assertAlmostEqual(result[0][1], expected_01, places=5) - test.assertAlmostEqual(result[1][0], expected_10, places=5) - test.assertAlmostEqual(result[1][1], expected_11, places=5) - - result = wp.mul(wp.mat22h(*a_values), wp.float16(b_value)) - test.assertNotAlmostEqual(result[0][0], expected_00, places=5) - test.assertNotAlmostEqual(result[0][1], expected_01, places=5) - test.assertNotAlmostEqual(result[1][0], expected_10, places=5) - test.assertNotAlmostEqual(result[1][1], expected_11, places=5) - test.assertAlmostEqual(result[0][0], expected_00, places=1) - test.assertAlmostEqual(result[0][1], expected_01, places=1) - test.assertAlmostEqual(result[1][0], expected_10, places=1) - test.assertAlmostEqual(result[1][1], expected_11, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - # Multiplying a 1-D tuple of length 4 is ambiguous because it could match - # either the `vec4f` or `mat22f` overload. As a result, only the 2-D variant - # of the tuple is expected to resolve correctly. - test.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat22f(*a_values), wp.float32(b_value))) - - -def test_mat33_float_args_precision(test, device): - a_values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) - a_values_2d = (a_values[0:3], a_values[3:6], a_values[6:9]) - b_value = 0.12 - expected_00 = 0.14759999999999998122 - expected_01 = 0.28079999999999999405 - expected_02 = 0.41399999999999997913 - expected_10 = 0.54719999999999990870 - expected_11 = 0.68040000000000000480 - expected_12 = 0.81359999999999998987 - expected_20 = 0.94679999999999997495 - expected_21 = 1.06800000000000006040 - expected_22 = 1.08119999999999993889 - - result = wp.mul(wp.mat33d(*a_values), wp.float64(b_value)) - test.assertAlmostEqual(result[0][0], expected_00, places=12) - test.assertAlmostEqual(result[0][1], expected_01, places=12) - test.assertAlmostEqual(result[0][2], expected_02, places=12) - test.assertAlmostEqual(result[1][0], expected_10, places=12) - test.assertAlmostEqual(result[1][1], expected_11, places=12) - test.assertAlmostEqual(result[1][2], expected_12, places=12) - test.assertAlmostEqual(result[2][0], expected_20, places=12) - test.assertAlmostEqual(result[2][1], expected_21, places=12) - test.assertAlmostEqual(result[2][2], expected_22, places=12) - - result = wp.mul(wp.mat33f(*a_values), wp.float32(b_value)) - test.assertNotAlmostEqual(result[0][0], expected_00, places=12) - test.assertNotAlmostEqual(result[0][1], expected_01, places=12) - test.assertNotAlmostEqual(result[0][2], expected_02, places=12) - test.assertNotAlmostEqual(result[1][0], expected_10, places=12) - test.assertNotAlmostEqual(result[1][1], expected_11, places=12) - test.assertNotAlmostEqual(result[1][2], expected_12, places=12) - test.assertNotAlmostEqual(result[2][0], expected_20, places=12) - test.assertNotAlmostEqual(result[2][1], expected_21, places=12) - test.assertNotAlmostEqual(result[2][2], expected_22, places=12) - test.assertAlmostEqual(result[0][0], expected_00, places=5) - test.assertAlmostEqual(result[0][1], expected_01, places=5) - test.assertAlmostEqual(result[0][2], expected_02, places=5) - test.assertAlmostEqual(result[1][0], expected_10, places=5) - test.assertAlmostEqual(result[1][1], expected_11, places=5) - test.assertAlmostEqual(result[1][2], expected_12, places=5) - test.assertAlmostEqual(result[2][0], expected_20, places=5) - test.assertAlmostEqual(result[2][1], expected_21, places=5) - test.assertAlmostEqual(result[2][2], expected_22, places=5) - - result = wp.mul(wp.mat33h(*a_values), wp.float16(b_value)) - test.assertNotAlmostEqual(result[0][0], expected_00, places=5) - test.assertNotAlmostEqual(result[0][1], expected_01, places=5) - test.assertNotAlmostEqual(result[0][2], expected_02, places=5) - test.assertNotAlmostEqual(result[1][0], expected_10, places=5) - test.assertNotAlmostEqual(result[1][1], expected_11, places=5) - test.assertNotAlmostEqual(result[1][2], expected_12, places=5) - test.assertNotAlmostEqual(result[2][0], expected_20, places=5) - test.assertNotAlmostEqual(result[2][1], expected_21, places=5) - test.assertNotAlmostEqual(result[2][2], expected_22, places=5) - test.assertAlmostEqual(result[0][0], expected_00, places=1) - test.assertAlmostEqual(result[0][1], expected_01, places=1) - test.assertAlmostEqual(result[0][2], expected_02, places=1) - test.assertAlmostEqual(result[1][0], expected_10, places=1) - test.assertAlmostEqual(result[1][1], expected_11, places=1) - test.assertAlmostEqual(result[1][2], expected_12, places=1) - test.assertAlmostEqual(result[2][0], expected_20, places=1) - test.assertAlmostEqual(result[2][1], expected_21, places=1) - test.assertAlmostEqual(result[2][2], expected_22, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.mat33f(*a_values), wp.float32(b_value))) - test.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat33f(*a_values), wp.float32(b_value))) - - -def test_mat44_float_args_precision(test, device): - a_values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01, 10.12, 11.23, 12.34, 13.45, 14.56, 15.67, 16.78) - a_values_2d = (a_values[0:4], a_values[4:8], a_values[8:12], a_values[12:16]) - b_value = 0.12 - expected_00 = 0.14759999999999998122 - expected_01 = 0.28079999999999999405 - expected_02 = 0.41399999999999997913 - expected_03 = 0.54719999999999990870 - expected_10 = 0.68040000000000000480 - expected_11 = 0.81359999999999998987 - expected_12 = 0.94679999999999997495 - expected_13 = 1.06800000000000006040 - expected_20 = 1.08119999999999993889 - expected_21 = 1.21439999999999992397 - expected_22 = 1.34759999999999990905 - expected_23 = 1.48079999999999989413 - expected_30 = 1.61399999999999987921 - expected_31 = 1.74720000000000008633 - expected_32 = 1.88039999999999984936 - expected_33 = 2.01360000000000027853 - - result = wp.mul(wp.mat44d(*a_values), wp.float64(b_value)) - test.assertAlmostEqual(result[0][0], expected_00, places=12) - test.assertAlmostEqual(result[0][1], expected_01, places=12) - test.assertAlmostEqual(result[0][2], expected_02, places=12) - test.assertAlmostEqual(result[0][3], expected_03, places=12) - test.assertAlmostEqual(result[1][0], expected_10, places=12) - test.assertAlmostEqual(result[1][1], expected_11, places=12) - test.assertAlmostEqual(result[1][2], expected_12, places=12) - test.assertAlmostEqual(result[1][3], expected_13, places=12) - test.assertAlmostEqual(result[2][0], expected_20, places=12) - test.assertAlmostEqual(result[2][1], expected_21, places=12) - test.assertAlmostEqual(result[2][2], expected_22, places=12) - test.assertAlmostEqual(result[2][3], expected_23, places=12) - test.assertAlmostEqual(result[3][0], expected_30, places=12) - test.assertAlmostEqual(result[3][1], expected_31, places=12) - test.assertAlmostEqual(result[3][2], expected_32, places=12) - test.assertAlmostEqual(result[3][3], expected_33, places=12) - - result = wp.mul(wp.mat44f(*a_values), wp.float32(b_value)) - test.assertNotAlmostEqual(result[0][0], expected_00, places=12) - test.assertNotAlmostEqual(result[0][1], expected_01, places=12) - test.assertNotAlmostEqual(result[0][2], expected_02, places=12) - test.assertNotAlmostEqual(result[0][3], expected_03, places=12) - test.assertNotAlmostEqual(result[1][0], expected_10, places=12) - test.assertNotAlmostEqual(result[1][1], expected_11, places=12) - test.assertNotAlmostEqual(result[1][2], expected_12, places=12) - test.assertNotAlmostEqual(result[1][3], expected_13, places=12) - test.assertNotAlmostEqual(result[2][0], expected_20, places=12) - test.assertNotAlmostEqual(result[2][1], expected_21, places=12) - test.assertNotAlmostEqual(result[2][2], expected_22, places=12) - test.assertNotAlmostEqual(result[2][3], expected_23, places=12) - test.assertNotAlmostEqual(result[3][0], expected_30, places=12) - test.assertNotAlmostEqual(result[3][1], expected_31, places=12) - test.assertNotAlmostEqual(result[3][2], expected_32, places=12) - test.assertNotAlmostEqual(result[3][3], expected_33, places=12) - test.assertAlmostEqual(result[0][0], expected_00, places=5) - test.assertAlmostEqual(result[0][1], expected_01, places=5) - test.assertAlmostEqual(result[0][2], expected_02, places=5) - test.assertAlmostEqual(result[0][3], expected_03, places=5) - test.assertAlmostEqual(result[1][0], expected_10, places=5) - test.assertAlmostEqual(result[1][1], expected_11, places=5) - test.assertAlmostEqual(result[1][2], expected_12, places=5) - test.assertAlmostEqual(result[1][3], expected_13, places=5) - test.assertAlmostEqual(result[2][0], expected_20, places=5) - test.assertAlmostEqual(result[2][1], expected_21, places=5) - test.assertAlmostEqual(result[2][2], expected_22, places=5) - test.assertAlmostEqual(result[2][3], expected_23, places=5) - test.assertAlmostEqual(result[3][0], expected_30, places=5) - test.assertAlmostEqual(result[3][1], expected_31, places=5) - test.assertAlmostEqual(result[3][2], expected_32, places=5) - test.assertAlmostEqual(result[3][3], expected_33, places=5) - - result = wp.mul(wp.mat44h(*a_values), wp.float16(b_value)) - test.assertNotAlmostEqual(result[0][0], expected_00, places=5) - test.assertNotAlmostEqual(result[0][1], expected_01, places=5) - test.assertNotAlmostEqual(result[0][2], expected_02, places=5) - test.assertNotAlmostEqual(result[0][3], expected_03, places=5) - test.assertNotAlmostEqual(result[1][0], expected_10, places=5) - test.assertNotAlmostEqual(result[1][1], expected_11, places=5) - test.assertNotAlmostEqual(result[1][2], expected_12, places=5) - test.assertNotAlmostEqual(result[1][3], expected_13, places=5) - test.assertNotAlmostEqual(result[2][0], expected_20, places=5) - test.assertNotAlmostEqual(result[2][1], expected_21, places=5) - test.assertNotAlmostEqual(result[2][2], expected_22, places=5) - test.assertNotAlmostEqual(result[2][3], expected_23, places=5) - test.assertNotAlmostEqual(result[3][0], expected_30, places=5) - test.assertNotAlmostEqual(result[3][1], expected_31, places=5) - test.assertNotAlmostEqual(result[3][2], expected_32, places=5) - test.assertNotAlmostEqual(result[3][3], expected_33, places=5) - test.assertAlmostEqual(result[0][0], expected_00, places=1) - test.assertAlmostEqual(result[0][1], expected_01, places=1) - test.assertAlmostEqual(result[0][2], expected_02, places=1) - test.assertAlmostEqual(result[0][3], expected_03, places=1) - test.assertAlmostEqual(result[1][0], expected_10, places=1) - test.assertAlmostEqual(result[1][1], expected_11, places=1) - test.assertAlmostEqual(result[1][2], expected_12, places=1) - test.assertAlmostEqual(result[1][3], expected_13, places=1) - test.assertAlmostEqual(result[2][0], expected_20, places=1) - test.assertAlmostEqual(result[2][1], expected_21, places=1) - test.assertAlmostEqual(result[2][2], expected_22, places=1) - test.assertAlmostEqual(result[2][3], expected_23, places=1) - test.assertAlmostEqual(result[3][0], expected_30, places=1) - test.assertAlmostEqual(result[3][1], expected_31, places=1) - test.assertAlmostEqual(result[3][2], expected_32, places=1) - test.assertAlmostEqual(result[3][3], expected_33, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.mat44f(*a_values), wp.float32(b_value))) - test.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat44f(*a_values), wp.float32(b_value))) - - -def test_vec2_arg_precision(test, device): - values = (1.23, 2.34) - expected = 2.64357712200722438922 - - result = wp.length(wp.vec2d(*values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.length(wp.vec2f(*values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.length(wp.vec2h(*values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.length(values), wp.length(wp.vec2f(*values))) - - -def test_vec2_arg_overflow(test, device): - values = (-1234567890, -1234567890) - - test.assertEqual(wp.length_sq(wp.vec2b(*values)), -120) - test.assertEqual(wp.length_sq(wp.vec2s(*values)), -6008) - test.assertEqual(wp.length_sq(wp.vec2i(*values)), 608168072) - test.assertEqual(wp.length_sq(wp.vec2l(*values)), 3048315750038104200) - - test.assertEqual(wp.length_sq(wp.vec2ub(*values)), 136) - test.assertEqual(wp.length_sq(wp.vec2us(*values)), 59528) - test.assertEqual(wp.length_sq(wp.vec2ui(*values)), 608168072) - test.assertEqual(wp.length_sq(wp.vec2ul(*values)), 3048315750038104200) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec2i(*values))) - - -def test_vec3_arg_precision(test, device): - values = (1.23, 2.34, 3.45) - expected = 4.34637780226247727455 - - result = wp.length(wp.vec3d(*values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.length(wp.vec3f(*values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.length(wp.vec3h(*values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.length(values), wp.length(wp.vec3f(*values))) - - -def test_vec3_arg_overflow(test, device): - values = (-1234567890, -1234567890, -1234567890) - - test.assertEqual(wp.length_sq(wp.vec3b(*values)), -52) - test.assertEqual(wp.length_sq(wp.vec3s(*values)), -9012) - test.assertEqual(wp.length_sq(wp.vec3i(*values)), 912252108) - test.assertEqual(wp.length_sq(wp.vec3l(*values)), 4572473625057156300) - - test.assertEqual(wp.length_sq(wp.vec3ub(*values)), 204) - test.assertEqual(wp.length_sq(wp.vec3us(*values)), 56524) - test.assertEqual(wp.length_sq(wp.vec3ui(*values)), 912252108) - test.assertEqual(wp.length_sq(wp.vec3ul(*values)), 4572473625057156300) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec3i(*values))) - - -def test_vec4_arg_precision(test, device): - values = (1.23, 2.34, 3.45, 4.56) - expected = 6.29957141399317777086 - - result = wp.length(wp.vec4d(*values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.length(wp.vec4f(*values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.length(wp.vec4h(*values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.length(values), wp.length(wp.vec4f(*values))) - - -def test_vec4_arg_overflow(test, device): - values = (-1234567890, -1234567890, -1234567890, -1234567890) - - test.assertEqual(wp.length_sq(wp.vec4b(*values)), 16) - test.assertEqual(wp.length_sq(wp.vec4s(*values)), -12016) - test.assertEqual(wp.length_sq(wp.vec4i(*values)), 1216336144) - test.assertEqual(wp.length_sq(wp.vec4l(*values)), 6096631500076208400) - - test.assertEqual(wp.length_sq(wp.vec4ub(*values)), 16) - test.assertEqual(wp.length_sq(wp.vec4us(*values)), 53520) - test.assertEqual(wp.length_sq(wp.vec4ui(*values)), 1216336144) - test.assertEqual(wp.length_sq(wp.vec4ul(*values)), 6096631500076208400) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec4i(*values))) - - -def test_vec2_vec2_args_precision(test, device): - a_values = (1.23, 2.34) - b_values = (3.45, 4.56) - expected = 14.91389999999999815827 - - result = wp.dot(wp.vec2d(*a_values), wp.vec2d(*b_values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.dot(wp.vec2f(*a_values), wp.vec2f(*b_values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.dot(wp.vec2h(*a_values), wp.vec2h(*b_values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec2f(*a_values), wp.vec2f(*b_values))) - - -def test_vec2_vec2_args_overflow(test, device): - values = (-1234567890, -1234567890) - - test.assertEqual(wp.dot(wp.vec2b(*values), wp.vec2b(*values)), -120) - test.assertEqual(wp.dot(wp.vec2s(*values), wp.vec2s(*values)), -6008) - test.assertEqual(wp.dot(wp.vec2i(*values), wp.vec2i(*values)), 608168072) - test.assertEqual(wp.dot(wp.vec2l(*values), wp.vec2l(*values)), 3048315750038104200) - - test.assertEqual(wp.dot(wp.vec2ub(*values), wp.vec2ub(*values)), 136) - test.assertEqual(wp.dot(wp.vec2us(*values), wp.vec2us(*values)), 59528) - test.assertEqual(wp.dot(wp.vec2ui(*values), wp.vec2ui(*values)), 608168072) - test.assertEqual(wp.dot(wp.vec2ul(*values), wp.vec2ul(*values)), 3048315750038104200) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.dot(values, values), wp.dot(wp.vec2i(*values), wp.vec2i(*values))) - - -def test_vec3_vec3_args_precision(test, device): - a_values = (1.23, 2.34, 3.45) - b_values = (4.56, 5.67, 6.78) - expected = 42.26760000000000161435 - - result = wp.dot(wp.vec3d(*a_values), wp.vec3d(*b_values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.dot(wp.vec3f(*a_values), wp.vec3f(*b_values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.dot(wp.vec3h(*a_values), wp.vec3h(*b_values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec3f(*a_values), wp.vec3f(*b_values))) - - -def test_vec3_vec3_args_overflow(test, device): - values = (-1234567890, -1234567890, -1234567890) - - test.assertEqual(wp.dot(wp.vec3b(*values), wp.vec3b(*values)), -52) - test.assertEqual(wp.dot(wp.vec3s(*values), wp.vec3s(*values)), -9012) - test.assertEqual(wp.dot(wp.vec3i(*values), wp.vec3i(*values)), 912252108) - test.assertEqual(wp.dot(wp.vec3l(*values), wp.vec3l(*values)), 4572473625057156300) - - test.assertEqual(wp.dot(wp.vec3ub(*values), wp.vec3ub(*values)), 204) - test.assertEqual(wp.dot(wp.vec3us(*values), wp.vec3us(*values)), 56524) - test.assertEqual(wp.dot(wp.vec3ui(*values), wp.vec3ui(*values)), 912252108) - test.assertEqual(wp.dot(wp.vec3ul(*values), wp.vec3ul(*values)), 4572473625057156300) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.dot(values, values), wp.dot(wp.vec3i(*values), wp.vec3i(*values))) - - -def test_vec4_vec4_args_precision(test, device): - a_values = (1.23, 2.34, 3.45, 4.56) - b_values = (5.67, 6.78, 7.89, 8.90) - expected = 90.64379999999999881766 - - result = wp.dot(wp.vec4d(*a_values), wp.vec4d(*b_values)) - test.assertAlmostEqual(result, expected, places=12) - - result = wp.dot(wp.vec4f(*a_values), wp.vec4f(*b_values)) - test.assertNotAlmostEqual(result, expected, places=12) - test.assertAlmostEqual(result, expected, places=5) - - result = wp.dot(wp.vec4h(*a_values), wp.vec4h(*b_values)) - test.assertNotAlmostEqual(result, expected, places=5) - test.assertAlmostEqual(result, expected, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec4f(*a_values), wp.vec4f(*b_values))) - - -def test_vec4_vec4_args_overflow(test, device): - values = (-1234567890, -1234567890, -1234567890, -1234567890) - - test.assertEqual(wp.dot(wp.vec4b(*values), wp.vec4b(*values)), 16) - test.assertEqual(wp.dot(wp.vec4s(*values), wp.vec4s(*values)), -12016) - test.assertEqual(wp.dot(wp.vec4i(*values), wp.vec4i(*values)), 1216336144) - test.assertEqual(wp.dot(wp.vec4l(*values), wp.vec4l(*values)), 6096631500076208400) - - test.assertEqual(wp.dot(wp.vec4ub(*values), wp.vec4ub(*values)), 16) - test.assertEqual(wp.dot(wp.vec4us(*values), wp.vec4us(*values)), 53520) - test.assertEqual(wp.dot(wp.vec4ui(*values), wp.vec4ui(*values)), 1216336144) - test.assertEqual(wp.dot(wp.vec4ul(*values), wp.vec4ul(*values)), 6096631500076208400) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.dot(values, values), wp.dot(wp.vec4i(*values), wp.vec4i(*values))) - - -def test_vec2_float_args_precision(test, device): - a_values = (1.23, 2.34) - b_value = 3.45 - expected_x = 4.24350000000000004974 - expected_y = 8.07300000000000039790 - - result = wp.mul(wp.vec2d(*a_values), wp.float64(b_value)) - test.assertAlmostEqual(result[0], expected_x, places=12) - test.assertAlmostEqual(result[1], expected_y, places=12) - - result = wp.mul(wp.vec2f(*a_values), wp.float32(b_value)) - test.assertNotAlmostEqual(result[0], expected_x, places=12) - test.assertNotAlmostEqual(result[1], expected_y, places=12) - test.assertAlmostEqual(result[0], expected_x, places=5) - test.assertAlmostEqual(result[1], expected_y, places=5) - - result = wp.mul(wp.vec2h(*a_values), wp.float16(b_value)) - test.assertNotAlmostEqual(result[0], expected_x, places=5) - test.assertNotAlmostEqual(result[1], expected_y, places=5) - test.assertAlmostEqual(result[0], expected_x, places=1) - test.assertAlmostEqual(result[1], expected_y, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec2f(*a_values), wp.float32(b_value))) - - -def test_vec3_float_args_precision(test, device): - a_values = (1.23, 2.34, 3.45) - b_value = 4.56 - expected_x = 5.60879999999999956373 - expected_y = 10.67039999999999899671 - expected_z = 15.73199999999999931788 - - result = wp.mul(wp.vec3d(*a_values), wp.float64(b_value)) - test.assertAlmostEqual(result[0], expected_x, places=12) - test.assertAlmostEqual(result[1], expected_y, places=12) - test.assertAlmostEqual(result[2], expected_z, places=12) - - result = wp.mul(wp.vec3f(*a_values), wp.float32(b_value)) - test.assertNotAlmostEqual(result[0], expected_x, places=12) - test.assertNotAlmostEqual(result[1], expected_y, places=12) - test.assertNotAlmostEqual(result[2], expected_z, places=12) - test.assertAlmostEqual(result[0], expected_x, places=5) - test.assertAlmostEqual(result[1], expected_y, places=5) - test.assertAlmostEqual(result[2], expected_z, places=5) - - result = wp.mul(wp.vec3h(*a_values), wp.float16(b_value)) - test.assertNotAlmostEqual(result[0], expected_x, places=5) - test.assertNotAlmostEqual(result[1], expected_y, places=5) - test.assertNotAlmostEqual(result[2], expected_z, places=5) - test.assertAlmostEqual(result[0], expected_x, places=1) - test.assertAlmostEqual(result[1], expected_y, places=1) - test.assertAlmostEqual(result[2], expected_z, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec3f(*a_values), wp.float32(b_value))) - - -def test_vec4_float_args_precision(test, device): - a_values = (1.23, 2.34, 3.45, 4.56) - b_value = 5.67 - expected_x = 6.97409999999999996589 - expected_y = 13.26779999999999937188 - expected_z = 19.56150000000000233058 - expected_w = 25.85519999999999640750 - - result = wp.mul(wp.vec4d(*a_values), wp.float64(b_value)) - test.assertAlmostEqual(result[0], expected_x, places=12) - test.assertAlmostEqual(result[1], expected_y, places=12) - test.assertAlmostEqual(result[2], expected_z, places=12) - test.assertAlmostEqual(result[3], expected_w, places=12) - - result = wp.mul(wp.vec4f(*a_values), wp.float32(b_value)) - test.assertNotAlmostEqual(result[0], expected_x, places=12) - test.assertNotAlmostEqual(result[1], expected_y, places=12) - test.assertNotAlmostEqual(result[2], expected_z, places=12) - test.assertNotAlmostEqual(result[3], expected_w, places=12) - test.assertAlmostEqual(result[0], expected_x, places=5) - test.assertAlmostEqual(result[1], expected_y, places=5) - test.assertAlmostEqual(result[2], expected_z, places=5) - test.assertAlmostEqual(result[3], expected_w, places=5) - - result = wp.mul(wp.vec4h(*a_values), wp.float16(b_value)) - test.assertNotAlmostEqual(result[0], expected_x, places=5) - test.assertNotAlmostEqual(result[1], expected_y, places=5) - test.assertNotAlmostEqual(result[2], expected_z, places=5) - test.assertNotAlmostEqual(result[3], expected_w, places=5) - test.assertAlmostEqual(result[0], expected_x, places=1) - test.assertAlmostEqual(result[1], expected_y, places=1) - test.assertAlmostEqual(result[2], expected_z, places=1) - test.assertAlmostEqual(result[3], expected_w, places=1) - - with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): - test.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec4f(*a_values), wp.float32(b_value))) - - def test_int_arg_support(test, device, dtype): np_type = wp.types.warp_type_to_np_dtype[dtype] value = -1234567890123456789 @@ -806,29 +78,25 @@ def test_int_int_args_support(test, device, dtype): else: with test.assertRaisesRegex( RuntimeError, - rf"Couldn't find a function 'mul' compatible with " - rf"the arguments '{dtype.__name__}, int'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments '{dtype.__name__}, int'$", ): wp.mul(dtype(value), value) with test.assertRaisesRegex( RuntimeError, - rf"Couldn't find a function 'mul' compatible with " - rf"the arguments '{np_type.__name__}, int'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments '{np_type.__name__}, int'$", ): wp.mul(nps(np_type, value), value) with test.assertRaisesRegex( RuntimeError, - rf"Couldn't find a function 'mul' compatible with " - rf"the arguments 'int, {dtype.__name__}'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments 'int, {dtype.__name__}'$", ): wp.mul(value, dtype(value)) with test.assertRaisesRegex( RuntimeError, - rf"Couldn't find a function 'mul' compatible with " - rf"the arguments 'int, {np_type.__name__}'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments 'int, {np_type.__name__}'$", ): wp.mul(value, nps(np_type, value)) @@ -915,85 +183,73 @@ def test_mat_mat_args_support(test, device, dtype): else: with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'mat_t, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'mat_t, tuple'$", ): wp.ddot(mat_cls(*a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(wpv(dtype, a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(wpm(dtype, 3, a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(npv(np_type, a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(npm(np_type, 3, a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'ndarray, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'ndarray, tuple'$", ): wp.ddot(np.array(npv(np_type, a_values)), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, mat_t'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, mat_t'$", ): wp.ddot(a_values, mat_cls(*b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(a_values, wpv(dtype, b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(a_values, wpm(dtype, 3, b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(a_values, npv(np_type, b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.ddot(a_values, npm(np_type, 3, b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'ddot' compatible with " - r"the arguments 'tuple, ndarray'$", + r"Couldn't find a function 'ddot' compatible with " r"the arguments 'tuple, ndarray'$", ): wp.ddot(a_values, np.array(npv(np_type, b_values))) @@ -1038,57 +294,49 @@ def test_mat_float_args_support(test, device, dtype): else: with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'mat_t, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'mat_t, float'$", ): wp.mul(mat_cls(*a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'tuple, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'tuple, float'$", ): wp.mul(wpv(dtype, a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'tuple, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'tuple, float'$", ): wp.mul(wpm(dtype, 3, a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'tuple, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'tuple, float'$", ): wp.mul(npv(np_type, a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'tuple, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'tuple, float'$", ): wp.mul(npm(np_type, 3, a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'ndarray, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'ndarray, float'$", ): wp.mul(np.array(npv(np_type, a_values)), b_value) with test.assertRaisesRegex( RuntimeError, - fr"Couldn't find a function 'mul' compatible with " - fr"the arguments 'tuple, {dtype.__name__}'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments 'tuple, {dtype.__name__}'$", ): wp.mul(a_values, dtype(b_value)) with test.assertRaisesRegex( RuntimeError, - fr"Couldn't find a function 'mul' compatible with " - fr"the arguments 'tuple, {np_type.__name__}'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments 'tuple, {np_type.__name__}'$", ): wp.mul(a_values, nps(np_type, b_value)) @@ -1147,57 +395,49 @@ def test_vec_vec_args_support(test, device, dtype): else: with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'vec_t, tuple'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'vec_t, tuple'$", ): wp.dot(vec_cls(*a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.dot(wpv(dtype, a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.dot(npv(np_type, a_values), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'ndarray, tuple'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'ndarray, tuple'$", ): wp.dot(np.array(npv(np_type, a_values)), b_values) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'tuple, vec_t'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'tuple, vec_t'$", ): wp.dot(a_values, vec_cls(*b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.dot(a_values, wpv(dtype, b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'tuple, tuple'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'tuple, tuple'$", ): wp.dot(a_values, npv(np_type, b_values)) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'dot' compatible with " - r"the arguments 'tuple, ndarray'$", + r"Couldn't find a function 'dot' compatible with " r"the arguments 'tuple, ndarray'$", ): wp.dot(a_values, np.array(npv(np_type, b_values))) @@ -1234,141 +474,819 @@ def test_vec_float_args_support(test, device, dtype): else: with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'vec_t, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'vec_t, float'$", ): wp.mul(vec_cls(*a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'tuple, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'tuple, float'$", ): wp.mul(wpv(dtype, a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'tuple, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'tuple, float'$", ): wp.mul(npv(np_type, a_values), b_value) with test.assertRaisesRegex( RuntimeError, - r"Couldn't find a function 'mul' compatible with " - r"the arguments 'ndarray, float'$", + r"Couldn't find a function 'mul' compatible with " r"the arguments 'ndarray, float'$", ): wp.mul(np.array(npv(np_type, a_values)), b_value) with test.assertRaisesRegex( RuntimeError, - fr"Couldn't find a function 'mul' compatible with " - fr"the arguments 'tuple, {dtype.__name__}'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments 'tuple, {dtype.__name__}'$", ): wp.mul(a_values, dtype(b_value)) with test.assertRaisesRegex( RuntimeError, - fr"Couldn't find a function 'mul' compatible with " - fr"the arguments 'tuple, {np_type.__name__}'$", + rf"Couldn't find a function 'mul' compatible with " rf"the arguments 'tuple, {np_type.__name__}'$", ): wp.mul(a_values, nps(np_type, b_value)) -def register(parent): - class TestBuiltinsResolution(parent): - pass - - add_function_test(TestBuiltinsResolution, "test_int_arg_overflow", test_int_arg_overflow) - add_function_test(TestBuiltinsResolution, "test_float_arg_precision", test_float_arg_precision) - add_function_test(TestBuiltinsResolution, "test_int_int_args_overflow", test_int_int_args_overflow) - add_function_test(TestBuiltinsResolution, "test_mat22_arg_precision", test_mat22_arg_precision) - add_function_test(TestBuiltinsResolution, "test_mat33_arg_precision", test_mat33_arg_precision) - add_function_test(TestBuiltinsResolution, "test_mat44_arg_precision", test_mat44_arg_precision) - add_function_test(TestBuiltinsResolution, "test_mat22_mat22_args_precision", test_mat22_mat22_args_precision) - add_function_test(TestBuiltinsResolution, "test_mat33_mat33_args_precision", test_mat33_mat33_args_precision) - add_function_test(TestBuiltinsResolution, "test_mat44_mat44_args", test_mat44_mat44_args) - add_function_test(TestBuiltinsResolution, "test_mat22_float_args_precision", test_mat22_float_args_precision) - add_function_test(TestBuiltinsResolution, "test_mat33_float_args_precision", test_mat33_float_args_precision) - add_function_test(TestBuiltinsResolution, "test_mat44_float_args_precision", test_mat44_float_args_precision) - add_function_test(TestBuiltinsResolution, "test_vec2_arg_precision", test_vec2_arg_precision) - add_function_test(TestBuiltinsResolution, "test_vec2_arg_overflow", test_vec2_arg_overflow) - add_function_test(TestBuiltinsResolution, "test_vec3_arg_precision", test_vec3_arg_precision) - add_function_test(TestBuiltinsResolution, "test_vec3_arg_overflow", test_vec3_arg_overflow) - add_function_test(TestBuiltinsResolution, "test_vec4_arg_precision", test_vec4_arg_precision) - add_function_test(TestBuiltinsResolution, "test_vec4_arg_overflow", test_vec4_arg_overflow) - add_function_test(TestBuiltinsResolution, "test_vec2_vec2_args_precision", test_vec2_vec2_args_precision) - add_function_test(TestBuiltinsResolution, "test_vec2_vec2_args_overflow", test_vec2_vec2_args_overflow) - add_function_test(TestBuiltinsResolution, "test_vec3_vec3_args_precision", test_vec3_vec3_args_precision) - add_function_test(TestBuiltinsResolution, "test_vec3_vec3_args_overflow", test_vec3_vec3_args_overflow) - add_function_test(TestBuiltinsResolution, "test_vec4_vec4_args_precision", test_vec4_vec4_args_precision) - add_function_test(TestBuiltinsResolution, "test_vec4_vec4_args_overflow", test_vec4_vec4_args_overflow) - add_function_test(TestBuiltinsResolution, "test_vec2_float_args_precision", test_vec2_float_args_precision) - add_function_test(TestBuiltinsResolution, "test_vec3_float_args_precision", test_vec3_float_args_precision) - add_function_test(TestBuiltinsResolution, "test_vec4_float_args_precision", test_vec4_float_args_precision) - - for dtype in wp.types.int_types: - add_function_test( - TestBuiltinsResolution, - f"test_int_arg_support_{dtype.__name__}", - test_int_arg_support, - dtype=dtype, - ) - add_function_test( - TestBuiltinsResolution, - f"test_int_int_args_support_{dtype.__name__}", - test_int_int_args_support, - dtype=dtype, - ) +class TestBuiltinsResolution(unittest.TestCase): + def test_int_arg_overflow(self): + value = -1234567890123456789 - for dtype in wp.types.float_types: - add_function_test( - TestBuiltinsResolution, - f"test_float_arg_support_{dtype.__name__}", - test_float_arg_support, - dtype=dtype, - ) - add_function_test( - TestBuiltinsResolution, - f"test_mat_arg_support_{dtype.__name__}", - test_mat_arg_support, - dtype=dtype, - ) - add_function_test( - TestBuiltinsResolution, - f"test_mat_mat_args_support_{dtype.__name__}", - test_mat_mat_args_support, - dtype=dtype, - ) - add_function_test( - TestBuiltinsResolution, - f"test_mat_float_args_support_{dtype.__name__}", - test_mat_float_args_support, - dtype=dtype, - ) - add_function_test( - TestBuiltinsResolution, - f"test_vec_arg_support_{dtype.__name__}", - test_vec_arg_support, - dtype=dtype, - ) - add_function_test( - TestBuiltinsResolution, - f"test_vec_vec_args_support_{dtype.__name__}", - test_vec_vec_args_support, - dtype=dtype, - ) - add_function_test( - TestBuiltinsResolution, - f"test_vec_float_args_support_{dtype.__name__}", - test_vec_float_args_support, - dtype=dtype, + self.assertEqual(wp.invert(wp.int8(value)), 20) + self.assertEqual(wp.invert(wp.int16(value)), -32492) + self.assertEqual(wp.invert(wp.int32(value)), 2112454932) + self.assertEqual(wp.invert(wp.int64(value)), 1234567890123456788) + + self.assertEqual(wp.invert(wp.uint8(value)), 20) + self.assertEqual(wp.invert(wp.uint16(value)), 33044) + self.assertEqual(wp.invert(wp.uint32(value)), 2112454932) + self.assertEqual(wp.invert(wp.uint64(value)), 1234567890123456788) + + self.assertEqual(wp.invert(value), wp.invert(wp.int32(value))) + + def test_float_arg_precision(self): + value = 1.23 + expected = 0.94248880193169748409 + + result = wp.sin(wp.float64(value)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.sin(wp.float32(value)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.sin(wp.float16(value)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + self.assertEqual(wp.sin(value), wp.sin(wp.float32(value))) + + def test_int_int_args_overflow(self): + value = -1234567890 + + self.assertEqual(wp.mul(wp.int8(value), wp.int8(value)), 68) + self.assertEqual(wp.mul(wp.int16(value), wp.int16(value)), -3004) + self.assertEqual(wp.mul(wp.int32(value), wp.int32(value)), 304084036) + self.assertEqual(wp.mul(wp.int64(value), wp.int64(value)), 1524157875019052100) + + self.assertEqual(wp.mul(wp.uint8(value), wp.uint8(value)), 68) + self.assertEqual(wp.mul(wp.uint16(value), wp.uint16(value)), 62532) + self.assertEqual(wp.mul(wp.uint32(value), wp.uint32(value)), 304084036) + self.assertEqual(wp.mul(wp.uint64(value), wp.uint64(value)), 1524157875019052100) + + self.assertEqual(wp.mul(value, value), wp.mul(wp.int32(value), wp.int32(value))) + + def test_mat22_arg_precision(self): + values = (1.23, 2.34, 3.45, 4.56) + values_2d = (values[0:2], values[2:4]) + expected = 5.78999999999999914735 + + result = wp.trace(wp.mat22d(*values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.trace(wp.mat22f(*values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.trace(wp.mat22h(*values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.trace(values), wp.trace(wp.mat22f(*values))) + self.assertEqual(wp.trace(values_2d), wp.trace(wp.mat22f(*values))) + + def test_mat33_arg_precision(self): + values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) + values_2d = (values[0:3], values[3:6], values[6:9]) + expected = 15.91000000000000014211 + + result = wp.trace(wp.mat33d(*values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.trace(wp.mat33f(*values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.trace(wp.mat33h(*values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.trace(values), wp.trace(wp.mat33f(*values))) + self.assertEqual(wp.trace(values_2d), wp.trace(wp.mat33f(*values))) + + def test_mat44_arg_precision(self): + values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01, 10.12, 11.23, 12.34, 13.45, 14.56, 15.67, 16.78) + values_2d = (values[0:4], values[4:8], values[8:12], values[12:16]) + expected = 36.02000000000000312639 + + result = wp.trace(wp.mat44d(*values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.trace(wp.mat44f(*values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.trace(wp.mat44h(*values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.trace(values), wp.trace(wp.mat44f(*values))) + self.assertEqual(wp.trace(values_2d), wp.trace(wp.mat44f(*values))) + + def test_mat22_mat22_args_precision(self): + a_values = (0.12, 1.23, 0.12, 1.23) + a_values_2d = (a_values[0:2], a_values[2:4]) + b_values = (1.23, 0.12, 1.23, 0.12) + b_values_2d = (b_values[0:2], b_values[2:4]) + expected = 0.59039999999999992486 + + result = wp.ddot(wp.mat22d(*a_values), wp.mat22d(*b_values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.ddot(wp.mat22h(*a_values), wp.mat22h(*b_values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + self.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + self.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + self.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat22f(*a_values), wp.mat22f(*b_values))) + + def test_mat33_mat33_args_precision(self): + a_values = (0.12, 1.23, 2.34, 0.12, 1.23, 2.34, 0.12, 1.23, 2.34) + a_values_2d = (a_values[0:3], a_values[3:6], a_values[6:9]) + b_values = (2.34, 1.23, 0.12, 2.34, 1.23, 0.12, 2.34, 1.23, 0.12) + b_values_2d = (b_values[0:3], b_values[3:6], b_values[6:9]) + expected = 6.22350000000000047606 + + result = wp.ddot(wp.mat33d(*a_values), wp.mat33d(*b_values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.ddot(wp.mat33h(*a_values), wp.mat33h(*b_values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + self.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + self.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + self.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat33f(*a_values), wp.mat33f(*b_values))) + + def test_mat44_mat44_args(self): + a_values = (0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45, 0.12, 1.23, 2.34, 3.45) + a_values_2d = (a_values[0:4], a_values[4:8], a_values[8:12], a_values[12:16]) + b_values = (3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12, 3.45, 2.34, 1.23, 0.12) + b_values_2d = (b_values[0:4], b_values[4:8], b_values[8:12], b_values[12:16]) + expected = 26.33760000000000189857 + + result = wp.ddot(wp.mat44d(*a_values), wp.mat44d(*b_values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.ddot(wp.mat44h(*a_values), wp.mat44h(*b_values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.ddot(a_values, b_values), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + self.assertEqual(wp.ddot(a_values_2d, b_values_2d), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + self.assertEqual(wp.ddot(a_values, b_values_2d), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + self.assertEqual(wp.ddot(a_values_2d, b_values), wp.ddot(wp.mat44f(*a_values), wp.mat44f(*b_values))) + + def test_mat22_float_args_precision(self): + a_values = (1.23, 2.34, 3.45, 4.56) + a_values_2d = (a_values[0:2], a_values[2:4]) + b_value = 0.12 + expected_00 = 0.14759999999999998122 + expected_01 = 0.28079999999999999405 + expected_10 = 0.41399999999999997913 + expected_11 = 0.54719999999999990870 + + result = wp.mul(wp.mat22d(*a_values), wp.float64(b_value)) + self.assertAlmostEqual(result[0][0], expected_00, places=12) + self.assertAlmostEqual(result[0][1], expected_01, places=12) + self.assertAlmostEqual(result[1][0], expected_10, places=12) + self.assertAlmostEqual(result[1][1], expected_11, places=12) + + result = wp.mul(wp.mat22f(*a_values), wp.float32(b_value)) + self.assertNotAlmostEqual(result[0][0], expected_00, places=12) + self.assertNotAlmostEqual(result[0][1], expected_01, places=12) + self.assertNotAlmostEqual(result[1][0], expected_10, places=12) + self.assertNotAlmostEqual(result[1][1], expected_11, places=12) + self.assertAlmostEqual(result[0][0], expected_00, places=5) + self.assertAlmostEqual(result[0][1], expected_01, places=5) + self.assertAlmostEqual(result[1][0], expected_10, places=5) + self.assertAlmostEqual(result[1][1], expected_11, places=5) + + result = wp.mul(wp.mat22h(*a_values), wp.float16(b_value)) + self.assertNotAlmostEqual(result[0][0], expected_00, places=5) + self.assertNotAlmostEqual(result[0][1], expected_01, places=5) + self.assertNotAlmostEqual(result[1][0], expected_10, places=5) + self.assertNotAlmostEqual(result[1][1], expected_11, places=5) + self.assertAlmostEqual(result[0][0], expected_00, places=1) + self.assertAlmostEqual(result[0][1], expected_01, places=1) + self.assertAlmostEqual(result[1][0], expected_10, places=1) + self.assertAlmostEqual(result[1][1], expected_11, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + # Multiplying a 1-D tuple of length 4 is ambiguous because it could match + # either the `vec4f` or `mat22f` overload. As a result, only the 2-D variant + # of the tuple is expected to resolve correctly. + self.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat22f(*a_values), wp.float32(b_value))) + + def test_mat33_float_args_precision(self): + a_values = (1.23, 2.34, 3.45, 4.56, 5.67, 6.78, 7.89, 8.90, 9.01) + a_values_2d = (a_values[0:3], a_values[3:6], a_values[6:9]) + b_value = 0.12 + expected_00 = 0.14759999999999998122 + expected_01 = 0.28079999999999999405 + expected_02 = 0.41399999999999997913 + expected_10 = 0.54719999999999990870 + expected_11 = 0.68040000000000000480 + expected_12 = 0.81359999999999998987 + expected_20 = 0.94679999999999997495 + expected_21 = 1.06800000000000006040 + expected_22 = 1.08119999999999993889 + + result = wp.mul(wp.mat33d(*a_values), wp.float64(b_value)) + self.assertAlmostEqual(result[0][0], expected_00, places=12) + self.assertAlmostEqual(result[0][1], expected_01, places=12) + self.assertAlmostEqual(result[0][2], expected_02, places=12) + self.assertAlmostEqual(result[1][0], expected_10, places=12) + self.assertAlmostEqual(result[1][1], expected_11, places=12) + self.assertAlmostEqual(result[1][2], expected_12, places=12) + self.assertAlmostEqual(result[2][0], expected_20, places=12) + self.assertAlmostEqual(result[2][1], expected_21, places=12) + self.assertAlmostEqual(result[2][2], expected_22, places=12) + + result = wp.mul(wp.mat33f(*a_values), wp.float32(b_value)) + self.assertNotAlmostEqual(result[0][0], expected_00, places=12) + self.assertNotAlmostEqual(result[0][1], expected_01, places=12) + self.assertNotAlmostEqual(result[0][2], expected_02, places=12) + self.assertNotAlmostEqual(result[1][0], expected_10, places=12) + self.assertNotAlmostEqual(result[1][1], expected_11, places=12) + self.assertNotAlmostEqual(result[1][2], expected_12, places=12) + self.assertNotAlmostEqual(result[2][0], expected_20, places=12) + self.assertNotAlmostEqual(result[2][1], expected_21, places=12) + self.assertNotAlmostEqual(result[2][2], expected_22, places=12) + self.assertAlmostEqual(result[0][0], expected_00, places=5) + self.assertAlmostEqual(result[0][1], expected_01, places=5) + self.assertAlmostEqual(result[0][2], expected_02, places=5) + self.assertAlmostEqual(result[1][0], expected_10, places=5) + self.assertAlmostEqual(result[1][1], expected_11, places=5) + self.assertAlmostEqual(result[1][2], expected_12, places=5) + self.assertAlmostEqual(result[2][0], expected_20, places=5) + self.assertAlmostEqual(result[2][1], expected_21, places=5) + self.assertAlmostEqual(result[2][2], expected_22, places=5) + + result = wp.mul(wp.mat33h(*a_values), wp.float16(b_value)) + self.assertNotAlmostEqual(result[0][0], expected_00, places=5) + self.assertNotAlmostEqual(result[0][1], expected_01, places=5) + self.assertNotAlmostEqual(result[0][2], expected_02, places=5) + self.assertNotAlmostEqual(result[1][0], expected_10, places=5) + self.assertNotAlmostEqual(result[1][1], expected_11, places=5) + self.assertNotAlmostEqual(result[1][2], expected_12, places=5) + self.assertNotAlmostEqual(result[2][0], expected_20, places=5) + self.assertNotAlmostEqual(result[2][1], expected_21, places=5) + self.assertNotAlmostEqual(result[2][2], expected_22, places=5) + self.assertAlmostEqual(result[0][0], expected_00, places=1) + self.assertAlmostEqual(result[0][1], expected_01, places=1) + self.assertAlmostEqual(result[0][2], expected_02, places=1) + self.assertAlmostEqual(result[1][0], expected_10, places=1) + self.assertAlmostEqual(result[1][1], expected_11, places=1) + self.assertAlmostEqual(result[1][2], expected_12, places=1) + self.assertAlmostEqual(result[2][0], expected_20, places=1) + self.assertAlmostEqual(result[2][1], expected_21, places=1) + self.assertAlmostEqual(result[2][2], expected_22, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.mat33f(*a_values), wp.float32(b_value))) + self.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat33f(*a_values), wp.float32(b_value))) + + def test_mat44_float_args_precision(self): + a_values = ( + 1.23, + 2.34, + 3.45, + 4.56, + 5.67, + 6.78, + 7.89, + 8.90, + 9.01, + 10.12, + 11.23, + 12.34, + 13.45, + 14.56, + 15.67, + 16.78, ) + a_values_2d = (a_values[0:4], a_values[4:8], a_values[8:12], a_values[12:16]) + b_value = 0.12 + expected_00 = 0.14759999999999998122 + expected_01 = 0.28079999999999999405 + expected_02 = 0.41399999999999997913 + expected_03 = 0.54719999999999990870 + expected_10 = 0.68040000000000000480 + expected_11 = 0.81359999999999998987 + expected_12 = 0.94679999999999997495 + expected_13 = 1.06800000000000006040 + expected_20 = 1.08119999999999993889 + expected_21 = 1.21439999999999992397 + expected_22 = 1.34759999999999990905 + expected_23 = 1.48079999999999989413 + expected_30 = 1.61399999999999987921 + expected_31 = 1.74720000000000008633 + expected_32 = 1.88039999999999984936 + expected_33 = 2.01360000000000027853 + + result = wp.mul(wp.mat44d(*a_values), wp.float64(b_value)) + self.assertAlmostEqual(result[0][0], expected_00, places=12) + self.assertAlmostEqual(result[0][1], expected_01, places=12) + self.assertAlmostEqual(result[0][2], expected_02, places=12) + self.assertAlmostEqual(result[0][3], expected_03, places=12) + self.assertAlmostEqual(result[1][0], expected_10, places=12) + self.assertAlmostEqual(result[1][1], expected_11, places=12) + self.assertAlmostEqual(result[1][2], expected_12, places=12) + self.assertAlmostEqual(result[1][3], expected_13, places=12) + self.assertAlmostEqual(result[2][0], expected_20, places=12) + self.assertAlmostEqual(result[2][1], expected_21, places=12) + self.assertAlmostEqual(result[2][2], expected_22, places=12) + self.assertAlmostEqual(result[2][3], expected_23, places=12) + self.assertAlmostEqual(result[3][0], expected_30, places=12) + self.assertAlmostEqual(result[3][1], expected_31, places=12) + self.assertAlmostEqual(result[3][2], expected_32, places=12) + self.assertAlmostEqual(result[3][3], expected_33, places=12) + + result = wp.mul(wp.mat44f(*a_values), wp.float32(b_value)) + self.assertNotAlmostEqual(result[0][0], expected_00, places=12) + self.assertNotAlmostEqual(result[0][1], expected_01, places=12) + self.assertNotAlmostEqual(result[0][2], expected_02, places=12) + self.assertNotAlmostEqual(result[0][3], expected_03, places=12) + self.assertNotAlmostEqual(result[1][0], expected_10, places=12) + self.assertNotAlmostEqual(result[1][1], expected_11, places=12) + self.assertNotAlmostEqual(result[1][2], expected_12, places=12) + self.assertNotAlmostEqual(result[1][3], expected_13, places=12) + self.assertNotAlmostEqual(result[2][0], expected_20, places=12) + self.assertNotAlmostEqual(result[2][1], expected_21, places=12) + self.assertNotAlmostEqual(result[2][2], expected_22, places=12) + self.assertNotAlmostEqual(result[2][3], expected_23, places=12) + self.assertNotAlmostEqual(result[3][0], expected_30, places=12) + self.assertNotAlmostEqual(result[3][1], expected_31, places=12) + self.assertNotAlmostEqual(result[3][2], expected_32, places=12) + self.assertNotAlmostEqual(result[3][3], expected_33, places=12) + self.assertAlmostEqual(result[0][0], expected_00, places=5) + self.assertAlmostEqual(result[0][1], expected_01, places=5) + self.assertAlmostEqual(result[0][2], expected_02, places=5) + self.assertAlmostEqual(result[0][3], expected_03, places=5) + self.assertAlmostEqual(result[1][0], expected_10, places=5) + self.assertAlmostEqual(result[1][1], expected_11, places=5) + self.assertAlmostEqual(result[1][2], expected_12, places=5) + self.assertAlmostEqual(result[1][3], expected_13, places=5) + self.assertAlmostEqual(result[2][0], expected_20, places=5) + self.assertAlmostEqual(result[2][1], expected_21, places=5) + self.assertAlmostEqual(result[2][2], expected_22, places=5) + self.assertAlmostEqual(result[2][3], expected_23, places=5) + self.assertAlmostEqual(result[3][0], expected_30, places=5) + self.assertAlmostEqual(result[3][1], expected_31, places=5) + self.assertAlmostEqual(result[3][2], expected_32, places=5) + self.assertAlmostEqual(result[3][3], expected_33, places=5) + + result = wp.mul(wp.mat44h(*a_values), wp.float16(b_value)) + self.assertNotAlmostEqual(result[0][0], expected_00, places=5) + self.assertNotAlmostEqual(result[0][1], expected_01, places=5) + self.assertNotAlmostEqual(result[0][2], expected_02, places=5) + self.assertNotAlmostEqual(result[0][3], expected_03, places=5) + self.assertNotAlmostEqual(result[1][0], expected_10, places=5) + self.assertNotAlmostEqual(result[1][1], expected_11, places=5) + self.assertNotAlmostEqual(result[1][2], expected_12, places=5) + self.assertNotAlmostEqual(result[1][3], expected_13, places=5) + self.assertNotAlmostEqual(result[2][0], expected_20, places=5) + self.assertNotAlmostEqual(result[2][1], expected_21, places=5) + self.assertNotAlmostEqual(result[2][2], expected_22, places=5) + self.assertNotAlmostEqual(result[2][3], expected_23, places=5) + self.assertNotAlmostEqual(result[3][0], expected_30, places=5) + self.assertNotAlmostEqual(result[3][1], expected_31, places=5) + self.assertNotAlmostEqual(result[3][2], expected_32, places=5) + self.assertNotAlmostEqual(result[3][3], expected_33, places=5) + self.assertAlmostEqual(result[0][0], expected_00, places=1) + self.assertAlmostEqual(result[0][1], expected_01, places=1) + self.assertAlmostEqual(result[0][2], expected_02, places=1) + self.assertAlmostEqual(result[0][3], expected_03, places=1) + self.assertAlmostEqual(result[1][0], expected_10, places=1) + self.assertAlmostEqual(result[1][1], expected_11, places=1) + self.assertAlmostEqual(result[1][2], expected_12, places=1) + self.assertAlmostEqual(result[1][3], expected_13, places=1) + self.assertAlmostEqual(result[2][0], expected_20, places=1) + self.assertAlmostEqual(result[2][1], expected_21, places=1) + self.assertAlmostEqual(result[2][2], expected_22, places=1) + self.assertAlmostEqual(result[2][3], expected_23, places=1) + self.assertAlmostEqual(result[3][0], expected_30, places=1) + self.assertAlmostEqual(result[3][1], expected_31, places=1) + self.assertAlmostEqual(result[3][2], expected_32, places=1) + self.assertAlmostEqual(result[3][3], expected_33, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.mat44f(*a_values), wp.float32(b_value))) + self.assertEqual(wp.mul(a_values_2d, b_value), wp.mul(wp.mat44f(*a_values), wp.float32(b_value))) + + def test_vec2_arg_precision(self): + values = (1.23, 2.34) + expected = 2.64357712200722438922 + + result = wp.length(wp.vec2d(*values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.length(wp.vec2f(*values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.length(wp.vec2h(*values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.length(values), wp.length(wp.vec2f(*values))) + + def test_vec2_arg_overflow(self): + values = (-1234567890, -1234567890) + + self.assertEqual(wp.length_sq(wp.vec2b(*values)), -120) + self.assertEqual(wp.length_sq(wp.vec2s(*values)), -6008) + self.assertEqual(wp.length_sq(wp.vec2i(*values)), 608168072) + self.assertEqual(wp.length_sq(wp.vec2l(*values)), 3048315750038104200) + + self.assertEqual(wp.length_sq(wp.vec2ub(*values)), 136) + self.assertEqual(wp.length_sq(wp.vec2us(*values)), 59528) + self.assertEqual(wp.length_sq(wp.vec2ui(*values)), 608168072) + self.assertEqual(wp.length_sq(wp.vec2ul(*values)), 3048315750038104200) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec2i(*values))) + + def test_vec3_arg_precision(self): + values = (1.23, 2.34, 3.45) + expected = 4.34637780226247727455 + + result = wp.length(wp.vec3d(*values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.length(wp.vec3f(*values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.length(wp.vec3h(*values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.length(values), wp.length(wp.vec3f(*values))) + + def test_vec3_arg_overflow(self): + values = (-1234567890, -1234567890, -1234567890) + + self.assertEqual(wp.length_sq(wp.vec3b(*values)), -52) + self.assertEqual(wp.length_sq(wp.vec3s(*values)), -9012) + self.assertEqual(wp.length_sq(wp.vec3i(*values)), 912252108) + self.assertEqual(wp.length_sq(wp.vec3l(*values)), 4572473625057156300) + + self.assertEqual(wp.length_sq(wp.vec3ub(*values)), 204) + self.assertEqual(wp.length_sq(wp.vec3us(*values)), 56524) + self.assertEqual(wp.length_sq(wp.vec3ui(*values)), 912252108) + self.assertEqual(wp.length_sq(wp.vec3ul(*values)), 4572473625057156300) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec3i(*values))) + + def test_vec4_arg_precision(self): + values = (1.23, 2.34, 3.45, 4.56) + expected = 6.29957141399317777086 + + result = wp.length(wp.vec4d(*values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.length(wp.vec4f(*values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.length(wp.vec4h(*values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.length(values), wp.length(wp.vec4f(*values))) + + def test_vec4_arg_overflow(self): + values = (-1234567890, -1234567890, -1234567890, -1234567890) + + self.assertEqual(wp.length_sq(wp.vec4b(*values)), 16) + self.assertEqual(wp.length_sq(wp.vec4s(*values)), -12016) + self.assertEqual(wp.length_sq(wp.vec4i(*values)), 1216336144) + self.assertEqual(wp.length_sq(wp.vec4l(*values)), 6096631500076208400) + + self.assertEqual(wp.length_sq(wp.vec4ub(*values)), 16) + self.assertEqual(wp.length_sq(wp.vec4us(*values)), 53520) + self.assertEqual(wp.length_sq(wp.vec4ui(*values)), 1216336144) + self.assertEqual(wp.length_sq(wp.vec4ul(*values)), 6096631500076208400) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.length_sq(values), wp.length_sq(wp.vec4i(*values))) + + def test_vec2_vec2_args_precision(self): + a_values = (1.23, 2.34) + b_values = (3.45, 4.56) + expected = 14.91389999999999815827 + + result = wp.dot(wp.vec2d(*a_values), wp.vec2d(*b_values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.dot(wp.vec2f(*a_values), wp.vec2f(*b_values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.dot(wp.vec2h(*a_values), wp.vec2h(*b_values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec2f(*a_values), wp.vec2f(*b_values))) + + def test_vec2_vec2_args_overflow(self): + values = (-1234567890, -1234567890) + + self.assertEqual(wp.dot(wp.vec2b(*values), wp.vec2b(*values)), -120) + self.assertEqual(wp.dot(wp.vec2s(*values), wp.vec2s(*values)), -6008) + self.assertEqual(wp.dot(wp.vec2i(*values), wp.vec2i(*values)), 608168072) + self.assertEqual(wp.dot(wp.vec2l(*values), wp.vec2l(*values)), 3048315750038104200) + + self.assertEqual(wp.dot(wp.vec2ub(*values), wp.vec2ub(*values)), 136) + self.assertEqual(wp.dot(wp.vec2us(*values), wp.vec2us(*values)), 59528) + self.assertEqual(wp.dot(wp.vec2ui(*values), wp.vec2ui(*values)), 608168072) + self.assertEqual(wp.dot(wp.vec2ul(*values), wp.vec2ul(*values)), 3048315750038104200) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.dot(values, values), wp.dot(wp.vec2i(*values), wp.vec2i(*values))) + + def test_vec3_vec3_args_precision(self): + a_values = (1.23, 2.34, 3.45) + b_values = (4.56, 5.67, 6.78) + expected = 42.26760000000000161435 + + result = wp.dot(wp.vec3d(*a_values), wp.vec3d(*b_values)) + self.assertAlmostEqual(result, expected, places=12) - return TestBuiltinsResolution + result = wp.dot(wp.vec3f(*a_values), wp.vec3f(*b_values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.dot(wp.vec3h(*a_values), wp.vec3h(*b_values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec3f(*a_values), wp.vec3f(*b_values))) + + def test_vec3_vec3_args_overflow(self): + values = (-1234567890, -1234567890, -1234567890) + + self.assertEqual(wp.dot(wp.vec3b(*values), wp.vec3b(*values)), -52) + self.assertEqual(wp.dot(wp.vec3s(*values), wp.vec3s(*values)), -9012) + self.assertEqual(wp.dot(wp.vec3i(*values), wp.vec3i(*values)), 912252108) + self.assertEqual(wp.dot(wp.vec3l(*values), wp.vec3l(*values)), 4572473625057156300) + + self.assertEqual(wp.dot(wp.vec3ub(*values), wp.vec3ub(*values)), 204) + self.assertEqual(wp.dot(wp.vec3us(*values), wp.vec3us(*values)), 56524) + self.assertEqual(wp.dot(wp.vec3ui(*values), wp.vec3ui(*values)), 912252108) + self.assertEqual(wp.dot(wp.vec3ul(*values), wp.vec3ul(*values)), 4572473625057156300) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.dot(values, values), wp.dot(wp.vec3i(*values), wp.vec3i(*values))) + + def test_vec4_vec4_args_precision(self): + a_values = (1.23, 2.34, 3.45, 4.56) + b_values = (5.67, 6.78, 7.89, 8.90) + expected = 90.64379999999999881766 + + result = wp.dot(wp.vec4d(*a_values), wp.vec4d(*b_values)) + self.assertAlmostEqual(result, expected, places=12) + + result = wp.dot(wp.vec4f(*a_values), wp.vec4f(*b_values)) + self.assertNotAlmostEqual(result, expected, places=12) + self.assertAlmostEqual(result, expected, places=5) + + result = wp.dot(wp.vec4h(*a_values), wp.vec4h(*b_values)) + self.assertNotAlmostEqual(result, expected, places=5) + self.assertAlmostEqual(result, expected, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.dot(a_values, b_values), wp.dot(wp.vec4f(*a_values), wp.vec4f(*b_values))) + + def test_vec4_vec4_args_overflow(self): + values = (-1234567890, -1234567890, -1234567890, -1234567890) + + self.assertEqual(wp.dot(wp.vec4b(*values), wp.vec4b(*values)), 16) + self.assertEqual(wp.dot(wp.vec4s(*values), wp.vec4s(*values)), -12016) + self.assertEqual(wp.dot(wp.vec4i(*values), wp.vec4i(*values)), 1216336144) + self.assertEqual(wp.dot(wp.vec4l(*values), wp.vec4l(*values)), 6096631500076208400) + + self.assertEqual(wp.dot(wp.vec4ub(*values), wp.vec4ub(*values)), 16) + self.assertEqual(wp.dot(wp.vec4us(*values), wp.vec4us(*values)), 53520) + self.assertEqual(wp.dot(wp.vec4ui(*values), wp.vec4ui(*values)), 1216336144) + self.assertEqual(wp.dot(wp.vec4ul(*values), wp.vec4ul(*values)), 6096631500076208400) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.dot(values, values), wp.dot(wp.vec4i(*values), wp.vec4i(*values))) + + def test_vec2_float_args_precision(self): + a_values = (1.23, 2.34) + b_value = 3.45 + expected_x = 4.24350000000000004974 + expected_y = 8.07300000000000039790 + + result = wp.mul(wp.vec2d(*a_values), wp.float64(b_value)) + self.assertAlmostEqual(result[0], expected_x, places=12) + self.assertAlmostEqual(result[1], expected_y, places=12) + + result = wp.mul(wp.vec2f(*a_values), wp.float32(b_value)) + self.assertNotAlmostEqual(result[0], expected_x, places=12) + self.assertNotAlmostEqual(result[1], expected_y, places=12) + self.assertAlmostEqual(result[0], expected_x, places=5) + self.assertAlmostEqual(result[1], expected_y, places=5) + + result = wp.mul(wp.vec2h(*a_values), wp.float16(b_value)) + self.assertNotAlmostEqual(result[0], expected_x, places=5) + self.assertNotAlmostEqual(result[1], expected_y, places=5) + self.assertAlmostEqual(result[0], expected_x, places=1) + self.assertAlmostEqual(result[1], expected_y, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec2f(*a_values), wp.float32(b_value))) + + def test_vec3_float_args_precision(self): + a_values = (1.23, 2.34, 3.45) + b_value = 4.56 + expected_x = 5.60879999999999956373 + expected_y = 10.67039999999999899671 + expected_z = 15.73199999999999931788 + + result = wp.mul(wp.vec3d(*a_values), wp.float64(b_value)) + self.assertAlmostEqual(result[0], expected_x, places=12) + self.assertAlmostEqual(result[1], expected_y, places=12) + self.assertAlmostEqual(result[2], expected_z, places=12) + + result = wp.mul(wp.vec3f(*a_values), wp.float32(b_value)) + self.assertNotAlmostEqual(result[0], expected_x, places=12) + self.assertNotAlmostEqual(result[1], expected_y, places=12) + self.assertNotAlmostEqual(result[2], expected_z, places=12) + self.assertAlmostEqual(result[0], expected_x, places=5) + self.assertAlmostEqual(result[1], expected_y, places=5) + self.assertAlmostEqual(result[2], expected_z, places=5) + + result = wp.mul(wp.vec3h(*a_values), wp.float16(b_value)) + self.assertNotAlmostEqual(result[0], expected_x, places=5) + self.assertNotAlmostEqual(result[1], expected_y, places=5) + self.assertNotAlmostEqual(result[2], expected_z, places=5) + self.assertAlmostEqual(result[0], expected_x, places=1) + self.assertAlmostEqual(result[1], expected_y, places=1) + self.assertAlmostEqual(result[2], expected_z, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec3f(*a_values), wp.float32(b_value))) + + def test_vec4_float_args_precision(self): + a_values = (1.23, 2.34, 3.45, 4.56) + b_value = 5.67 + expected_x = 6.97409999999999996589 + expected_y = 13.26779999999999937188 + expected_z = 19.56150000000000233058 + expected_w = 25.85519999999999640750 + + result = wp.mul(wp.vec4d(*a_values), wp.float64(b_value)) + self.assertAlmostEqual(result[0], expected_x, places=12) + self.assertAlmostEqual(result[1], expected_y, places=12) + self.assertAlmostEqual(result[2], expected_z, places=12) + self.assertAlmostEqual(result[3], expected_w, places=12) + + result = wp.mul(wp.vec4f(*a_values), wp.float32(b_value)) + self.assertNotAlmostEqual(result[0], expected_x, places=12) + self.assertNotAlmostEqual(result[1], expected_y, places=12) + self.assertNotAlmostEqual(result[2], expected_z, places=12) + self.assertNotAlmostEqual(result[3], expected_w, places=12) + self.assertAlmostEqual(result[0], expected_x, places=5) + self.assertAlmostEqual(result[1], expected_y, places=5) + self.assertAlmostEqual(result[2], expected_z, places=5) + self.assertAlmostEqual(result[3], expected_w, places=5) + + result = wp.mul(wp.vec4h(*a_values), wp.float16(b_value)) + self.assertNotAlmostEqual(result[0], expected_x, places=5) + self.assertNotAlmostEqual(result[1], expected_y, places=5) + self.assertNotAlmostEqual(result[2], expected_z, places=5) + self.assertNotAlmostEqual(result[3], expected_w, places=5) + self.assertAlmostEqual(result[0], expected_x, places=1) + self.assertAlmostEqual(result[1], expected_y, places=1) + self.assertAlmostEqual(result[2], expected_z, places=1) + self.assertAlmostEqual(result[3], expected_w, places=1) + + with open(os.devnull, "w") as f, contextlib.redirect_stdout(f): + self.assertEqual(wp.mul(a_values, b_value), wp.mul(wp.vec4f(*a_values), wp.float32(b_value))) + + +for dtype in wp.types.int_types: + add_function_test( + TestBuiltinsResolution, + f"test_int_arg_support_{dtype.__name__}", + test_int_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_int_int_args_support_{dtype.__name__}", + test_int_int_args_support, + dtype=dtype, + ) + +for dtype in wp.types.float_types: + add_function_test( + TestBuiltinsResolution, + f"test_float_arg_support_{dtype.__name__}", + test_float_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_mat_arg_support_{dtype.__name__}", + test_mat_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_mat_mat_args_support_{dtype.__name__}", + test_mat_mat_args_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_mat_float_args_support_{dtype.__name__}", + test_mat_float_args_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_vec_arg_support_{dtype.__name__}", + test_vec_arg_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_vec_vec_args_support_{dtype.__name__}", + test_vec_vec_args_support, + dtype=dtype, + ) + add_function_test( + TestBuiltinsResolution, + f"test_vec_float_args_support_{dtype.__name__}", + test_vec_float_args_support, + dtype=dtype, + ) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_bvh.py b/warp/tests/test_bvh.py index a67e56dfb..d749b9a37 100644 --- a/warp/tests/test_bvh.py +++ b/warp/tests/test_bvh.py @@ -10,8 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() @@ -118,8 +117,8 @@ def test_bvh(test, type, device): if test_case == 0: lowers = rng.random(size=(num_bounds, 3)) * 5.0 uppers = lowers + rng.random(size=(num_bounds, 3)) * 5.0 - wp.copy(device_lowers, wp.array(lowers, dtype=wp.vec3)) - wp.copy(device_uppers, wp.array(uppers, dtype=wp.vec3)) + wp.copy(device_lowers, wp.array(lowers, dtype=wp.vec3, device=device)) + wp.copy(device_uppers, wp.array(uppers, dtype=wp.vec3, device=device)) bvh.refit() bounds_intersected.zero_() @@ -132,19 +131,17 @@ def test_bvh_query_ray(test, device): test_bvh(test, "ray", device) -def register(parent): - devices = get_test_devices() +devices = get_test_devices(mode="basic") # TODO: Fix the illegal address error when two CUDA devices are used + - class TestBvh(parent): - pass +class TestBvh(unittest.TestCase): + pass - add_function_test(TestBvh, "test_bvh_aabb", test_bvh_query_aabb, devices=devices) - add_function_test(TestBvh, "test_bvh_ray", test_bvh_query_ray, devices=devices) - return TestBvh +add_function_test(TestBvh, "test_bvh_aabb", test_bvh_query_aabb, devices=devices) +add_function_test(TestBvh, "test_bvh_ray", test_bvh_query_ray, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_closest_point_edge_edge.py b/warp/tests/test_closest_point_edge_edge.py index 8762421b3..0c0f4a415 100644 --- a/warp/tests/test_closest_point_edge_edge.py +++ b/warp/tests/test_closest_point_edge_edge.py @@ -5,12 +5,12 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import numpy as np - import unittest +import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() epsilon = 0.00001 @@ -171,62 +171,58 @@ def test_edge_edge_perpendicular_s0_t1(test, device): test.assertAlmostEqual(st0[1], 1.0) # t value -def register(parent): - devices = get_test_devices() - - class TestClosestPointEdgeEdgeMethods(parent): - pass - - add_function_test( - TestClosestPointEdgeEdgeMethods, - "test_edge_edge_middle_crossing", - test_edge_edge_middle_crossing, - devices=devices, - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, "test_edge_edge_parallel_s1_t0", test_edge_edge_parallel_s1_t0, devices=devices - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, "test_edge_edge_parallel_s0_t1", test_edge_edge_parallel_s0_t1, devices=devices - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, - "test_edge_edge_both_degenerate_case", - test_edge_edge_both_degenerate_case, - devices=devices, - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, - "test_edge_edge_degenerate_first_edge", - test_edge_edge_degenerate_first_edge, - devices=devices, - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, - "test_edge_edge_degenerate_second_edge", - test_edge_edge_degenerate_second_edge, - devices=devices, - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, "test_edge_edge_parallel", test_edge_edge_parallel, devices=devices - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, - "test_edge_edge_perpendicular_s1_t0", - test_edge_edge_perpendicular_s1_t0, - devices=devices, - ) - add_function_test( - TestClosestPointEdgeEdgeMethods, - "test_edge_edge_perpendicular_s0_t1", - test_edge_edge_perpendicular_s0_t1, - devices=devices, - ) - - return TestClosestPointEdgeEdgeMethods +devices = get_test_devices() + + +class TestClosestPointEdgeEdgeMethods(unittest.TestCase): + pass + + +add_function_test( + TestClosestPointEdgeEdgeMethods, + "test_edge_edge_middle_crossing", + test_edge_edge_middle_crossing, + devices=devices, +) +add_function_test( + TestClosestPointEdgeEdgeMethods, "test_edge_edge_parallel_s1_t0", test_edge_edge_parallel_s1_t0, devices=devices +) +add_function_test( + TestClosestPointEdgeEdgeMethods, "test_edge_edge_parallel_s0_t1", test_edge_edge_parallel_s0_t1, devices=devices +) +add_function_test( + TestClosestPointEdgeEdgeMethods, + "test_edge_edge_both_degenerate_case", + test_edge_edge_both_degenerate_case, + devices=devices, +) +add_function_test( + TestClosestPointEdgeEdgeMethods, + "test_edge_edge_degenerate_first_edge", + test_edge_edge_degenerate_first_edge, + devices=devices, +) +add_function_test( + TestClosestPointEdgeEdgeMethods, + "test_edge_edge_degenerate_second_edge", + test_edge_edge_degenerate_second_edge, + devices=devices, +) +add_function_test(TestClosestPointEdgeEdgeMethods, "test_edge_edge_parallel", test_edge_edge_parallel, devices=devices) +add_function_test( + TestClosestPointEdgeEdgeMethods, + "test_edge_edge_perpendicular_s1_t0", + test_edge_edge_perpendicular_s1_t0, + devices=devices, +) +add_function_test( + TestClosestPointEdgeEdgeMethods, + "test_edge_edge_perpendicular_s0_t1", + test_edge_edge_perpendicular_s0_t1, + devices=devices, +) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_codegen.py b/warp/tests/test_codegen.py index a078e5e76..958e83c22 100644 --- a/warp/tests/test_codegen.py +++ b/warp/tests/test_codegen.py @@ -5,12 +5,11 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path import sys import unittest import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * # wp.config.mode = "debug" @@ -346,7 +345,7 @@ def test_range_expression(): def test_unresolved_func(test, device): # kernel with unresolved function must be in a separate module, otherwise the current module would fail to load - from warp.tests.test_unresolved_func import unresolved_func_kernel + from warp.tests.aux_test_unresolved_func import unresolved_func_kernel # ensure that an appropriate exception is raised when the bad module gets loaded with test.assertRaisesRegex(RuntimeError, "Could not find function wp.missing_func"): @@ -354,13 +353,13 @@ def test_unresolved_func(test, device): # remove all references to the bad module so that subsequent calls to wp.force_load() # won't try to load it unless we explicitly re-import it again - del wp.context.user_modules["warp.tests.test_unresolved_func"] - del sys.modules["warp.tests.test_unresolved_func"] + del wp.context.user_modules["warp.tests.aux_test_unresolved_func"] + del sys.modules["warp.tests.aux_test_unresolved_func"] def test_unresolved_symbol(test, device): # kernel with unresolved symbol must be in a separate module, otherwise the current module would fail to load - from warp.tests.test_unresolved_symbol import unresolved_symbol_kernel + from warp.tests.aux_test_unresolved_symbol import unresolved_symbol_kernel # ensure that an appropriate exception is raised when the bad module gets loaded with test.assertRaisesRegex(KeyError, "Referencing undefined symbol: missing_symbol"): @@ -368,143 +367,140 @@ def test_unresolved_symbol(test, device): # remove all references to the bad module so that subsequent calls to wp.force_load() # won't try to load it unless we explicitly re-import it again - del wp.context.user_modules["warp.tests.test_unresolved_symbol"] - del sys.modules["warp.tests.test_unresolved_symbol"] - - -def register(parent): - class TestCodeGen(parent): - pass - - devices = get_test_devices() - - add_kernel_test(TestCodeGen, name="test_inplace", kernel=test_inplace, dim=1, devices=devices) - add_kernel_test(TestCodeGen, name="test_rename", kernel=test_rename, dim=1, devices=devices) - add_kernel_test(TestCodeGen, name="test_constant", kernel=test_constant, inputs=[1.0], dim=1, devices=devices) - add_kernel_test( - TestCodeGen, name="test_dynamic_for_rename", kernel=test_dynamic_for_rename, inputs=[10], dim=1, devices=devices - ) - add_kernel_test( - TestCodeGen, - name="test_dynamic_for_inplace", - kernel=test_dynamic_for_inplace, - inputs=[10], - dim=1, - devices=devices, - ) - add_kernel_test(TestCodeGen, name="test_reassign", kernel=test_reassign, dim=1, devices=devices) - add_kernel_test( - TestCodeGen, name="test_dynamic_reassign", kernel=test_dynamic_reassign, inputs=[2], dim=1, devices=devices - ) - - add_kernel_test( - TestCodeGen, - name="test_range_dynamic_forward", - kernel=test_range_dynamic, - dim=1, - inputs=[0, 4, 1], - expect=[0, 1, 2, 3], - devices=devices, - ) - add_kernel_test( - TestCodeGen, - name="test_range_dynamic_reverse", - kernel=test_range_dynamic, - dim=1, - inputs=[4, 0, -1], - expect=[4, 3, 2, 1], - devices=devices, - ) - add_kernel_test( - TestCodeGen, - name="test_range_dynamic_foward_step", - kernel=test_range_dynamic, - dim=1, - inputs=[0, 8, 2], - expect=[0, 2, 4, 6], - devices=devices, - ) - add_kernel_test( - TestCodeGen, - name="test_range_dynamic_reverse_step", - kernel=test_range_dynamic, - dim=1, - inputs=[8, 0, -2], - expect=[8, 6, 4, 2], - devices=devices, - ) - - add_kernel_test( - TestCodeGen, - name="test_range_static_sum", - kernel=test_range_static_sum, - dim=1, - expect=[10, 10, 10], - devices=devices, - ) - add_kernel_test( - TestCodeGen, - name="test_range_dynamic_sum", - kernel=test_range_dynamic_sum, - dim=1, - inputs=[0, 10, 2], - expect=[10, 10, 10, 10], - devices=devices, - ) - add_kernel_test( - TestCodeGen, - name="test_range_dynamic_sum_zero", - kernel=test_range_dynamic_sum, - dim=1, - inputs=[0, 0, 1], - expect=[0, 0, 0, 0], - devices=devices, - ) - add_kernel_test(TestCodeGen, name="test_range_constant", kernel=test_range_constant, dim=1, devices=devices) - add_kernel_test( - TestCodeGen, - name="test_range_constant_dynamic_nested", - kernel=test_range_constant_dynamic_nested, - dim=1, - inputs=[10], - devices=devices, - ) - add_kernel_test( - TestCodeGen, - name="test_range_dynamic_nested", - kernel=test_range_dynamic_nested, - dim=1, - inputs=[4], - devices=devices, - ) - add_kernel_test( - TestCodeGen, - name="test_range_expression", - kernel=test_range_expression, - dim=1, - devices=devices, - ) - - add_kernel_test(TestCodeGen, name="test_while_zero", kernel=test_while, dim=1, inputs=[0], devices=devices) - add_kernel_test(TestCodeGen, name="test_while_positive", kernel=test_while, dim=1, inputs=[16], devices=devices) - add_kernel_test(TestCodeGen, name="test_pass", kernel=test_pass, dim=1, inputs=[16], devices=devices) - - add_kernel_test(TestCodeGen, name="test_break", kernel=test_break, dim=1, inputs=[10], devices=devices) - add_kernel_test(TestCodeGen, name="test_break_early", kernel=test_break_early, dim=1, inputs=[10], devices=devices) - add_kernel_test(TestCodeGen, name="test_break_unroll", kernel=test_break_unroll, dim=1, devices=devices) - add_kernel_test( - TestCodeGen, name="test_break_multiple", kernel=test_break_multiple, dim=1, inputs=[10], devices=devices - ) - add_kernel_test(TestCodeGen, name="test_continue", kernel=test_continue, dim=1, inputs=[10], devices=devices) - add_kernel_test(TestCodeGen, name="test_continue_unroll", kernel=test_continue_unroll, dim=1, devices=devices) - - add_function_test(TestCodeGen, func=test_unresolved_func, name="test_unresolved_func", devices=devices) - add_function_test(TestCodeGen, func=test_unresolved_symbol, name="test_unresolved_symbol", devices=devices) - - return TestCodeGen + del wp.context.user_modules["warp.tests.aux_test_unresolved_symbol"] + del sys.modules["warp.tests.aux_test_unresolved_symbol"] + + +class TestCodeGen(unittest.TestCase): + pass + + +devices = get_test_devices() + +add_kernel_test(TestCodeGen, name="test_inplace", kernel=test_inplace, dim=1, devices=devices) +add_kernel_test(TestCodeGen, name="test_rename", kernel=test_rename, dim=1, devices=devices) +add_kernel_test(TestCodeGen, name="test_constant", kernel=test_constant, inputs=[1.0], dim=1, devices=devices) +add_kernel_test( + TestCodeGen, name="test_dynamic_for_rename", kernel=test_dynamic_for_rename, inputs=[10], dim=1, devices=devices +) +add_kernel_test( + TestCodeGen, + name="test_dynamic_for_inplace", + kernel=test_dynamic_for_inplace, + inputs=[10], + dim=1, + devices=devices, +) +add_kernel_test(TestCodeGen, name="test_reassign", kernel=test_reassign, dim=1, devices=devices) +add_kernel_test( + TestCodeGen, name="test_dynamic_reassign", kernel=test_dynamic_reassign, inputs=[2], dim=1, devices=devices +) + +add_kernel_test( + TestCodeGen, + name="test_range_dynamic_forward", + kernel=test_range_dynamic, + dim=1, + inputs=[0, 4, 1], + expect=[0, 1, 2, 3], + devices=devices, +) +add_kernel_test( + TestCodeGen, + name="test_range_dynamic_reverse", + kernel=test_range_dynamic, + dim=1, + inputs=[4, 0, -1], + expect=[4, 3, 2, 1], + devices=devices, +) +add_kernel_test( + TestCodeGen, + name="test_range_dynamic_forward_step", + kernel=test_range_dynamic, + dim=1, + inputs=[0, 8, 2], + expect=[0, 2, 4, 6], + devices=devices, +) +add_kernel_test( + TestCodeGen, + name="test_range_dynamic_reverse_step", + kernel=test_range_dynamic, + dim=1, + inputs=[8, 0, -2], + expect=[8, 6, 4, 2], + devices=devices, +) + +add_kernel_test( + TestCodeGen, + name="test_range_static_sum", + kernel=test_range_static_sum, + dim=1, + expect=[10, 10, 10], + devices=devices, +) +add_kernel_test( + TestCodeGen, + name="test_range_dynamic_sum", + kernel=test_range_dynamic_sum, + dim=1, + inputs=[0, 10, 2], + expect=[10, 10, 10, 10], + devices=devices, +) +add_kernel_test( + TestCodeGen, + name="test_range_dynamic_sum_zero", + kernel=test_range_dynamic_sum, + dim=1, + inputs=[0, 0, 1], + expect=[0, 0, 0, 0], + devices=devices, +) +add_kernel_test(TestCodeGen, name="test_range_constant", kernel=test_range_constant, dim=1, devices=devices) +add_kernel_test( + TestCodeGen, + name="test_range_constant_dynamic_nested", + kernel=test_range_constant_dynamic_nested, + dim=1, + inputs=[10], + devices=devices, +) +add_kernel_test( + TestCodeGen, + name="test_range_dynamic_nested", + kernel=test_range_dynamic_nested, + dim=1, + inputs=[4], + devices=devices, +) +add_kernel_test( + TestCodeGen, + name="test_range_expression", + kernel=test_range_expression, + dim=1, + devices=devices, +) + +add_kernel_test(TestCodeGen, name="test_while_zero", kernel=test_while, dim=1, inputs=[0], devices=devices) +add_kernel_test(TestCodeGen, name="test_while_positive", kernel=test_while, dim=1, inputs=[16], devices=devices) +add_kernel_test(TestCodeGen, name="test_pass", kernel=test_pass, dim=1, inputs=[16], devices=devices) + +add_kernel_test(TestCodeGen, name="test_break", kernel=test_break, dim=1, inputs=[10], devices=devices) +add_kernel_test(TestCodeGen, name="test_break_early", kernel=test_break_early, dim=1, inputs=[10], devices=devices) +add_kernel_test(TestCodeGen, name="test_break_unroll", kernel=test_break_unroll, dim=1, devices=devices) +add_kernel_test( + TestCodeGen, name="test_break_multiple", kernel=test_break_multiple, dim=1, inputs=[10], devices=devices +) +add_kernel_test(TestCodeGen, name="test_continue", kernel=test_continue, dim=1, inputs=[10], devices=devices) +add_kernel_test(TestCodeGen, name="test_continue_unroll", kernel=test_continue_unroll, dim=1, devices=devices) + +add_function_test(TestCodeGen, func=test_unresolved_func, name="test_unresolved_func", devices=devices) +add_function_test(TestCodeGen, func=test_unresolved_symbol, name="test_unresolved_symbol", devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_compile_consts.py b/warp/tests/test_compile_consts.py index a98c0dfe6..d7e2ec400 100644 --- a/warp/tests/test_compile_consts.py +++ b/warp/tests/test_compile_consts.py @@ -5,14 +5,11 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import os -import sys - import unittest -from warp.tests.test_base import * -import warp.tests.test_compile_consts_dummy import warp as wp +import warp.tests.aux_test_compile_consts_dummy +from warp.tests.unittest_utils import * wp.init() @@ -40,7 +37,7 @@ def test_constants_bool(): @wp.kernel def test_constants_int(a: int): if Foobar.ONE > 0: - a = 123 + Foobar.TWO + warp.tests.test_compile_consts_dummy.MINUS_ONE + a = 123 + Foobar.TWO + warp.tests.aux_test_compile_consts_dummy.MINUS_ONE else: a = 456 + LOCAL_ONE expect_eq(a, 124) @@ -82,26 +79,23 @@ def closure_kernel_fn(expected: int): wp.launch(two_closure, dim=(1), inputs=[2], device=device) -def register(parent): - class TestConstants(parent): - pass +class TestConstants(unittest.TestCase): + pass - a = 0 - x = 0.0 - devices = get_test_devices() +a = 0 +x = 0.0 - add_kernel_test(TestConstants, test_constants_bool, dim=1, inputs=[], devices=devices) - add_kernel_test(TestConstants, test_constants_int, dim=1, inputs=[a], devices=devices) - add_kernel_test(TestConstants, test_constants_float, dim=1, inputs=[x], devices=devices) +devices = get_test_devices() - add_function_test(TestConstants, "test_constant_math", test_constant_math, devices=devices) - add_function_test(TestConstants, "test_constant_closure_capture", test_constant_closure_capture, devices=devices) +add_kernel_test(TestConstants, test_constants_bool, dim=1, inputs=[], devices=devices) +add_kernel_test(TestConstants, test_constants_int, dim=1, inputs=[a], devices=devices) +add_kernel_test(TestConstants, test_constants_float, dim=1, inputs=[x], devices=devices) - return TestConstants +add_function_test(TestConstants, "test_constant_math", test_constant_math, devices=devices) +add_function_test(TestConstants, "test_constant_closure_capture", test_constant_closure_capture, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_conditional.py b/warp/tests/test_conditional.py index b0a1aaa9c..b9c7f081b 100644 --- a/warp/tests/test_conditional.py +++ b/warp/tests/test_conditional.py @@ -8,7 +8,7 @@ import unittest import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -203,46 +203,44 @@ def test_conditional_chain_mixed(): def test_conditional_unequal_types(test: unittest.TestCase, device): # The bad kernel must be in a separate module, otherwise the current module would fail to load - from warp.tests.test_conditional_unequal_types_kernels import unequal_types_kernel + from warp.tests.aux_test_conditional_unequal_types_kernels import ( + unequal_types_kernel, + ) with test.assertRaises(TypeError): wp.launch(unequal_types_kernel, dim=(1,), inputs=[], device=device) # remove all references to the bad module so that subsequent calls to wp.force_load() # won't try to load it unless we explicitly re-import it again - del wp.context.user_modules["warp.tests.test_conditional_unequal_types_kernels"] - del sys.modules["warp.tests.test_conditional_unequal_types_kernels"] - - -def register(parent): - devices = get_test_devices() - - class TestConditional(parent): - pass - - add_kernel_test(TestConditional, kernel=test_conditional_if_else, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_conditional_if_else_nested, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_boolean_and, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_boolean_or, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_boolean_compound, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_boolean_literal, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_int_logical_not, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_int_conditional_assign_overload, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_bool_param_conditional, dim=1, inputs=[True], devices=devices) - add_kernel_test(TestConditional, kernel=test_conditional_chain_basic, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_conditional_chain_empty_range, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_conditional_chain_faker, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_conditional_chain_and, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_conditional_chain_eqs, dim=1, devices=devices) - add_kernel_test(TestConditional, kernel=test_conditional_chain_mixed, dim=1, devices=devices) - add_function_test( - TestConditional, "test_conditional_unequal_types", test_conditional_unequal_types, devices=devices - ) + del wp.context.user_modules["warp.tests.aux_test_conditional_unequal_types_kernels"] + del sys.modules["warp.tests.aux_test_conditional_unequal_types_kernels"] + + +devices = get_test_devices() + + +class TestConditional(unittest.TestCase): + pass + - return TestConditional +add_kernel_test(TestConditional, kernel=test_conditional_if_else, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_conditional_if_else_nested, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_boolean_and, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_boolean_or, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_boolean_compound, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_boolean_literal, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_int_logical_not, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_int_conditional_assign_overload, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_bool_param_conditional, dim=1, inputs=[True], devices=devices) +add_kernel_test(TestConditional, kernel=test_conditional_chain_basic, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_conditional_chain_empty_range, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_conditional_chain_faker, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_conditional_chain_and, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_conditional_chain_eqs, dim=1, devices=devices) +add_kernel_test(TestConditional, kernel=test_conditional_chain_mixed, dim=1, devices=devices) +add_function_test(TestConditional, "test_conditional_unequal_types", test_conditional_unequal_types, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_conditional_unequal_types_kernels.py b/warp/tests/test_conditional_unequal_types_kernels.py deleted file mode 100644 index c2d16f6d5..000000000 --- a/warp/tests/test_conditional_unequal_types_kernels.py +++ /dev/null @@ -1,14 +0,0 @@ -# This file defines a kernel that fails on codegen.py - -import warp as wp - - -@wp.kernel -def unequal_types_kernel(): - x = wp.int32(10) - y = 10 - z = True - - # Throws a TypeError - if x == y == z: - pass diff --git a/warp/tests/test_copy.py b/warp/tests/test_copy.py index 1b956a25b..63942ef46 100644 --- a/warp/tests/test_copy.py +++ b/warp/tests/test_copy.py @@ -5,13 +5,12 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path +import unittest + import numpy as np import warp as wp -from warp.tests.test_base import * - -import unittest +from warp.tests.unittest_utils import * wp.init() @@ -200,19 +199,17 @@ def test_copy_indexed(test, device): assert_np_equal(a4.numpy(), expected4 * s) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestCopy(parent): - pass +class TestCopy(unittest.TestCase): + pass - add_function_test(TestCopy, "test_copy_strided", test_copy_strided, devices=devices) - add_function_test(TestCopy, "test_copy_indexed", test_copy_indexed, devices=devices) - return TestCopy +add_function_test(TestCopy, "test_copy_strided", test_copy_strided, devices=devices) +add_function_test(TestCopy, "test_copy_indexed", test_copy_indexed, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_coverage.py b/warp/tests/test_coverage.py deleted file mode 100644 index 8ffb6d410..000000000 --- a/warp/tests/test_coverage.py +++ /dev/null @@ -1,38 +0,0 @@ -import os - -import coverage - -cover = coverage.Coverage( - source=["warp", "warp.sim", "warp.render"], - omit=[ - "build*.py", - "copyright.py", - "setup.py", - os.path.join("warp", "stubs.py"), - os.path.join("warp", "tests", "*.py"), - os.path.join("warp", "thirdparty", "appdirs.py"), - os.path.join("warp", "fem", "**", "*.py"), - os.path.join("warp", "render", "render_opengl.py"), - ], -) - -cover.config.disable_warnings = [ - "module-not-measured", - "module-not-imported", - "no-data-collected", - "couldnt-parse", -] - -cover.exclude("@wp") -cover.exclude("@warp") -cover.start() - -import test_all # noqa: E402 - -test_all.run() - - -cover.stop() -cover.save() - -cover.html_report() diff --git a/warp/tests/test_ctypes.py b/warp/tests/test_ctypes.py index 9717f3496..660ef8f01 100644 --- a/warp/tests/test_ctypes.py +++ b/warp/tests/test_ctypes.py @@ -5,14 +5,12 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path +import unittest + import numpy as np -import math import warp as wp -from warp.tests.test_base import * - -import unittest +from warp.tests.unittest_utils import * wp.init() @@ -556,89 +554,79 @@ def test_transform_matrix(): wp.expect_near(r_2, r_0 - t, 1.0e-4) -def register(parent): - devices = get_test_devices() - - class TestCTypes(parent): - pass - - inputs = [ - wp.vec2(1.0, 2.0), - wp.vec3(1.0, 2.0, 3.0), - wp.vec4(1.0, 2.0, 3.0, 4.0), - wp.mat22(1.0, 2.0, 3.0, 4.0), - wp.mat33(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0), - wp.mat44(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0, 13.0, 14.0, 15.0, 16.0), - ] - - add_function_test(TestCTypes, "test_mat22", test_mat22, devices=devices) - add_function_test(TestCTypes, "test_mat33", test_mat33, devices=devices) - add_function_test(TestCTypes, "test_mat44", test_mat44, devices=devices) - add_kernel_test( - TestCTypes, - name="test_transformation_constructor", - kernel=test_transformation_constructor, - dim=1, - devices=devices, - ) - add_kernel_test( - TestCTypes, - name="test_spatial_vector_constructor", - kernel=test_spatial_vector_constructor, - dim=1, - devices=devices, - ) - add_kernel_test( - TestCTypes, - name="test_scalar_arg_types", - kernel=test_scalar_arg_types, - dim=1, - inputs=[-64, 255, -64, 255, -64, 255, -64, 255, 3.14159, 3.14159], - devices=devices, - ) - add_kernel_test( - TestCTypes, - name="test_scalar_arg_types_explicit", - kernel=test_scalar_arg_types, - dim=1, - inputs=[ - wp.int8(-64), - wp.uint8(255), - wp.int16(-64), - wp.uint16(255), - wp.int32(-64), - wp.uint32(255), - wp.int64(-64), - wp.uint64(255), - wp.float32(3.14159), - wp.float64(3.14159), - ], - devices=devices, - ) - add_kernel_test( - TestCTypes, name="test_vector_arg_types", kernel=test_vector_arg_types, dim=1, inputs=inputs, devices=devices - ) - add_kernel_test(TestCTypes, name="test_type_convesrions", kernel=test_type_conversions, dim=1, devices=devices) - - add_function_test( - TestCTypes, "test_scalar_array_load", test_scalar_array_types, devices=devices, load=True, store=False - ) - add_function_test( - TestCTypes, "test_scalar_array_store", test_scalar_array_types, devices=devices, load=False, store=True - ) - add_function_test(TestCTypes, "test_vec2_arg", test_vec2_arg, devices=devices, n=8) - add_function_test(TestCTypes, "test_vec2_transform", test_vec2_transform, devices=devices, n=8) - add_function_test(TestCTypes, "test_vec3_arg", test_vec3_arg, devices=devices, n=8) - add_function_test(TestCTypes, "test_vec3_transform", test_vec3_transform, devices=devices, n=8) - add_function_test(TestCTypes, "test_transform_multiply", test_transform_multiply, devices=devices, n=8) - add_kernel_test(TestCTypes, name="test_transform_matrix", kernel=test_transform_matrix, dim=1, devices=devices) - add_function_test(TestCTypes, "test_scalar_array", test_scalar_array, devices=devices) - add_function_test(TestCTypes, "test_vector_array", test_vector_array, devices=devices) - - return TestCTypes +devices = get_test_devices() + + +class TestCTypes(unittest.TestCase): + pass + + +inputs = [ + wp.vec2(1.0, 2.0), + wp.vec3(1.0, 2.0, 3.0), + wp.vec4(1.0, 2.0, 3.0, 4.0), + wp.mat22(1.0, 2.0, 3.0, 4.0), + wp.mat33(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0), + wp.mat44(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0, 11.0, 12.0, 13.0, 14.0, 15.0, 16.0), +] + +add_function_test(TestCTypes, "test_mat22", test_mat22, devices=devices) +add_function_test(TestCTypes, "test_mat33", test_mat33, devices=devices) +add_function_test(TestCTypes, "test_mat44", test_mat44, devices=devices) +add_kernel_test( + TestCTypes, name="test_transformation_constructor", kernel=test_transformation_constructor, dim=1, devices=devices +) +add_kernel_test( + TestCTypes, name="test_spatial_vector_constructor", kernel=test_spatial_vector_constructor, dim=1, devices=devices +) +add_kernel_test( + TestCTypes, + name="test_scalar_arg_types", + kernel=test_scalar_arg_types, + dim=1, + inputs=[-64, 255, -64, 255, -64, 255, -64, 255, 3.14159, 3.14159], + devices=devices, +) +add_kernel_test( + TestCTypes, + name="test_scalar_arg_types_explicit", + kernel=test_scalar_arg_types, + dim=1, + inputs=[ + wp.int8(-64), + wp.uint8(255), + wp.int16(-64), + wp.uint16(255), + wp.int32(-64), + wp.uint32(255), + wp.int64(-64), + wp.uint64(255), + wp.float32(3.14159), + wp.float64(3.14159), + ], + devices=devices, +) +add_kernel_test( + TestCTypes, name="test_vector_arg_types", kernel=test_vector_arg_types, dim=1, inputs=inputs, devices=devices +) +add_kernel_test(TestCTypes, name="test_type_convesrions", kernel=test_type_conversions, dim=1, devices=devices) + +add_function_test( + TestCTypes, "test_scalar_array_load", test_scalar_array_types, devices=devices, load=True, store=False +) +add_function_test( + TestCTypes, "test_scalar_array_store", test_scalar_array_types, devices=devices, load=False, store=True +) +add_function_test(TestCTypes, "test_vec2_arg", test_vec2_arg, devices=devices, n=8) +add_function_test(TestCTypes, "test_vec2_transform", test_vec2_transform, devices=devices, n=8) +add_function_test(TestCTypes, "test_vec3_arg", test_vec3_arg, devices=devices, n=8) +add_function_test(TestCTypes, "test_vec3_transform", test_vec3_transform, devices=devices, n=8) +add_function_test(TestCTypes, "test_transform_multiply", test_transform_multiply, devices=devices, n=8) +add_kernel_test(TestCTypes, name="test_transform_matrix", kernel=test_transform_matrix, dim=1, devices=devices) +add_function_test(TestCTypes, "test_scalar_array", test_scalar_array, devices=devices) +add_function_test(TestCTypes, "test_vector_array", test_vector_array, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_dense.py b/warp/tests/test_dense.py index 0841bb1a3..a489d52e5 100644 --- a/warp/tests/test_dense.py +++ b/warp/tests/test_dense.py @@ -1,11 +1,15 @@ -import numpy as np -import math - -import warp as wp -from warp.tests.test_base import * +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. import unittest +import warp as wp +from warp.tests.unittest_utils import * + wp.init() @@ -42,20 +46,22 @@ def eval_dense_solve( wp.dense_solve(n, A, L, b, x) -def register(parent): - devices = get_test_devices() - - class TestDense(parent): - pass - +def test_dense_compilation(test, device): # just testing compilation of the dense matrix routines # most are deprecated / WIP - wp.force_load() + wp.load_module(device=device) + + +devices = get_test_devices() + + +class TestDense(unittest.TestCase): + pass + - return TestDense +add_function_test(TestDense, "test_dense_compilation", test_dense_compilation, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_devices.py b/warp/tests/test_devices.py index 2125c43bc..c597eb472 100644 --- a/warp/tests/test_devices.py +++ b/warp/tests/test_devices.py @@ -8,33 +8,31 @@ import unittest import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() -def test_devices_get_device_functions(test, device): - # save default device - saved_device = wp.get_device() - - test.assertTrue(saved_device.is_cuda) +def test_devices_get_cuda_device_functions(test, device): + test.assertTrue(device.is_cuda) test.assertTrue(wp.is_device_available(device)) device_ordinal = device.ordinal current_device = wp.get_cuda_device(device_ordinal) test.assertEqual(current_device, device) - current_device = wp.get_cuda_device() # No-ordinal version test.assertTrue(wp.is_device_available(current_device)) + if device == current_device: + test.assertEqual(device, "cuda") + else: + test.assertNotEqual(device, "cuda") + preferred_device = wp.get_preferred_device() test.assertTrue(wp.is_device_available(preferred_device)) - # restore default device - wp.set_device(saved_device) - -def test_devices_map_device(test, device): +def test_devices_map_cuda_device(test, device): with wp.ScopedDevice(device): saved_alias = device.alias # Map alias twice to check code path @@ -58,42 +56,43 @@ def test_devices_verify_cuda_device(test, device): wp.config.verify_cuda = verify_cuda_saved +@unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") def test_devices_can_access_self(test, device): test.assertTrue(device.can_access(device)) - # Also test CPU access - cpu_device = wp.get_device("cpu") - if device != cpu_device: - test.assertFalse(device.can_access(cpu_device)) + for warp_device in wp.get_devices(): + device_str = str(warp_device) + + if (device.is_cpu and warp_device.is_cuda) or (device.is_cuda and warp_device.is_cpu): + test.assertFalse(device.can_access(warp_device)) + test.assertNotEqual(device, warp_device) + test.assertNotEqual(device, device_str) - test.assertNotEqual(cpu_device, "cuda") +devices = get_test_devices() -def register(parent): - devices = get_test_devices() - class TestDevices(parent): - pass +class TestDevices(unittest.TestCase): + pass - add_function_test( - TestDevices, - "test_devices_get_device_functions", - test_devices_get_device_functions, - devices=wp.get_cuda_devices(), - ) - add_function_test(TestDevices, "test_devices_map_device", test_devices_map_device, devices=wp.get_cuda_devices()) - add_function_test( - TestDevices, "test_devices_unmap_imaginary_device", test_devices_unmap_imaginary_device, devices=devices - ) - add_function_test(TestDevices, "test_devices_verify_cuda_device", test_devices_verify_cuda_device, devices=devices) - if wp.is_cuda_available(): - add_function_test(TestDevices, "test_devices_can_access_self", test_devices_can_access_self, devices=devices) +add_function_test( + TestDevices, + "test_devices_get_cuda_device_functions", + test_devices_get_cuda_device_functions, + devices=get_unique_cuda_test_devices(), +) +add_function_test( + TestDevices, "test_devices_map_cuda_device", test_devices_map_cuda_device, devices=get_unique_cuda_test_devices() +) +add_function_test( + TestDevices, "test_devices_unmap_imaginary_device", test_devices_unmap_imaginary_device, devices=devices +) +add_function_test(TestDevices, "test_devices_verify_cuda_device", test_devices_verify_cuda_device, devices=devices) - return TestDevices +add_function_test(TestDevices, "test_devices_can_access_self", test_devices_can_access_self, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_dlpack.py b/warp/tests/test_dlpack.py index 4c14c4bc4..2d514485c 100644 --- a/warp/tests/test_dlpack.py +++ b/warp/tests/test_dlpack.py @@ -5,13 +5,14 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import numpy as np -import unittest -import os import ctypes +import os +import unittest + +import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -299,79 +300,77 @@ def test_dlpack_jax_to_warp(test, device): assert_np_equal(a2.numpy(), np.asarray(j)) -def register(parent): - class TestDLPack(parent): - pass - - devices = get_test_devices() - - add_function_test(TestDLPack, "test_dlpack_warp_to_warp", test_dlpack_warp_to_warp, devices=devices) - add_function_test(TestDLPack, "test_dlpack_dtypes_and_shapes", test_dlpack_dtypes_and_shapes, devices=devices) - - # torch interop via dlpack - try: - import torch - import torch.utils.dlpack - - # check which Warp devices work with Torch - # CUDA devices may fail if Torch was not compiled with CUDA support - test_devices = get_test_devices() - torch_compatible_devices = [] - for d in test_devices: - try: - t = torch.arange(10, device=wp.device_to_torch(d)) - t += 1 - torch_compatible_devices.append(d) - except Exception as e: - print(f"Skipping Torch DLPack tests on device '{d}' due to exception: {e}") - - if torch_compatible_devices: - add_function_test( - TestDLPack, "test_dlpack_warp_to_torch", test_dlpack_warp_to_torch, devices=torch_compatible_devices - ) - add_function_test( - TestDLPack, "test_dlpack_torch_to_warp", test_dlpack_torch_to_warp, devices=torch_compatible_devices - ) - - except Exception as e: - print(f"Skipping Torch DLPack tests due to exception: {e}") - - # jax interop via dlpack - try: - # prevent Jax from gobbling up GPU memory - os.environ["XLA_PYTHON_CLIENT_PREALLOCATE"] = "false" - - import jax - import jax.dlpack - - # check which Warp devices work with Jax - # CUDA devices may fail if Jax cannot find a CUDA Toolkit - test_devices = get_test_devices() - jax_compatible_devices = [] - for d in test_devices: - try: - with jax.default_device(wp.device_to_jax(d)): - j = jax.numpy.arange(10, dtype=jax.numpy.float32) - j += 1 - jax_compatible_devices.append(d) - except Exception as e: - print(f"Skipping Jax DLPack tests on device '{d}' due to exception: {e}") - - if jax_compatible_devices: - add_function_test( - TestDLPack, "test_dlpack_warp_to_jax", test_dlpack_warp_to_jax, devices=jax_compatible_devices - ) - add_function_test( - TestDLPack, "test_dlpack_jax_to_warp", test_dlpack_jax_to_warp, devices=jax_compatible_devices - ) - - except Exception as e: - print(f"Skipping Jax DLPack tests due to exception: {e}") - - return TestDLPack +class TestDLPack(unittest.TestCase): + pass + + +devices = get_test_devices() + +add_function_test(TestDLPack, "test_dlpack_warp_to_warp", test_dlpack_warp_to_warp, devices=devices) +add_function_test(TestDLPack, "test_dlpack_dtypes_and_shapes", test_dlpack_dtypes_and_shapes, devices=devices) + +# torch interop via dlpack +try: + import torch + import torch.utils.dlpack + + # check which Warp devices work with Torch + # CUDA devices may fail if Torch was not compiled with CUDA support + test_devices = get_test_devices() + torch_compatible_devices = [] + for d in test_devices: + try: + t = torch.arange(10, device=wp.device_to_torch(d)) + t += 1 + torch_compatible_devices.append(d) + except Exception as e: + print(f"Skipping Torch DLPack tests on device '{d}' due to exception: {e}") + + if torch_compatible_devices: + add_function_test( + TestDLPack, "test_dlpack_warp_to_torch", test_dlpack_warp_to_torch, devices=torch_compatible_devices + ) + add_function_test( + TestDLPack, "test_dlpack_torch_to_warp", test_dlpack_torch_to_warp, devices=torch_compatible_devices + ) + +except Exception as e: + print(f"Skipping Torch DLPack tests due to exception: {e}") + +# jax interop via dlpack +try: + # prevent Jax from gobbling up GPU memory + os.environ["XLA_PYTHON_CLIENT_PREALLOCATE"] = "false" + os.environ["XLA_PYTHON_CLIENT_ALLOCATOR"] = "platform" + + import jax + import jax.dlpack + + # check which Warp devices work with Jax + # CUDA devices may fail if Jax cannot find a CUDA Toolkit + test_devices = get_test_devices() + jax_compatible_devices = [] + for d in test_devices: + try: + with jax.default_device(wp.device_to_jax(d)): + j = jax.numpy.arange(10, dtype=jax.numpy.float32) + j += 1 + jax_compatible_devices.append(d) + except Exception as e: + print(f"Skipping Jax DLPack tests on device '{d}' due to exception: {e}") + + if jax_compatible_devices: + add_function_test( + TestDLPack, "test_dlpack_warp_to_jax", test_dlpack_warp_to_jax, devices=jax_compatible_devices + ) + add_function_test( + TestDLPack, "test_dlpack_jax_to_warp", test_dlpack_jax_to_warp, devices=jax_compatible_devices + ) + +except Exception as e: + print(f"Skipping Jax DLPack tests due to exception: {e}") if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_examples.py b/warp/tests/test_examples.py index a87497841..b0999d2c6 100644 --- a/warp/tests/test_examples.py +++ b/warp/tests/test_examples.py @@ -1,130 +1,225 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import importlib import os import unittest import warp as wp +from warp.tests.unittest_utils import get_unique_cuda_test_devices + +wp.init() # registers an example to run as a TestCase -def add_example_test(cls, name, options): +def add_example_test(cls, name, devices=None, options={}): def run(test, device): - # disable scoped timer to avoid log spam - wp.ScopedTimer.enabled = False - try: module = importlib.import_module(f"examples.{name}") + + torch_cuda_required = options.setdefault("torch_cuda_required", False) + options.pop("torch_cuda_required", None) + if torch_cuda_required and wp.get_device(device).is_cuda: + # Ensure torch has CUDA support + import torch + + if not torch.cuda.is_available(): + test.skipTest("Torch not compiled with CUDA support") + except Exception as e: - print(f"Skipping example: {name}\n Reason: {e}") - return + test.skipTest(f"{e}") # create default USD stage output path which many examples expect - if "stage" not in options: - stage_path = os.path.join(os.path.dirname(__file__), f"outputs/{name}.usd") - options["stage"] = stage_path - - if "num_frames" in options: - num_frames = options["num_frames"] - del options["num_frames"] - else: - num_frames = 10 - - e = module.Example(**options) - - for _ in range(num_frames): - e.update() - e.render() - - wp.ScopedTimer.enabled = True - - from warp.tests.test_base import add_function_test - - add_function_test(cls, f"test_{name}", run, check_output=False) - - -def register(parent): - class TestExamples(parent): - pass - - # Exclude unless we can run headless somehow - # add_example_test(TestExamples, name="example_render_opengl", options={}) - - # TODO: Test CPU and GPU versions - if wp.is_cuda_available(): - add_example_test(TestExamples, name="example_dem", options={}) - add_example_test(TestExamples, name="example_diffray", options={}) - add_example_test(TestExamples, name="example_fluid", options={}) - add_example_test(TestExamples, name="example_jacobian_ik", options={}) - add_example_test(TestExamples, name="example_marching_cubes", options={}) - add_example_test(TestExamples, name="example_mesh", options={}) - add_example_test(TestExamples, name="example_mesh_intersect", options={"num_frames": 1}) - add_example_test(TestExamples, name="example_nvdb", options={}) - add_example_test(TestExamples, name="example_raycast", options={}) - add_example_test(TestExamples, name="example_raymarch", options={}) - add_example_test(TestExamples, name="example_sim_cartpole", options={}) - add_example_test(TestExamples, name="example_sim_cloth", options={}) - add_example_test(TestExamples, name="example_sim_fk_grad", options={}) - # add_example_test(TestExamples, name="example_sim_fk_grad_torch", options={}) # disabling due to failure on TC machines that have torch but not CUDA torch - add_example_test(TestExamples, name="example_sim_grad_bounce", options={}) - add_example_test(TestExamples, name="example_sim_grad_cloth", options={}) - add_example_test(TestExamples, name="example_sim_granular", options={}) - add_example_test(TestExamples, name="example_sim_granular_collision_sdf", options={}) - add_example_test(TestExamples, name="example_sim_neo_hookean", options={}) - add_example_test(TestExamples, name="example_sim_particle_chain", options={}) - add_example_test(TestExamples, name="example_sim_quadruped", options={}) - add_example_test(TestExamples, name="example_sim_rigid_chain", options={}) - add_example_test(TestExamples, name="example_sim_rigid_contact", options={}) - add_example_test(TestExamples, name="example_sim_rigid_fem", options={}) - add_example_test(TestExamples, name="example_sim_rigid_force", options={}) - add_example_test(TestExamples, name="example_sim_rigid_gyroscopic", options={}) - add_example_test(TestExamples, name="example_sim_rigid_kinematics", options={}) - add_example_test(TestExamples, name="example_sim_trajopt", options={}) - add_example_test(TestExamples, name="example_sph", options={}) - add_example_test(TestExamples, name="example_wave", options={"resx": 256, "resy": 256}) - add_example_test(TestExamples, name="fem.example_diffusion_mgpu", options={"quiet": True, "num_frames": 1}) - - # USD import failures should not count as a test failure - try: - from pxr import Usd, UsdGeom - - have_usd = True - except: - have_usd = False - - # The following examples do not need CUDA, but they need USD - if have_usd: - add_example_test(TestExamples, name="fem.example_apic_fluid", options={"quiet": True, "res": [16, 16, 16]}) - add_example_test( - TestExamples, - name="fem.example_diffusion", - options={"quiet": True, "resolution": 10, "mesh": "tri", "num_frames": 1}, - ) - add_example_test( - TestExamples, name="fem.example_diffusion_3d", options={"quiet": True, "resolution": 10, "num_frames": 1} - ) - add_example_test( - TestExamples, - name="fem.example_deformed_geometry", - options={"quiet": True, "resolution": 10, "num_frames": 1, "mesh": "tri"}, - ) - add_example_test( - TestExamples, name="fem.example_convection_diffusion", options={"quiet": True, "resolution": 20} - ) - add_example_test( - TestExamples, - name="fem.example_mixed_elasticity", - options={"quiet": True, "nonconforming_stresses": True, "mesh": "quad", "num_frames": 1}, - ) - add_example_test(TestExamples, name="fem.example_stokes_transfer", options={"quiet": True, "num_frames": 1}) - - return TestExamples + options.setdefault("stage", os.path.join(os.path.dirname(__file__), f"outputs/{name}.usd")) + num_frames = options.get("num_frames", 10) + options.pop("num_frames", None) -if __name__ == "__main__": - wp.init() + # Don't want to force load all modules by default for serial test runner + wp.config.graph_capture_module_load_default = False + + try: + enable_backward = options.get("enable_backward", True) + wp.set_module_options({"enable_backward": enable_backward}, module) + options.pop("enable_backward", None) + wp.load_module(module, device=wp.get_device()) + extra_load_modules = options.get("load_modules", []) + for module_name in extra_load_modules: + wp.load_module(module_name, device=wp.get_device()) + options.pop("load_modules", None) + + e = module.Example(**options) + + # disable scoped timer to avoid log spam from time steps + wp.ScopedTimer.enabled = False + + for _ in range(num_frames): + e.update() + e.render() + except Exception as e: + test.fail(f"{e}") + finally: + wp.ScopedTimer.enabled = True + wp.config.graph_capture_module_load_default = True + + from warp.tests.unittest_utils import add_function_test + + add_function_test(cls, f"test_{name}", run, devices=devices, check_output=False) + + +# TODO: Make the example classes use the passed in device +cuda_test_devices = get_unique_cuda_test_devices() + +# NOTE: To give the parallel test runner more opportunities to parallelize test cases, +# we break up the tests into multiple TestCase classes that should be non-conflicting +# w.r.t. kernel compilation + + +class TestExamples(unittest.TestCase): + pass + + +# Exclude unless we can run headless somehow +# add_example_test(TestExamples, name="example_render_opengl", options={}) + +add_example_test(TestExamples, name="example_dem", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_diffray", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_fluid", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_jacobian_ik", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_marching_cubes", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_mesh", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_mesh_intersect", devices=cuda_test_devices, options={"num_frames": 1}) +add_example_test(TestExamples, name="example_nvdb", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_raycast", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_raymarch", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_sph", devices=cuda_test_devices) +add_example_test(TestExamples, name="example_wave", devices=cuda_test_devices, options={"resx": 256, "resy": 256}) + + +class TestSimExamples(unittest.TestCase): + pass + + +add_example_test( + TestSimExamples, + name="example_sim_cartpole", + devices=cuda_test_devices, + options={"load_modules": ["warp.sim.integrator_euler"]}, +) +add_example_test( + TestSimExamples, + name="example_sim_cloth", + devices=cuda_test_devices, + options={"load_modules": ["warp.sim.collide", "warp.sim.integrator_euler", "warp.sim.particles"]}, +) +add_example_test(TestSimExamples, name="example_sim_fk_grad", devices=cuda_test_devices) +add_example_test( + TestSimExamples, name="example_sim_fk_grad_torch", devices=cuda_test_devices, options={"torch_cuda_required": True} +) +add_example_test( + TestSimExamples, + name="example_sim_grad_bounce", + devices=cuda_test_devices, + options={"load_modules": ["warp.sim.integrator_euler", "warp.sim.particles"]}, +) +add_example_test( + TestSimExamples, + name="example_sim_grad_cloth", + devices=cuda_test_devices, + options={"load_modules": ["warp.sim.integrator_euler", "warp.sim.particles"]}, +) +add_example_test(TestSimExamples, name="example_sim_granular", devices=cuda_test_devices) +add_example_test(TestSimExamples, name="example_sim_granular_collision_sdf", devices=cuda_test_devices) +add_example_test(TestSimExamples, name="example_sim_neo_hookean", devices=cuda_test_devices) +add_example_test(TestSimExamples, name="example_sim_particle_chain", devices=cuda_test_devices) +add_example_test( + TestSimExamples, + name="example_sim_quadruped", + devices=cuda_test_devices, + options={"load_modules": ["warp.sim.integrator_xpbd", "warp.sim.integrator_euler"]}, +) +add_example_test( + TestSimExamples, + name="example_sim_rigid_chain", + devices=cuda_test_devices, + options={"load_modules": ["warp.sim.integrator_xpbd", "warp.sim.integrator_euler"]}, +) +add_example_test( + TestSimExamples, + name="example_sim_rigid_contact", + devices=cuda_test_devices, + options={"load_modules": ["warp.sim.integrator_euler"]}, +) +add_example_test(TestSimExamples, name="example_sim_rigid_fem", devices=cuda_test_devices) +add_example_test(TestSimExamples, name="example_sim_rigid_force", devices=cuda_test_devices) +add_example_test(TestSimExamples, name="example_sim_rigid_gyroscopic", devices=cuda_test_devices) +add_example_test(TestSimExamples, name="example_sim_rigid_kinematics", devices=cuda_test_devices) +add_example_test(TestSimExamples, name="example_sim_trajopt", devices=cuda_test_devices) + + +class TestFemExamples(unittest.TestCase): + pass + + +add_example_test( + TestFemExamples, + name="fem.example_diffusion_mgpu", + devices=cuda_test_devices, + options={"quiet": True, "num_frames": 1, "enable_backward": False}, +) + +# The following examples do not need CUDA, but they need USD +add_example_test( + TestFemExamples, + name="fem.example_apic_fluid", + devices=cuda_test_devices, + options={"quiet": True, "res": [16, 16, 16], "enable_backward": False}, +) +add_example_test( + TestFemExamples, + name="fem.example_diffusion", + devices=cuda_test_devices, + options={"quiet": True, "resolution": 10, "mesh": "tri", "num_frames": 1, "enable_backward": False}, +) +add_example_test( + TestFemExamples, + name="fem.example_diffusion_3d", + devices=cuda_test_devices, + options={"quiet": True, "resolution": 10, "num_frames": 1, "enable_backward": False}, +) +add_example_test( + TestFemExamples, + name="fem.example_deformed_geometry", + devices=cuda_test_devices, + options={"quiet": True, "resolution": 10, "num_frames": 1, "mesh": "tri", "enable_backward": False}, +) +add_example_test( + TestFemExamples, + name="fem.example_convection_diffusion", + devices=cuda_test_devices, + options={"quiet": True, "resolution": 20, "enable_backward": False}, +) +add_example_test( + TestFemExamples, + name="fem.example_mixed_elasticity", + devices=cuda_test_devices, + options={"quiet": True, "nonconforming_stresses": True, "mesh": "quad", "num_frames": 1, "enable_backward": False}, +) +add_example_test( + TestFemExamples, + name="fem.example_stokes_transfer", + devices=cuda_test_devices, + options={"quiet": True, "num_frames": 1, "enable_backward": False}, +) + + +if __name__ == "__main__": # force rebuild of all kernels wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) - unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_fabricarray.py b/warp/tests/test_fabricarray.py index 09642c1ea..7a23c204f 100644 --- a/warp/tests/test_fabricarray.py +++ b/warp/tests/test_fabricarray.py @@ -12,7 +12,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -930,32 +930,26 @@ def test_fabricarrayarray(test, device): wp.overload(fa_generic_sums_kernel_indexed, [wp.indexedfabricarrayarray(dtype=T), wp.array(dtype=T)]) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestFabricArray(parent): - pass - # fabric arrays - add_function_test(TestFabricArray, "test_fabricarray_kernel", test_fabricarray_kernel, devices=devices) - add_function_test(TestFabricArray, "test_fabricarray_empty", test_fabricarray_empty, devices=devices) - add_function_test( - TestFabricArray, "test_fabricarray_generic_dtype", test_fabricarray_generic_dtype, devices=devices - ) - add_function_test( - TestFabricArray, "test_fabricarray_generic_array", test_fabricarray_generic_array, devices=devices - ) - add_function_test(TestFabricArray, "test_fabricarray_fill_scalar", test_fabricarray_fill_scalar, devices=devices) - add_function_test(TestFabricArray, "test_fabricarray_fill_vector", test_fabricarray_fill_vector, devices=devices) - add_function_test(TestFabricArray, "test_fabricarray_fill_matrix", test_fabricarray_fill_matrix, devices=devices) +class TestFabricArray(unittest.TestCase): + pass - # fabric arrays of arrays - add_function_test(TestFabricArray, "test_fabricarrayarray", test_fabricarrayarray, devices=devices) - return TestFabricArray +# fabric arrays +add_function_test(TestFabricArray, "test_fabricarray_kernel", test_fabricarray_kernel, devices=devices) +add_function_test(TestFabricArray, "test_fabricarray_empty", test_fabricarray_empty, devices=devices) +add_function_test(TestFabricArray, "test_fabricarray_generic_dtype", test_fabricarray_generic_dtype, devices=devices) +add_function_test(TestFabricArray, "test_fabricarray_generic_array", test_fabricarray_generic_array, devices=devices) +add_function_test(TestFabricArray, "test_fabricarray_fill_scalar", test_fabricarray_fill_scalar, devices=devices) +add_function_test(TestFabricArray, "test_fabricarray_fill_vector", test_fabricarray_fill_vector, devices=devices) +add_function_test(TestFabricArray, "test_fabricarray_fill_matrix", test_fabricarray_fill_matrix, devices=devices) + +# fabric arrays of arrays +add_function_test(TestFabricArray, "test_fabricarrayarray", test_fabricarrayarray, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_fast_math.py b/warp/tests/test_fast_math.py index 1fe4b578e..0347c1086 100644 --- a/warp/tests/test_fast_math.py +++ b/warp/tests/test_fast_math.py @@ -1,11 +1,14 @@ -import warp as wp -import numpy as np +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. import unittest import warp as wp -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() @@ -33,19 +36,19 @@ def test_fast_math(test, device): with CheckOutput(): wp.launch(test_pow, dim=1, inputs=[-2.0, 2.0, 2.0], device=device) + # Turn fast math back off + wp.set_module_options({"fast_math": False}) + -def register(parent): - class TestFastMath(parent): - pass +class TestFastMath(unittest.TestCase): + pass - devices = get_test_devices() - add_function_test(TestFastMath, "test_fast_math", test_fast_math, devices=devices) +devices = get_test_devices() - return TestFastMath +add_function_test(TestFastMath, "test_fast_math", test_fast_math, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_fem.py b/warp/tests/test_fem.py index 36f5fb110..c62c49006 100644 --- a/warp/tests/test_fem.py +++ b/warp/tests/test_fem.py @@ -1,4 +1,4 @@ -# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. # NVIDIA CORPORATION and its licensors retain all intellectual property # and proprietary rights in and to this software, related documentation # and any modifications thereto. Any use, reproduction, disclosure or @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * from warp.fem import Field, Sample, Domain, Coords @@ -1230,38 +1230,42 @@ def test_particle_quadratures(test_case, device): test_case.assertAlmostEqual(val, 1.25, places=5) -def register(parent): - devices = get_test_devices() - - class TestFem(parent): - pass - - add_function_test(TestFem, "test_regular_quadrature", test_regular_quadrature) - add_function_test(TestFem, "test_closest_point_queries", test_closest_point_queries) - add_function_test(TestFem, "test_grad_decomposition", test_grad_decomposition, devices=devices) - add_function_test(TestFem, "test_integrate_gradient", test_integrate_gradient, devices=devices) - add_function_test(TestFem, "test_interpolate_gradient", test_interpolate_gradient, devices=devices) - add_function_test(TestFem, "test_vector_divergence_theorem", test_vector_divergence_theorem, devices=devices) - add_function_test(TestFem, "test_tensor_divergence_theorem", test_tensor_divergence_theorem, devices=devices) - add_function_test(TestFem, "test_grid_2d", test_grid_2d, devices=devices) - add_function_test(TestFem, "test_triangle_mesh", test_triangle_mesh, devices=devices) - add_function_test(TestFem, "test_quad_mesh", test_quad_mesh, devices=devices) - add_function_test(TestFem, "test_grid_3d", test_grid_3d, devices=devices) - add_function_test(TestFem, "test_tet_mesh", test_tet_mesh, devices=devices) - add_function_test(TestFem, "test_hex_mesh", test_hex_mesh, devices=devices) - add_function_test(TestFem, "test_deformed_geometry", test_deformed_geometry, devices=devices) - add_function_test(TestFem, "test_dof_mapper", test_dof_mapper) - add_function_test(TestFem, "test_square_shape_functions", test_square_shape_functions) - add_function_test(TestFem, "test_cube_shape_functions", test_cube_shape_functions) - add_function_test(TestFem, "test_tri_shape_functions", test_tri_shape_functions) - add_function_test(TestFem, "test_tet_shape_functions", test_tet_shape_functions) - add_function_test(TestFem, "test_point_basis", test_point_basis) - add_function_test(TestFem, "test_particle_quadratures", test_particle_quadratures) - - return TestFem +devices = get_test_devices() + + +class TestFem(unittest.TestCase): + pass + + +add_function_test(TestFem, "test_regular_quadrature", test_regular_quadrature) +add_function_test(TestFem, "test_closest_point_queries", test_closest_point_queries) +add_function_test(TestFem, "test_grad_decomposition", test_grad_decomposition, devices=devices) +add_function_test(TestFem, "test_integrate_gradient", test_integrate_gradient, devices=devices) +add_function_test(TestFem, "test_interpolate_gradient", test_interpolate_gradient, devices=devices) +add_function_test(TestFem, "test_vector_divergence_theorem", test_vector_divergence_theorem, devices=devices) +add_function_test(TestFem, "test_tensor_divergence_theorem", test_tensor_divergence_theorem, devices=devices) +add_function_test(TestFem, "test_grid_2d", test_grid_2d, devices=devices) +add_function_test(TestFem, "test_triangle_mesh", test_triangle_mesh, devices=devices) +add_function_test(TestFem, "test_quad_mesh", test_quad_mesh, devices=devices) +add_function_test(TestFem, "test_grid_3d", test_grid_3d, devices=devices) +add_function_test(TestFem, "test_tet_mesh", test_tet_mesh, devices=devices) +add_function_test(TestFem, "test_hex_mesh", test_hex_mesh, devices=devices) +add_function_test(TestFem, "test_deformed_geometry", test_deformed_geometry, devices=devices) +add_function_test(TestFem, "test_dof_mapper", test_dof_mapper) +add_function_test(TestFem, "test_point_basis", test_point_basis) +add_function_test(TestFem, "test_particle_quadratures", test_particle_quadratures) + + +class TestFemShapeFunctions(unittest.TestCase): + pass + + +add_function_test(TestFemShapeFunctions, "test_square_shape_functions", test_square_shape_functions) +add_function_test(TestFemShapeFunctions, "test_cube_shape_functions", test_cube_shape_functions) +add_function_test(TestFemShapeFunctions, "test_tri_shape_functions", test_tri_shape_functions) +add_function_test(TestFemShapeFunctions, "test_tet_shape_functions", test_tet_shape_functions) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_fp16.py b/warp/tests/test_fp16.py index 09b08870e..4ccdf5114 100644 --- a/warp/tests/test_fp16.py +++ b/warp/tests/test_fp16.py @@ -1,9 +1,16 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -102,25 +109,22 @@ def test_fp16_grad(test, device): assert_np_equal(input.grad.numpy(), np.ones(len(s)) * 2.0) -def register(parent): - class TestFp16(parent): - pass +class TestFp16(unittest.TestCase): + pass - devices = [] - if wp.is_cpu_available(): - devices.append("cpu") - for cuda_device in wp.get_cuda_devices(): - if cuda_device.arch >= 70: - devices.append(cuda_device) - add_function_test(TestFp16, "test_fp16_conversion", test_fp16_conversion, devices=devices) - add_function_test(TestFp16, "test_fp16_grad", test_fp16_grad, devices=devices) - add_function_test(TestFp16, "test_fp16_kernel_parameter", test_fp16_kernel_parameter, devices=devices) +devices = [] +if wp.is_cpu_available(): + devices.append("cpu") +for cuda_device in get_unique_cuda_test_devices(): + if cuda_device.arch >= 70: + devices.append(cuda_device) - return TestFp16 +add_function_test(TestFp16, "test_fp16_conversion", test_fp16_conversion, devices=devices) +add_function_test(TestFp16, "test_fp16_grad", test_fp16_grad, devices=devices) +add_function_test(TestFp16, "test_fp16_kernel_parameter", test_fp16_kernel_parameter, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_func.py b/warp/tests/test_func.py index 109d70a15..a42d1e039 100644 --- a/warp/tests/test_func.py +++ b/warp/tests/test_func.py @@ -5,14 +5,13 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path -import numpy as np import math +import unittest -import warp as wp -from warp.tests.test_base import * +import numpy as np -import unittest +import warp as wp +from warp.tests.unittest_utils import * wp.init() @@ -83,169 +82,6 @@ def test_override_func(): wp.expect_eq(i, 3) -def test_native_func_export(test, device): - # tests calling native functions from Python - - q = wp.quat(0.0, 0.0, 0.0, 1.0) - assert_np_equal(np.array([*q]), np.array([0.0, 0.0, 0.0, 1.0])) - - r = wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), 2.0) - assert_np_equal(np.array([*r]), np.array([0.8414709568023682, 0.0, 0.0, 0.5403022170066833]), tol=1.0e-3) - - q = wp.quat(1.0, 2.0, 3.0, 4.0) - q = wp.normalize(q) * 2.0 - assert_np_equal( - np.array([*q]), - np.array([0.18257418274879456, 0.3651483654975891, 0.547722578048706, 0.7302967309951782]) * 2.0, - tol=1.0e-3, - ) - - v2 = wp.vec2(1.0, 2.0) - v2 = wp.normalize(v2) * 2.0 - assert_np_equal(np.array([*v2]), np.array([0.4472135901451111, 0.8944271802902222]) * 2.0, tol=1.0e-3) - - v3 = wp.vec3(1.0, 2.0, 3.0) - v3 = wp.normalize(v3) * 2.0 - assert_np_equal( - np.array([*v3]), np.array([0.26726123690605164, 0.5345224738121033, 0.8017836809158325]) * 2.0, tol=1.0e-3 - ) - - v4 = wp.vec4(1.0, 2.0, 3.0, 4.0) - v4 = wp.normalize(v4) * 2.0 - assert_np_equal( - np.array([*v4]), - np.array([0.18257418274879456, 0.3651483654975891, 0.547722578048706, 0.7302967309951782]) * 2.0, - tol=1.0e-3, - ) - - v = wp.vec2(0.0) - v += wp.vec2(1.0, 1.0) - assert v == wp.vec2(1.0, 1.0) - v -= wp.vec2(1.0, 1.0) - assert v == wp.vec2(0.0, 0.0) - v = wp.vec2(2.0, 2.0) - wp.vec2(1.0, 1.0) - assert v == wp.vec2(1.0, 1.0) - v *= 2.0 - assert v == wp.vec2(2.0, 2.0) - v = v * 2.0 - assert v == wp.vec2(4.0, 4.0) - v = v / 2.0 - assert v == wp.vec2(2.0, 2.0) - v /= 2.0 - assert v == wp.vec2(1.0, 1.0) - v = -v - assert v == wp.vec2(-1.0, -1.0) - v = +v - assert v == wp.vec2(-1.0, -1.0) - - m22 = wp.mat22(1.0, 2.0, 3.0, 4.0) - m22 = m22 + m22 - - test.assertEqual(m22[1, 1], 8.0) - test.assertEqual(str(m22), "[[2.0, 4.0],\n [6.0, 8.0]]") - - t = wp.transform( - wp.vec3(1.0, 2.0, 3.0), - wp.quat(4.0, 5.0, 6.0, 7.0), - ) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t * wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0), (396.0, 432.0, 720.0, 56.0, 70.0, 84.0, -28.0)) - test.assertSequenceEqual( - t * wp.transform((1.0, 2.0, 3.0), (4.0, 5.0, 6.0, 7.0)), (396.0, 432.0, 720.0, 56.0, 70.0, 84.0, -28.0) - ) - - t = wp.transform() - test.assertSequenceEqual(t, (0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)) - - t = wp.transform(p=(1.0, 2.0, 3.0), q=(4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform(q=(4.0, 5.0, 6.0, 7.0), p=(1.0, 2.0, 3.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform((1.0, 2.0, 3.0), q=(4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform(p=(1.0, 2.0, 3.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 0.0, 0.0, 0.0, 1.0)) - - t = wp.transform(q=(4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t, (0.0, 0.0, 0.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform((1.0, 2.0, 3.0), (4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform(p=wp.vec3(1.0, 2.0, 3.0), q=wp.quat(4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform(wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - t = wp.transform(*wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) - - transformf = wp.types.transformation(dtype=float) - - t = wp.transformf((1.0, 2.0, 3.0), (4.0, 5.0, 6.0, 7.0)) - test.assertSequenceEqual( - t + transformf((2.0, 3.0, 4.0), (5.0, 6.0, 7.0, 8.0)), - (3.0, 5.0, 7.0, 9.0, 11.0, 13.0, 15.0), - ) - test.assertSequenceEqual( - t - transformf((2.0, 3.0, 4.0), (5.0, 6.0, 7.0, 8.0)), - (-1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0), - ) - - f = wp.sin(math.pi * 0.5) - test.assertAlmostEqual(f, 1.0, places=3) - - m = wp.mat22(0.0, 0.0, 0.0, 0.0) - m += wp.mat22(1.0, 1.0, 1.0, 1.0) - assert m == wp.mat22(1.0, 1.0, 1.0, 1.0) - m -= wp.mat22(1.0, 1.0, 1.0, 1.0) - assert m == wp.mat22(0.0, 0.0, 0.0, 0.0) - m = wp.mat22(2.0, 2.0, 2.0, 2.0) - wp.mat22(1.0, 1.0, 1.0, 1.0) - assert m == wp.mat22(1.0, 1.0, 1.0, 1.0) - m *= 2.0 - assert m == wp.mat22(2.0, 2.0, 2.0, 2.0) - m = m * 2.0 - assert m == wp.mat22(4.0, 4.0, 4.0, 4.0) - m = m / 2.0 - assert m == wp.mat22(2.0, 2.0, 2.0, 2.0) - m /= 2.0 - assert m == wp.mat22(1.0, 1.0, 1.0, 1.0) - m = -m - assert m == wp.mat22(-1.0, -1.0, -1.0, -1.0) - m = +m - assert m == wp.mat22(-1.0, -1.0, -1.0, -1.0) - m = m * m - assert m == wp.mat22(2.0, 2.0, 2.0, 2.0) - - -def test_native_function_error_resolution(test, device): - a = wp.mat22f(1.0, 2.0, 3.0, 4.0) - b = wp.mat22d(1.0, 2.0, 3.0, 4.0) - with test.assertRaisesRegex( - RuntimeError, - r"^Couldn't find a function 'mul' compatible with " r"the arguments 'mat22f, mat22d'$", - ): - a * b - - -def test_user_func_export(test, device): - # tests calling overloaded user-defined functions from Python - i = custom(1) - f = custom(1.0) - v = custom(wp.vec3(1.0, 0.0, 0.0)) - - test.assertEqual(i, 2) - test.assertEqual(f, 2.0) - assert_np_equal(np.array([*v]), np.array([2.0, 0.0, 0.0])) - - def test_func_closure_capture(test, device): def make_closure_kernel(func): def closure_kernel_fn(data: wp.array(dtype=float), expected: float): @@ -321,34 +157,181 @@ def test_builtin_shadowing(): wp.expect_eq(sign(1.23), 123.0) -def register(parent): - devices = get_test_devices() - - class TestFunc(parent): - pass - - add_kernel_test(TestFunc, kernel=test_overload_func, name="test_overload_func", dim=1, devices=devices) - add_function_test(TestFunc, func=test_return_func, name="test_return_func", devices=devices) - add_kernel_test(TestFunc, kernel=test_override_func, name="test_override_func", dim=1, devices=devices) - add_function_test(TestFunc, func=test_native_func_export, name="test_native_func_export", devices=["cpu"]) - add_function_test( - TestFunc, - func=test_native_function_error_resolution, - name="test_native_function_error_resolution", - devices=["cpu"], - ) - add_function_test(TestFunc, func=test_user_func_export, name="test_user_func_export", devices=["cpu"]) - add_function_test(TestFunc, func=test_func_closure_capture, name="test_func_closure_capture", devices=devices) - add_function_test(TestFunc, func=test_multi_valued_func, name="test_multi_valued_func", devices=devices) - add_kernel_test(TestFunc, kernel=test_func_defaults, name="test_func_defaults", dim=1, devices=devices) - add_kernel_test(TestFunc, kernel=test_builtin_shadowing, name="test_builtin_shadowing", dim=1, devices=devices) - - return TestFunc +devices = get_test_devices() + + +class TestFunc(unittest.TestCase): + def test_user_func_export(self): + # tests calling overloaded user-defined functions from Python + i = custom(1) + f = custom(1.0) + v = custom(wp.vec3(1.0, 0.0, 0.0)) + + self.assertEqual(i, 2) + self.assertEqual(f, 2.0) + assert_np_equal(np.array([*v]), np.array([2.0, 0.0, 0.0])) + + def test_native_func_export(self): + # tests calling native functions from Python + + q = wp.quat(0.0, 0.0, 0.0, 1.0) + assert_np_equal(np.array([*q]), np.array([0.0, 0.0, 0.0, 1.0])) + + r = wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), 2.0) + assert_np_equal(np.array([*r]), np.array([0.8414709568023682, 0.0, 0.0, 0.5403022170066833]), tol=1.0e-3) + + q = wp.quat(1.0, 2.0, 3.0, 4.0) + q = wp.normalize(q) * 2.0 + assert_np_equal( + np.array([*q]), + np.array([0.18257418274879456, 0.3651483654975891, 0.547722578048706, 0.7302967309951782]) * 2.0, + tol=1.0e-3, + ) + + v2 = wp.vec2(1.0, 2.0) + v2 = wp.normalize(v2) * 2.0 + assert_np_equal(np.array([*v2]), np.array([0.4472135901451111, 0.8944271802902222]) * 2.0, tol=1.0e-3) + + v3 = wp.vec3(1.0, 2.0, 3.0) + v3 = wp.normalize(v3) * 2.0 + assert_np_equal( + np.array([*v3]), np.array([0.26726123690605164, 0.5345224738121033, 0.8017836809158325]) * 2.0, tol=1.0e-3 + ) + + v4 = wp.vec4(1.0, 2.0, 3.0, 4.0) + v4 = wp.normalize(v4) * 2.0 + assert_np_equal( + np.array([*v4]), + np.array([0.18257418274879456, 0.3651483654975891, 0.547722578048706, 0.7302967309951782]) * 2.0, + tol=1.0e-3, + ) + + v = wp.vec2(0.0) + v += wp.vec2(1.0, 1.0) + assert v == wp.vec2(1.0, 1.0) + v -= wp.vec2(1.0, 1.0) + assert v == wp.vec2(0.0, 0.0) + v = wp.vec2(2.0, 2.0) - wp.vec2(1.0, 1.0) + assert v == wp.vec2(1.0, 1.0) + v *= 2.0 + assert v == wp.vec2(2.0, 2.0) + v = v * 2.0 + assert v == wp.vec2(4.0, 4.0) + v = v / 2.0 + assert v == wp.vec2(2.0, 2.0) + v /= 2.0 + assert v == wp.vec2(1.0, 1.0) + v = -v + assert v == wp.vec2(-1.0, -1.0) + v = +v + assert v == wp.vec2(-1.0, -1.0) + + m22 = wp.mat22(1.0, 2.0, 3.0, 4.0) + m22 = m22 + m22 + + self.assertEqual(m22[1, 1], 8.0) + self.assertEqual(str(m22), "[[2.0, 4.0],\n [6.0, 8.0]]") + + t = wp.transform( + wp.vec3(1.0, 2.0, 3.0), + wp.quat(4.0, 5.0, 6.0, 7.0), + ) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t * wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0), (396.0, 432.0, 720.0, 56.0, 70.0, 84.0, -28.0)) + self.assertSequenceEqual( + t * wp.transform((1.0, 2.0, 3.0), (4.0, 5.0, 6.0, 7.0)), (396.0, 432.0, 720.0, 56.0, 70.0, 84.0, -28.0) + ) + + t = wp.transform() + self.assertSequenceEqual(t, (0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0)) + + t = wp.transform(p=(1.0, 2.0, 3.0), q=(4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform(q=(4.0, 5.0, 6.0, 7.0), p=(1.0, 2.0, 3.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform((1.0, 2.0, 3.0), q=(4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform(p=(1.0, 2.0, 3.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 0.0, 0.0, 0.0, 1.0)) + + t = wp.transform(q=(4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t, (0.0, 0.0, 0.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform((1.0, 2.0, 3.0), (4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform(p=wp.vec3(1.0, 2.0, 3.0), q=wp.quat(4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform(wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + t = wp.transform(*wp.transform(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual(t, (1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0)) + + transformf = wp.types.transformation(dtype=float) + + t = wp.transformf((1.0, 2.0, 3.0), (4.0, 5.0, 6.0, 7.0)) + self.assertSequenceEqual( + t + transformf((2.0, 3.0, 4.0), (5.0, 6.0, 7.0, 8.0)), + (3.0, 5.0, 7.0, 9.0, 11.0, 13.0, 15.0), + ) + self.assertSequenceEqual( + t - transformf((2.0, 3.0, 4.0), (5.0, 6.0, 7.0, 8.0)), + (-1.0, -1.0, -1.0, -1.0, -1.0, -1.0, -1.0), + ) + + f = wp.sin(math.pi * 0.5) + self.assertAlmostEqual(f, 1.0, places=3) + + m = wp.mat22(0.0, 0.0, 0.0, 0.0) + m += wp.mat22(1.0, 1.0, 1.0, 1.0) + assert m == wp.mat22(1.0, 1.0, 1.0, 1.0) + m -= wp.mat22(1.0, 1.0, 1.0, 1.0) + assert m == wp.mat22(0.0, 0.0, 0.0, 0.0) + m = wp.mat22(2.0, 2.0, 2.0, 2.0) - wp.mat22(1.0, 1.0, 1.0, 1.0) + assert m == wp.mat22(1.0, 1.0, 1.0, 1.0) + m *= 2.0 + assert m == wp.mat22(2.0, 2.0, 2.0, 2.0) + m = m * 2.0 + assert m == wp.mat22(4.0, 4.0, 4.0, 4.0) + m = m / 2.0 + assert m == wp.mat22(2.0, 2.0, 2.0, 2.0) + m /= 2.0 + assert m == wp.mat22(1.0, 1.0, 1.0, 1.0) + m = -m + assert m == wp.mat22(-1.0, -1.0, -1.0, -1.0) + m = +m + assert m == wp.mat22(-1.0, -1.0, -1.0, -1.0) + m = m * m + assert m == wp.mat22(2.0, 2.0, 2.0, 2.0) + + + def test_native_function_error_resolution(self): + a = wp.mat22f(1.0, 2.0, 3.0, 4.0) + b = wp.mat22d(1.0, 2.0, 3.0, 4.0) + with self.assertRaisesRegex( + RuntimeError, + r"^Couldn't find a function 'mul' compatible with " r"the arguments 'mat22f, mat22d'$", + ): + a * b + + +add_kernel_test(TestFunc, kernel=test_overload_func, name="test_overload_func", dim=1, devices=devices) +add_function_test(TestFunc, func=test_return_func, name="test_return_func", devices=devices) +add_kernel_test(TestFunc, kernel=test_override_func, name="test_override_func", dim=1, devices=devices) +add_function_test(TestFunc, func=test_func_closure_capture, name="test_func_closure_capture", devices=devices) +add_function_test(TestFunc, func=test_multi_valued_func, name="test_multi_valued_func", devices=devices) +add_kernel_test(TestFunc, kernel=test_func_defaults, name="test_func_defaults", dim=1, devices=devices) +add_kernel_test(TestFunc, kernel=test_builtin_shadowing, name="test_builtin_shadowing", dim=1, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) - wp.force_load() - unittest.main(verbosity=2) diff --git a/warp/tests/test_generics.py b/warp/tests/test_generics.py index dcddea20c..e1e158519 100644 --- a/warp/tests/test_generics.py +++ b/warp/tests/test_generics.py @@ -5,12 +5,13 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import numpy as np import unittest from typing import Any +import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -487,81 +488,74 @@ def kernel(): ) -def register(parent): - class TestGenerics(parent): - pass - - devices = get_test_devices() - - add_kernel_test(TestGenerics, name="test_generic_adder", kernel=test_generic_adder, dim=1, devices=devices) - add_kernel_test(TestGenerics, name="test_specialized_func", kernel=test_specialized_func, dim=1, devices=devices) - - add_function_test(TestGenerics, "test_generic_array_kernel", test_generic_array_kernel, devices=devices) - add_function_test(TestGenerics, "test_generic_accumulator_kernel", test_generic_accumulator_kernel, devices=devices) - add_function_test(TestGenerics, "test_generic_fill", test_generic_fill, devices=devices) - add_function_test(TestGenerics, "test_generic_fill_overloads", test_generic_fill_overloads, devices=devices) - add_function_test(TestGenerics, "test_generic_transform_kernel", test_generic_transform_kernel, devices=devices) - add_function_test( - TestGenerics, "test_generic_transform_array_kernel", test_generic_transform_array_kernel, devices=devices - ) - add_function_test(TestGenerics, "test_generic_type_cast", test_generic_type_cast, devices=devices) - add_function_test(TestGenerics, "test_generic_type_construction", test_generic_type_construction, devices=devices) - add_function_test( - TestGenerics, "test_generic_scalar_construction", test_generic_scalar_construction, devices=devices - ) - add_function_test(TestGenerics, "test_generic_type_as_argument", test_generic_type_as_argument, devices=devices) - - foo = Foo() - foo.x = 17.0 - foo.y = 25.0 - foo.z = 42.0 - - bar = Bar() - bar.x = wp.vec3(1, 2, 3) - bar.y = wp.vec3(10, 20, 30) - bar.z = wp.vec3(11, 22, 33) - - add_kernel_test( - TestGenerics, - name="test_generic_struct_kernel", - kernel=test_generic_struct_kernel, - dim=1, - inputs=[foo], - devices=devices, - ) - add_kernel_test( - TestGenerics, - name="test_generic_struct_kernel", - kernel=test_generic_struct_kernel, - dim=1, - inputs=[bar], - devices=devices, - ) - - add_kernel_test( - TestGenerics, - name="test_generic_struct_construction_kernel", - kernel=test_generic_struct_construction_kernel, - dim=1, - inputs=[foo], - devices=devices, - ) - add_kernel_test( - TestGenerics, - name="test_generic_struct_construction_kernel", - kernel=test_generic_struct_construction_kernel, - dim=1, - inputs=[bar], - devices=devices, - ) - - add_function_test(TestGenerics, "test_type_operator_mispell", test_type_operator_mispell, devices=devices) - add_function_test(TestGenerics, "test_type_attribute_error", test_type_attribute_error, devices=devices) - - return TestGenerics - +class TestGenerics(unittest.TestCase): + pass + + +devices = get_test_devices() + +add_kernel_test(TestGenerics, name="test_generic_adder", kernel=test_generic_adder, dim=1, devices=devices) +add_kernel_test(TestGenerics, name="test_specialized_func", kernel=test_specialized_func, dim=1, devices=devices) + +add_function_test(TestGenerics, "test_generic_array_kernel", test_generic_array_kernel, devices=devices) +add_function_test(TestGenerics, "test_generic_accumulator_kernel", test_generic_accumulator_kernel, devices=devices) +add_function_test(TestGenerics, "test_generic_fill", test_generic_fill, devices=devices) +add_function_test(TestGenerics, "test_generic_fill_overloads", test_generic_fill_overloads, devices=devices) +add_function_test(TestGenerics, "test_generic_transform_kernel", test_generic_transform_kernel, devices=devices) +add_function_test( + TestGenerics, "test_generic_transform_array_kernel", test_generic_transform_array_kernel, devices=devices +) +add_function_test(TestGenerics, "test_generic_type_cast", test_generic_type_cast, devices=devices) +add_function_test(TestGenerics, "test_generic_type_construction", test_generic_type_construction, devices=devices) +add_function_test(TestGenerics, "test_generic_scalar_construction", test_generic_scalar_construction, devices=devices) +add_function_test(TestGenerics, "test_generic_type_as_argument", test_generic_type_as_argument, devices=devices) + +foo = Foo() +foo.x = 17.0 +foo.y = 25.0 +foo.z = 42.0 + +bar = Bar() +bar.x = wp.vec3(1, 2, 3) +bar.y = wp.vec3(10, 20, 30) +bar.z = wp.vec3(11, 22, 33) + +add_kernel_test( + TestGenerics, + name="test_generic_struct_kernel", + kernel=test_generic_struct_kernel, + dim=1, + inputs=[foo], + devices=devices, +) +add_kernel_test( + TestGenerics, + name="test_generic_struct_kernel", + kernel=test_generic_struct_kernel, + dim=1, + inputs=[bar], + devices=devices, +) + +add_kernel_test( + TestGenerics, + name="test_generic_struct_construction_kernel", + kernel=test_generic_struct_construction_kernel, + dim=1, + inputs=[foo], + devices=devices, +) +add_kernel_test( + TestGenerics, + name="test_generic_struct_construction_kernel", + kernel=test_generic_struct_construction_kernel, + dim=1, + inputs=[bar], + devices=devices, +) +add_function_test(TestGenerics, "test_type_operator_mispell", test_type_operator_mispell, devices=devices) +add_function_test(TestGenerics, "test_type_attribute_error", test_type_attribute_error, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_grad.py b/warp/tests/test_grad.py index d8ed5d062..6b7d74cae 100644 --- a/warp/tests/test_grad.py +++ b/warp/tests/test_grad.py @@ -11,7 +11,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -67,26 +67,26 @@ def test_for_loop_grad(test, device): def test_for_loop_graph_grad(test, device): + wp.load_module(device=device) + n = 32 val = np.ones(n, dtype=np.float32) x = wp.array(val, device=device, requires_grad=True) sum = wp.zeros(1, dtype=wp.float32, device=device, requires_grad=True) - wp.force_load() - - wp.capture_begin() - - tape = wp.Tape() - with tape: - wp.launch(for_loop_grad, dim=1, inputs=[n, x, sum], device=device) - - tape.backward(loss=sum) + wp.capture_begin(device, force_module_load=False) + try: + tape = wp.Tape() + with tape: + wp.launch(for_loop_grad, dim=1, inputs=[n, x, sum], device=device) - graph = wp.capture_end() + tape.backward(loss=sum) + finally: + graph = wp.capture_end(device) wp.capture_launch(graph) - wp.synchronize() + wp.synchronize_device(device) # ensure forward pass outputs persist assert_np_equal(sum.numpy(), 2.0 * np.sum(x.numpy())) @@ -94,7 +94,7 @@ def test_for_loop_graph_grad(test, device): assert_np_equal(x.grad.numpy(), 2.0 * val) wp.capture_launch(graph) - wp.synchronize() + wp.synchronize_device(device) @wp.kernel @@ -610,31 +610,31 @@ def test_struct_attribute_gradient(test_case, device): test_case.assertEqual(src.grad.numpy()[0], 5.0) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestGrad(parent): - pass +class TestGrad(unittest.TestCase): + pass - # add_function_test(TestGrad, "test_while_loop_grad", test_while_loop_grad, devices=devices) - add_function_test(TestGrad, "test_for_loop_nested_for_grad", test_for_loop_nested_for_grad, devices=devices) - add_function_test(TestGrad, "test_scalar_grad", test_scalar_grad, devices=devices) - add_function_test(TestGrad, "test_for_loop_grad", test_for_loop_grad, devices=devices) - add_function_test(TestGrad, "test_for_loop_graph_grad", test_for_loop_graph_grad, devices=wp.get_cuda_devices()) - add_function_test(TestGrad, "test_for_loop_nested_if_grad", test_for_loop_nested_if_grad, devices=devices) - add_function_test(TestGrad, "test_preserve_outputs_grad", test_preserve_outputs_grad, devices=devices) - add_function_test(TestGrad, "test_vector_math_grad", test_vector_math_grad, devices=devices) - add_function_test(TestGrad, "test_matrix_math_grad", test_matrix_math_grad, devices=devices) - add_function_test(TestGrad, "test_3d_math_grad", test_3d_math_grad, devices=devices) - add_function_test(TestGrad, "test_multi_valued_function_grad", test_multi_valued_function_grad, devices=devices) - add_function_test(TestGrad, "test_mesh_grad", test_mesh_grad, devices=devices) - add_function_test(TestGrad, "test_name_clash", test_name_clash, devices=devices) - add_function_test(TestGrad, "test_struct_attribute_gradient", test_struct_attribute_gradient, devices=devices) - return TestGrad +# add_function_test(TestGrad, "test_while_loop_grad", test_while_loop_grad, devices=devices) +add_function_test(TestGrad, "test_for_loop_nested_for_grad", test_for_loop_nested_for_grad, devices=devices) +add_function_test(TestGrad, "test_scalar_grad", test_scalar_grad, devices=devices) +add_function_test(TestGrad, "test_for_loop_grad", test_for_loop_grad, devices=devices) +add_function_test( + TestGrad, "test_for_loop_graph_grad", test_for_loop_graph_grad, devices=get_unique_cuda_test_devices() +) +add_function_test(TestGrad, "test_for_loop_nested_if_grad", test_for_loop_nested_if_grad, devices=devices) +add_function_test(TestGrad, "test_preserve_outputs_grad", test_preserve_outputs_grad, devices=devices) +add_function_test(TestGrad, "test_vector_math_grad", test_vector_math_grad, devices=devices) +add_function_test(TestGrad, "test_matrix_math_grad", test_matrix_math_grad, devices=devices) +add_function_test(TestGrad, "test_3d_math_grad", test_3d_math_grad, devices=devices) +add_function_test(TestGrad, "test_multi_valued_function_grad", test_multi_valued_function_grad, devices=devices) +add_function_test(TestGrad, "test_mesh_grad", test_mesh_grad, devices=devices) +add_function_test(TestGrad, "test_name_clash", test_name_clash, devices=devices) +add_function_test(TestGrad, "test_struct_attribute_gradient", test_struct_attribute_gradient, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_grad_customs.py b/warp/tests/test_grad_customs.py index a4d7bbf6e..eee0353c8 100644 --- a/warp/tests/test_grad_customs.py +++ b/warp/tests/test_grad_customs.py @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -160,19 +160,17 @@ def test_custom_overload_grad(test, device): # fmt: on -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestGradCustoms(parent): - pass - add_function_test(TestGradCustoms, "test_custom_replay_grad", test_custom_replay_grad, devices=devices) - add_function_test(TestGradCustoms, "test_custom_overload_grad", test_custom_overload_grad, devices=devices) +class TestGradCustoms(unittest.TestCase): + pass - return TestGradCustoms + +add_function_test(TestGradCustoms, "test_custom_replay_grad", test_custom_replay_grad, devices=devices) +add_function_test(TestGradCustoms, "test_custom_overload_grad", test_custom_overload_grad, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_hash_grid.py b/warp/tests/test_hash_grid.py index 177d1b81a..ff9e45f2c 100644 --- a/warp/tests/test_hash_grid.py +++ b/warp/tests/test_hash_grid.py @@ -10,8 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() @@ -73,6 +72,7 @@ def count_neighbors_reference( def test_hashgrid_query(test, device): + wp.load_module(device=device) rng = np.random.default_rng(123) grid = wp.HashGrid(dim_x, dim_y, dim_z, device) @@ -134,19 +134,15 @@ def particle_grid(dim_x, dim_y, dim_z, lower, radius, jitter): test.assertTrue(np.array_equal(counts, counts_ref)) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestHashGrid(parent): - pass - add_function_test(TestHashGrid, "test_hashgrid_query", test_hashgrid_query, devices=devices) +class TestHashGrid(unittest.TestCase): + pass - return TestHashGrid +add_function_test(TestHashGrid, "test_hashgrid_query", test_hashgrid_query, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - wp.force_load() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_import.py b/warp/tests/test_import.py index d0d60298a..11025cc36 100644 --- a/warp/tests/test_import.py +++ b/warp/tests/test_import.py @@ -5,20 +5,14 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path -import numpy as np -import math +import unittest import warp as wp -from warp.tests.test_base import * - -import unittest +import warp.tests.test_func as test_func +from warp.tests.unittest_utils import * wp.init() -# from test_func import sqr -import warp.tests.test_func as test_func - @wp.kernel def test_import_func(): @@ -30,24 +24,16 @@ def test_import_func(): wp.expect_eq(y, 8.0) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestImport(parent): - pass +class TestImport(unittest.TestCase): + pass - add_kernel_test(TestImport, kernel=test_import_func, name="test_import_func", dim=1, devices=devices) - return TestImport +add_kernel_test(TestImport, kernel=test_import_func, name="test_import_func", dim=1, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - c = register(unittest.TestCase) - # unittest.main(verbosity=2) - - wp.force_load() - - loader = unittest.defaultTestLoader - testSuite = loader.loadTestsFromTestCase(c) - testSuite.debug() + unittest.main(verbosity=2) diff --git a/warp/tests/test_indexedarray.py b/warp/tests/test_indexedarray.py index 4e1c9af6f..d33be60eb 100644 --- a/warp/tests/test_indexedarray.py +++ b/warp/tests/test_indexedarray.py @@ -12,7 +12,7 @@ import warp as wp from warp.tests.test_array import FillStruct -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -1106,31 +1106,29 @@ def test_indexedarray_fill_struct(test, device): assert_np_equal(a4.numpy(), np.zeros(a4.shape, dtype=nptype)) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestIndexedArray(parent): - pass - add_function_test(TestIndexedArray, "test_indexedarray_1d", test_indexedarray_1d, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_2d", test_indexedarray_2d, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_3d", test_indexedarray_3d, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_4d", test_indexedarray_4d, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_mixed", test_indexedarray_mixed, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_shape", test_indexedarray_shape, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_getitem", test_indexedarray_getitem, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_slicing", test_indexedarray_slicing, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_generics", test_indexedarray_generics, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_empty", test_indexedarray_empty, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_fill_scalar", test_indexedarray_fill_scalar, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_fill_vector", test_indexedarray_fill_vector, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_fill_matrix", test_indexedarray_fill_matrix, devices=devices) - add_function_test(TestIndexedArray, "test_indexedarray_fill_struct", test_indexedarray_fill_struct, devices=devices) +class TestIndexedArray(unittest.TestCase): + pass - return TestIndexedArray + +add_function_test(TestIndexedArray, "test_indexedarray_1d", test_indexedarray_1d, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_2d", test_indexedarray_2d, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_3d", test_indexedarray_3d, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_4d", test_indexedarray_4d, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_mixed", test_indexedarray_mixed, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_shape", test_indexedarray_shape, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_getitem", test_indexedarray_getitem, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_slicing", test_indexedarray_slicing, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_generics", test_indexedarray_generics, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_empty", test_indexedarray_empty, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_fill_scalar", test_indexedarray_fill_scalar, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_fill_vector", test_indexedarray_fill_vector, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_fill_matrix", test_indexedarray_fill_matrix, devices=devices) +add_function_test(TestIndexedArray, "test_indexedarray_fill_struct", test_indexedarray_fill_struct, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_intersect.py b/warp/tests/test_intersect.py index c19214350..1f0a64be0 100644 --- a/warp/tests/test_intersect.py +++ b/warp/tests/test_intersect.py @@ -1,8 +1,16 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest -import warp as wp import numpy as np -from warp.tests.test_base import * + +import warp as wp +from warp.tests.unittest_utils import * wp.init() @@ -44,18 +52,16 @@ def test_intersect_tri(test, device): assert_np_equal(result.numpy(), np.array([0])) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestIntersect(parent): - pass +class TestIntersect(unittest.TestCase): + pass - add_function_test(TestIntersect, "test_intersect_tri", test_intersect_tri, devices=devices) - return TestIntersect +add_function_test(TestIntersect, "test_intersect_tri", test_intersect_tri, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_large.py b/warp/tests/test_large.py index f35f0fde1..e32e6bdd3 100644 --- a/warp/tests/test_large.py +++ b/warp/tests/test_large.py @@ -1,4 +1,4 @@ -# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. # NVIDIA CORPORATION and its licensors retain all intellectual property # and proprietary rights in and to this software, related documentation # and any modifications thereto. Any use, reproduction, disclosure or @@ -9,7 +9,7 @@ import unittest import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -114,30 +114,28 @@ def test_large_arrays_fast(test, device): assert_np_equal(a1.numpy(), np.zeros_like(a1.numpy())) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestLarge(parent): - pass - add_function_test( - TestLarge, "test_large_launch_large_kernel", test_large_launch_large_kernel, devices=wp.get_cuda_devices() - ) +class TestLarge(unittest.TestCase): + pass - add_function_test(TestLarge, "test_large_launch_max_blocks", test_large_launch_max_blocks, devices=devices) - add_function_test( - TestLarge, - "test_large_launch_very_large_kernel", - test_large_launch_very_large_kernel, - devices=wp.get_cuda_devices(), - ) - add_function_test(TestLarge, "test_large_arrays_fast", test_large_arrays_fast, devices=devices) +add_function_test( + TestLarge, "test_large_launch_large_kernel", test_large_launch_large_kernel, devices=get_unique_cuda_test_devices() +) + +add_function_test(TestLarge, "test_large_launch_max_blocks", test_large_launch_max_blocks, devices=devices) +add_function_test( + TestLarge, + "test_large_launch_very_large_kernel", + test_large_launch_very_large_kernel, + devices=get_unique_cuda_test_devices(), +) - return TestLarge +add_function_test(TestLarge, "test_large_arrays_fast", test_large_arrays_fast, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_launch.py b/warp/tests/test_launch.py index ea578adec..6a13d33b0 100644 --- a/warp/tests/test_launch.py +++ b/warp/tests/test_launch.py @@ -7,11 +7,10 @@ import unittest -# include parent path import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -306,27 +305,25 @@ def test_launch_tuple_args(test, device): assert_np_equal(out.numpy(), np.array((0, 3, 6, 9))) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestLaunch(parent): - pass - add_function_test(TestLaunch, "test_launch_1d", test1d, devices=devices) - add_function_test(TestLaunch, "test_launch_2d", test2d, devices=devices) - add_function_test(TestLaunch, "test_launch_3d", test3d, devices=devices) - add_function_test(TestLaunch, "test_launch_4d", test4d, devices=devices) +class TestLaunch(unittest.TestCase): + pass - add_function_test(TestLaunch, "test_launch_cmd", test_launch_cmd, devices=devices) - add_function_test(TestLaunch, "test_launch_cmd_set_param", test_launch_cmd_set_param, devices=devices) - add_function_test(TestLaunch, "test_launch_cmd_set_ctype", test_launch_cmd_set_ctype, devices=devices) - add_function_test(TestLaunch, "test_launch_cmd_set_dim", test_launch_cmd_set_dim, devices=devices) - add_function_test(TestLaunch, "test_launch_cmd_empty", test_launch_cmd_empty, devices=devices) - return TestLaunch +add_function_test(TestLaunch, "test_launch_1d", test1d, devices=devices) +add_function_test(TestLaunch, "test_launch_2d", test2d, devices=devices) +add_function_test(TestLaunch, "test_launch_3d", test3d, devices=devices) +add_function_test(TestLaunch, "test_launch_4d", test4d, devices=devices) + +add_function_test(TestLaunch, "test_launch_cmd", test_launch_cmd, devices=devices) +add_function_test(TestLaunch, "test_launch_cmd_set_param", test_launch_cmd_set_param, devices=devices) +add_function_test(TestLaunch, "test_launch_cmd_set_ctype", test_launch_cmd_set_ctype, devices=devices) +add_function_test(TestLaunch, "test_launch_cmd_set_dim", test_launch_cmd_set_dim, devices=devices) +add_function_test(TestLaunch, "test_launch_cmd_empty", test_launch_cmd_empty, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_lerp.py b/warp/tests/test_lerp.py index 52f0f8db8..187b2d663 100644 --- a/warp/tests/test_lerp.py +++ b/warp/tests/test_lerp.py @@ -5,14 +5,16 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. +import unittest from dataclasses import dataclass from typing import Any -import unittest import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * + +wp.init() @dataclass @@ -162,8 +164,6 @@ def check_backwards(self): ), } -wp.init() - def test_lerp(test, device): def make_kernel_fn(data_type): @@ -184,78 +184,78 @@ def fn( key=f"test_lerp_{data_type.__name__}_kernel", ) - for test_data in TEST_DATA[data_type]: - a = wp.array( - [test_data.a], - dtype=data_type, - device=device, - requires_grad=True, - ) - b = wp.array( - [test_data.b], - dtype=data_type, - device=device, - requires_grad=True, - ) - t = wp.array( - [test_data.t], - dtype=float, - device=device, - requires_grad=True, - ) - out = wp.array( - [0] * wp.types.type_length(data_type), - dtype=data_type, - device=device, - requires_grad=True, - ) - - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[a, b, t, out], + with test.subTest(data_type=data_type): + for test_data in TEST_DATA[data_type]: + a = wp.array( + [test_data.a], + dtype=data_type, device=device, + requires_grad=True, ) - - assert_np_equal( - out.numpy(), - np.array([test_data.expected]), - tol=1e-6, - ) - - if test_data.check_backwards(): - tape.backward(out) - - assert_np_equal( - tape.gradients[a].numpy(), - np.array([test_data.expected_adj_a]), - tol=1e-6, + b = wp.array( + [test_data.b], + dtype=data_type, + device=device, + requires_grad=True, ) - assert_np_equal( - tape.gradients[b].numpy(), - np.array([test_data.expected_adj_b]), - tol=1e-6, + t = wp.array( + [test_data.t], + dtype=float, + device=device, + requires_grad=True, + ) + out = wp.array( + [0] * wp.types.type_length(data_type), + dtype=data_type, + device=device, + requires_grad=True, ) + + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[a, b, t, out], + device=device, + ) + assert_np_equal( - tape.gradients[t].numpy(), - np.array([test_data.expected_adj_t]), + out.numpy(), + np.array([test_data.expected]), tol=1e-6, ) + if test_data.check_backwards(): + tape.backward(out) + + assert_np_equal( + tape.gradients[a].numpy(), + np.array([test_data.expected_adj_a]), + tol=1e-6, + ) + assert_np_equal( + tape.gradients[b].numpy(), + np.array([test_data.expected_adj_b]), + tol=1e-6, + ) + assert_np_equal( + tape.gradients[t].numpy(), + np.array([test_data.expected_adj_t]), + tol=1e-6, + ) + + +devices = get_test_devices() + -def register(parent): - devices = get_test_devices() +class TestLerp(unittest.TestCase): + pass - class TestLerp(parent): - pass - add_function_test(TestLerp, "test_lerp", test_lerp, devices=devices) - return TestLerp +add_function_test(TestLerp, "test_lerp", test_lerp, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_lvalue.py b/warp/tests/test_lvalue.py index 0eb7471c4..5cea866f1 100644 --- a/warp/tests/test_lvalue.py +++ b/warp/tests/test_lvalue.py @@ -1,11 +1,16 @@ -import warp as wp -import numpy as np -from warp.tests.test_base import * +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. import unittest +import warp as wp +from warp.tests.unittest_utils import * + wp.init() -wp.config.mode = "debug" @wp.kernel @@ -450,45 +455,39 @@ def test_swizzle(test, device): raise AssertionError(f"Unexpected result, got: {f} expected: {expected}") -def test_swizzle_error_invalid_attribute(test, device): - v = wp.vec3(1, 2, 3) - with test.assertRaisesRegex( - AttributeError, - r"'vec3f' object has no attribute 'foo'$", - ): - v.foo - - try: - v.bar = 123 - except AttributeError: - test.fail() +devices = get_test_devices() -def register(parent): - devices = get_test_devices() +class TestLValue(unittest.TestCase): + def test_swizzle_error_invalid_attribute(self): + v = wp.vec3(1, 2, 3) + with self.assertRaisesRegex( + AttributeError, + r"'vec3f' object has no attribute 'foo'$", + ): + v.foo - class TestLValue(parent): - pass + try: + v.bar = 123 + except AttributeError: + self.fail() - add_function_test(TestLValue, "test_rmw_array", test_rmw_array, devices=devices) - add_function_test(TestLValue, "test_rmw_array_struct", test_rmw_array_struct, devices=devices) - add_function_test(TestLValue, "test_lookup", test_lookup, devices=devices) - add_function_test(TestLValue, "test_lookup2", test_lookup2, devices=devices) - add_function_test(TestLValue, "test_grad", test_grad, devices=devices) - add_function_test(TestLValue, "test_unary", test_unary, devices=devices) - add_function_test(TestLValue, "test_rvalue", test_rvalue, devices=devices) - add_function_test(TestLValue, "test_intermediate", test_intermediate, devices=devices) - add_function_test(TestLValue, "test_array_assign", test_array_assign, devices=devices) - add_function_test(TestLValue, "test_array_struct_assign", test_array_struct_assign, devices=devices) - add_function_test(TestLValue, "test_array_struct_struct_assign", test_array_struct_struct_assign, devices=devices) - add_function_test(TestLValue, "test_complex", test_complex, devices=devices) - add_function_test(TestLValue, "test_swizzle", test_swizzle, devices=devices) - add_function_test(TestLValue, "test_swizzle_error_invalid_attribute", test_swizzle_error_invalid_attribute) - return TestLValue +add_function_test(TestLValue, "test_rmw_array", test_rmw_array, devices=devices) +add_function_test(TestLValue, "test_rmw_array_struct", test_rmw_array_struct, devices=devices) +add_function_test(TestLValue, "test_lookup", test_lookup, devices=devices) +add_function_test(TestLValue, "test_lookup2", test_lookup2, devices=devices) +add_function_test(TestLValue, "test_grad", test_grad, devices=devices) +add_function_test(TestLValue, "test_unary", test_unary, devices=devices) +add_function_test(TestLValue, "test_rvalue", test_rvalue, devices=devices) +add_function_test(TestLValue, "test_intermediate", test_intermediate, devices=devices) +add_function_test(TestLValue, "test_array_assign", test_array_assign, devices=devices) +add_function_test(TestLValue, "test_array_struct_assign", test_array_struct_assign, devices=devices) +add_function_test(TestLValue, "test_array_struct_struct_assign", test_array_struct_struct_assign, devices=devices) +add_function_test(TestLValue, "test_complex", test_complex, devices=devices) +add_function_test(TestLValue, "test_swizzle", test_swizzle, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_marching_cubes.py b/warp/tests/test_marching_cubes.py index 2d63e8a91..5b112e2cb 100644 --- a/warp/tests/test_marching_cubes.py +++ b/warp/tests/test_marching_cubes.py @@ -5,14 +5,12 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -# include parent path +import unittest + import numpy as np -import math import warp as wp -from warp.tests.test_base import * - -import unittest +from warp.tests.unittest_utils import * wp.init() @@ -39,7 +37,7 @@ def test_marching_cubes(test, device): radius = dim / 4.0 - wp.launch(make_field, dim=field.shape, inputs=[field, wp.vec3(dim / 2, dim / 2, dim / 2), radius], device="cuda") + wp.launch(make_field, dim=field.shape, inputs=[field, wp.vec3(dim / 2, dim / 2, dim / 2), radius], device=device) iso.surface(field=field, threshold=0.0) @@ -52,18 +50,16 @@ def test_marching_cubes(test, device): iso.resize(nx=dim * 2, ny=dim * 2, nz=dim * 2, max_verts=max_verts, max_tris=max_tris) -def register(parent): - devices = ["cuda"] +devices = get_unique_cuda_test_devices() + - class TestMarchingCubes(parent): - pass +class TestMarchingCubes(unittest.TestCase): + pass - add_function_test(TestMarchingCubes, "test_marching_cubes", test_marching_cubes, devices=devices) - return TestMarchingCubes +add_function_test(TestMarchingCubes, "test_marching_cubes", test_marching_cubes, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_mat.py b/warp/tests/test_mat.py index 321bc1cf9..ee36736c5 100644 --- a/warp/tests/test_mat.py +++ b/warp/tests/test_mat.py @@ -8,8 +8,9 @@ import unittest import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -21,20 +22,8 @@ np.byte, ] -np_unsigned_int_types = [ - np.uint8, - np.uint16, - np.uint32, - np.uint64, - np.ubyte, -] - -np_int_types = np_signed_int_types + np_unsigned_int_types - np_float_types = [np.float16, np.float32, np.float64] -np_scalar_types = np_int_types + np_float_types - def randvals(rng, shape, dtype): if dtype in np_float_types: @@ -64,415 +53,9 @@ def output_select_kernel_fn( return getkernel(output_select_kernel_fn, suffix=dtype.__name__) - -def test_arrays(test, device, dtype): - rng = np.random.default_rng(123) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) - - v2_np = randvals(rng, [10, 2, 2], dtype) - v3_np = randvals(rng, [10, 3, 3], dtype) - v4_np = randvals(rng, [10, 4, 4], dtype) - v5_np = randvals(rng, [10, 5, 5], dtype) - v32_np = randvals(rng, [10, 3, 2], dtype) - - v2 = wp.array(v2_np, dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(v3_np, dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(v4_np, dtype=mat44, requires_grad=True, device=device) - v5 = wp.array(v5_np, dtype=mat55, requires_grad=True, device=device) - v32 = wp.array(v32_np, dtype=mat32, requires_grad=True, device=device) - - assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) - assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) - assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) - assert_np_equal(v5.numpy(), v5_np, tol=1.0e-6) - assert_np_equal(v32.numpy(), v32_np, tol=1.0e-6) - - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - - v2 = wp.array(v2_np, dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(v3_np, dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(v4_np, dtype=mat44, requires_grad=True, device=device) - - assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) - assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) - assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) - - -def test_components(test, device, dtype): - # test accessing matrix components from Python - this is especially important - # for float16, which requires special handling internally - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat23 = wp.types.matrix(shape=(2, 3), dtype=wptype) - - m = mat23(1, 2, 3, 4, 5, 6) - - # test __getitem__ for row vectors - r0 = m[0] - r1 = m[1] - test.assertEqual(r0[0], 1) - test.assertEqual(r0[1], 2) - test.assertEqual(r0[2], 3) - test.assertEqual(r1[0], 4) - test.assertEqual(r1[1], 5) - test.assertEqual(r1[2], 6) - - # test __getitem__ for individual components - test.assertEqual(m[0, 0], 1) - test.assertEqual(m[0, 1], 2) - test.assertEqual(m[0, 2], 3) - test.assertEqual(m[1, 0], 4) - test.assertEqual(m[1, 1], 5) - test.assertEqual(m[1, 2], 6) - - # test __setitem__ for row vectors - m[0] = [7, 8, 9] - m[1] = [10, 11, 12] - test.assertEqual(m[0, 0], 7) - test.assertEqual(m[0, 1], 8) - test.assertEqual(m[0, 2], 9) - test.assertEqual(m[1, 0], 10) - test.assertEqual(m[1, 1], 11) - test.assertEqual(m[1, 2], 12) - - # test __setitem__ for individual components - m[0, 0] = 13 - m[0, 1] = 14 - m[0, 2] = 15 - m[1, 0] = 16 - m[1, 1] = 17 - m[1, 2] = 18 - test.assertEqual(m[0, 0], 13) - test.assertEqual(m[0, 1], 14) - test.assertEqual(m[0, 2], 15) - test.assertEqual(m[1, 0], 16) - test.assertEqual(m[1, 1], 17) - test.assertEqual(m[1, 2], 18) - - -def test_py_arithmetic_ops(test, device, dtype): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - def make_mat(*args): - if wptype in wp.types.int_types: - # Cast to the correct integer type to simulate wrapping. - return tuple(tuple(wptype._type_(x).value for x in row) for row in args) - - return args - - def make_vec(*args): - if wptype in wp.types.int_types: - # Cast to the correct integer type to simulate wrapping. - return tuple(wptype._type_(x).value for x in args) - - return args - - mat_cls = wp.mat((3, 3), wptype) - vec_cls = wp.vec(3, wptype) - - m = mat_cls(((-1, 2, 3), (4, -5, 6), (7, 8, -9))) - test.assertSequenceEqual(+m, make_mat((-1, 2, 3), (4, -5, 6), (7, 8, -9))) - test.assertSequenceEqual(-m, make_mat((1, -2, -3), (-4, 5, -6), (-7, -8, 9))) - test.assertSequenceEqual(m + mat_cls((5, 5, 5) * 3), make_mat((4, 7, 8), (9, 0, 11), (12, 13, -4))) - test.assertSequenceEqual(m - mat_cls((5, 5, 5) * 3), make_mat((-6, -3, -2), (-1, -10, 1), (2, 3, -14))) - test.assertSequenceEqual(m * vec_cls(5, 5, 5), make_vec(20, 25, 30)) - test.assertSequenceEqual(m @ vec_cls(5, 5, 5), make_vec(20, 25, 30)) - test.assertSequenceEqual(vec_cls(5, 5, 5) * m, make_vec(50, 25, 0)) - test.assertSequenceEqual(vec_cls(5, 5, 5) @ m, make_vec(50, 25, 0)) - - m = mat_cls(((2, 4, 6), (8, 10, 12), (14, 16, 18))) - test.assertSequenceEqual(m * wptype(2), make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) - test.assertSequenceEqual(wptype(2) * m, make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) - test.assertSequenceEqual(m / wptype(2), make_mat((1, 2, 3), (4, 5, 6), (7, 8, 9))) - test.assertSequenceEqual(wptype(5040) / m, make_mat((2520, 1260, 840), (630, 504, 420), (360, 315, 280))) - test.assertSequenceEqual(m * vec_cls(5, 5, 5), make_vec(60, 150, 240)) - test.assertSequenceEqual(m @ vec_cls(5, 5, 5), make_vec(60, 150, 240)) - test.assertSequenceEqual(vec_cls(5, 5, 5) * m, make_vec(120, 150, 180)) - test.assertSequenceEqual(vec_cls(5, 5, 5) @ m, make_vec(120, 150, 180)) - - -def test_constants(test, device, dtype, register_kernels=False): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) - - cm22 = wp.constant(mat22(22)) - cm33 = wp.constant(mat33(33)) - cm44 = wp.constant(mat44(44)) - cm55 = wp.constant(mat55(55)) - cm32 = wp.constant(mat32(32)) - - def check_matrix_constants(): - wp.expect_eq(cm22, mat22(wptype(22))) - wp.expect_eq(cm33, mat33(wptype(33))) - wp.expect_eq(cm44, mat44(wptype(44))) - wp.expect_eq(cm55, mat55(wptype(55))) - wp.expect_eq(cm32, mat32(wptype(32))) - - kernel = getkernel(check_matrix_constants, suffix=dtype.__name__) - - if register_kernels: - return - wp.launch(kernel, dim=1, inputs=[]) -def test_constructors(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_scalar_mat_constructor( - input: wp.array(dtype=wptype), - outcomponents: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - m2result = wptype(2) * mat22(input[0]) - m3result = wptype(2) * mat33(input[0]) - m4result = wptype(2) * mat44(input[0]) - m5result = wptype(2) * mat55(input[0]) - - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = m2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = m3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = m4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = m5result[i, j] - idx = idx + 1 - - def check_component_mat_constructor( - input: wp.array(dtype=wptype), - outcomponents: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - m2result = wptype(2) * mat22(input[0], input[1], input[2], input[3]) - m3result = wptype(2) * mat33( - input[4], - input[5], - input[6], - input[7], - input[8], - input[9], - input[10], - input[11], - input[12], - ) - m4result = wptype(2) * mat44( - input[13], - input[14], - input[15], - input[16], - input[17], - input[18], - input[19], - input[20], - input[21], - input[22], - input[23], - input[24], - input[25], - input[26], - input[27], - input[28], - ) - m5result = wptype(2) * mat55( - input[29], - input[30], - input[31], - input[32], - input[33], - input[34], - input[35], - input[36], - input[37], - input[38], - input[39], - input[40], - input[41], - input[42], - input[43], - input[44], - input[45], - input[46], - input[47], - input[48], - input[49], - input[50], - input[51], - input[52], - input[53], - ) - - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = m2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = m3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = m4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = m5result[i, j] - idx = idx + 1 - - def check_vector_mat_constructor( - input: wp.array(dtype=wptype), - outcomponents: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - m2result = wptype(2) * mat22(vec2(input[0], input[2]), vec2(input[1], input[3])) - m3result = wptype(2) * mat33( - vec3(input[4], input[7], input[10]), - vec3(input[5], input[8], input[11]), - vec3(input[6], input[9], input[12]), - ) - m4result = wptype(2) * mat44( - vec4(input[13], input[17], input[21], input[25]), - vec4(input[14], input[18], input[22], input[26]), - vec4(input[15], input[19], input[23], input[27]), - vec4(input[16], input[20], input[24], input[28]), - ) - m5result = wptype(2) * mat55( - vec5(input[29], input[34], input[39], input[44], input[49]), - vec5(input[30], input[35], input[40], input[45], input[50]), - vec5(input[31], input[36], input[41], input[46], input[51]), - vec5(input[32], input[37], input[42], input[47], input[52]), - vec5(input[33], input[38], input[43], input[48], input[53]), - ) - - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = m2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = m3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = m4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = m5result[i, j] - idx = idx + 1 - - kernel = getkernel(check_scalar_mat_constructor, suffix=dtype.__name__) - compkernel = getkernel(check_component_mat_constructor, suffix=dtype.__name__) - veckernel = getkernel(check_vector_mat_constructor, suffix=dtype.__name__) - - if register_kernels: - return - - input = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) - val = input.numpy()[0] - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy()[:4], 2 * val * np.ones(2 * 2), tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * val * np.ones(3 * 3), tol=tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * val * np.ones(4 * 4), tol=tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * val * np.ones(5 * 5), tol=tol) - - if dtype in np_float_types: - for idx in range(len(outcomponents)): - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) - tape.backward(loss=out) - test.assertEqual(tape.gradients[input].numpy()[0], 2) - tape.zero() - - input = wp.array(randvals(rng, [2 * 2 + 3 * 3 + 4 * 4 + 5 * 5], dtype), requires_grad=True, device=device) - - wp.launch(compkernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) - assert_np_equal(2 * input.numpy(), outcomponents.numpy(), tol=10 * tol) - - if dtype in np_float_types: - for idx in range(len(outcomponents)): - tape = wp.Tape() - with tape: - wp.launch(compkernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) - tape.backward(loss=out) - expectedgrads = np.zeros(len(input)) - expectedgrads[idx] = 2 - assert_np_equal(tape.gradients[input].numpy(), expectedgrads) - tape.zero() - - wp.launch(veckernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) - assert_np_equal(2 * input.numpy(), outcomponents.numpy(), tol=10 * tol) - - if dtype in np_float_types: - for idx in range(len(outcomponents)): - tape = wp.Tape() - with tape: - wp.launch(veckernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) - tape.backward(loss=out) - expectedgrads = np.zeros(len(input)) - expectedgrads[idx] = 2 - assert_np_equal(tape.gradients[input].numpy(), expectedgrads) - tape.zero() - - def test_anon_constructor_error_shape_keyword_missing(test, device): @wp.kernel def kernel(): @@ -645,6 +228,47 @@ def test_tpl_ops_with_anon(test, device): test.assertSequenceEqual(m, ((0.0, 1.0), (2.0, 3.0))) +def test_py_arithmetic_ops(test, device, dtype): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def make_mat(*args): + if wptype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(tuple(wptype._type_(x).value for x in row) for row in args) + + return args + + def make_vec(*args): + if wptype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(wptype._type_(x).value for x in args) + + return args + + mat_cls = wp.mat((3, 3), wptype) + vec_cls = wp.vec(3, wptype) + + m = mat_cls(((-1, 2, 3), (4, -5, 6), (7, 8, -9))) + test.assertSequenceEqual(+m, make_mat((-1, 2, 3), (4, -5, 6), (7, 8, -9))) + test.assertSequenceEqual(-m, make_mat((1, -2, -3), (-4, 5, -6), (-7, -8, 9))) + test.assertSequenceEqual(m + mat_cls((5, 5, 5) * 3), make_mat((4, 7, 8), (9, 0, 11), (12, 13, -4))) + test.assertSequenceEqual(m - mat_cls((5, 5, 5) * 3), make_mat((-6, -3, -2), (-1, -10, 1), (2, 3, -14))) + test.assertSequenceEqual(m * vec_cls(5, 5, 5), make_vec(20, 25, 30)) + test.assertSequenceEqual(m @ vec_cls(5, 5, 5), make_vec(20, 25, 30)) + test.assertSequenceEqual(vec_cls(5, 5, 5) * m, make_vec(50, 25, 0)) + test.assertSequenceEqual(vec_cls(5, 5, 5) @ m, make_vec(50, 25, 0)) + + m = mat_cls(((2, 4, 6), (8, 10, 12), (14, 16, 18))) + test.assertSequenceEqual(m * wptype(2), make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) + test.assertSequenceEqual(wptype(2) * m, make_mat((4, 8, 12), (16, 20, 24), (28, 32, 36))) + test.assertSequenceEqual(m / wptype(2), make_mat((1, 2, 3), (4, 5, 6), (7, 8, 9))) + test.assertSequenceEqual(wptype(5040) / m, make_mat((2520, 1260, 840), (630, 504, 420), (360, 315, 280))) + test.assertSequenceEqual(m * vec_cls(5, 5, 5), make_vec(60, 150, 240)) + test.assertSequenceEqual(m @ vec_cls(5, 5, 5), make_vec(60, 150, 240)) + test.assertSequenceEqual(vec_cls(5, 5, 5) * m, make_vec(120, 150, 180)) + test.assertSequenceEqual(vec_cls(5, 5, 5) @ m, make_vec(120, 150, 180)) + + def test_quat_constructor(test, device, dtype, register_kernels=False): rng = np.random.default_rng(123) @@ -744,11 +368,11 @@ def check_mat_quat_constructor( idx = idx + 1 -def test_indexing(test, device, dtype, register_kernels=False): +def test_negation(test, device, dtype, register_kernels=False): rng = np.random.default_rng(123) tol = { - np.float16: 1.0e-3, + np.float16: 1.0e-2, np.float32: 1.0e-6, np.float64: 1.0e-8, }.get(dtype, 0) @@ -761,391 +385,41 @@ def test_indexing(test, device, dtype, register_kernels=False): output_select_kernel = get_select_kernel(wptype) - def check_mat_indexing( + def check_mat_negation( m2: wp.array(dtype=mat22), m3: wp.array(dtype=mat33), m4: wp.array(dtype=mat44), m5: wp.array(dtype=mat55), outcomponents: wp.array(dtype=wptype), ): + mat2 = -m2[0] + mat3 = -m3[0] + mat4 = -m4[0] + mat5 = -m5[0] + # multiply outputs by 2 so we've got something to backpropagate: idx = 0 for i in range(2): for j in range(2): - outcomponents[idx] = wptype(2) * m2[0][i, j] + outcomponents[idx] = wptype(2) * mat2[i, j] idx = idx + 1 for i in range(3): for j in range(3): - outcomponents[idx] = wptype(2) * m3[0][i, j] + outcomponents[idx] = wptype(2) * mat3[i, j] idx = idx + 1 for i in range(4): for j in range(4): - outcomponents[idx] = wptype(2) * m4[0][i, j] + outcomponents[idx] = wptype(2) * mat4[i, j] idx = idx + 1 for i in range(5): for j in range(5): - outcomponents[idx] = wptype(2) * m5[0][i, j] + outcomponents[idx] = wptype(2) * mat5[i, j] idx = idx + 1 - kernel = getkernel(check_mat_indexing, suffix=dtype.__name__) - - if register_kernels: - return - - m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy()[:4], 2 * m2.numpy().reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * m3.numpy().reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * m4.numpy().reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * m5.numpy().reshape(-1), tol=tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, input in [(2, m2), (3, m3), (4, m4), (5, m5)]: - for i in range(dim): - for j in range(dim): - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5], outputs=[outcomponents], device=device) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - expectedresult = np.zeros((dim, dim), dtype=dtype) - expectedresult[i, j] = 2 - assert_np_equal(tape.gradients[input].numpy()[0], expectedresult) - tape.zero() - idx = idx + 1 - - -def test_equality(test, device, dtype, register_kernels=False): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - def check_mat_equality(): - wp.expect_eq( - mat22(wptype(1.0), wptype(2.0), wptype(3.0), wptype(4.0)), - mat22(wptype(1.0), wptype(2.0), wptype(3.0), wptype(4.0)), - ) - wp.expect_neq( - mat22(wptype(1.0), wptype(2.0), wptype(3.0), -wptype(4.0)), - mat22(wptype(1.0), wptype(2.0), wptype(3.0), wptype(4.0)), - ) - - wp.expect_eq( - mat33( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - ), - mat33( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - ), - ) - wp.expect_neq( - mat33( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - ), - mat33( - wptype(1.0), - wptype(2.0), - wptype(3.0), - -wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - ), - ) - - wp.expect_eq( - mat44( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - ), - mat44( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - ), - ) - - wp.expect_neq( - mat44( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - ), - mat44( - -wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - ), - ) - - wp.expect_eq( - mat55( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - wptype(17.0), - wptype(18.0), - wptype(19.0), - wptype(20.0), - wptype(21.0), - wptype(22.0), - wptype(23.0), - wptype(24.0), - wptype(25.0), - ), - mat55( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - wptype(17.0), - wptype(18.0), - wptype(19.0), - wptype(20.0), - wptype(21.0), - wptype(22.0), - wptype(23.0), - wptype(24.0), - wptype(25.0), - ), - ) - - wp.expect_neq( - mat55( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - wptype(17.0), - wptype(18.0), - wptype(19.0), - wptype(20.0), - wptype(21.0), - wptype(22.0), - wptype(23.0), - wptype(24.0), - wptype(25.0), - ), - mat55( - wptype(1.0), - wptype(2.0), - wptype(3.0), - wptype(4.0), - wptype(5.0), - wptype(6.0), - wptype(7.0), - wptype(8.0), - wptype(9.0), - wptype(10.0), - wptype(11.0), - wptype(12.0), - wptype(13.0), - wptype(14.0), - wptype(15.0), - wptype(16.0), - -wptype(17.0), - wptype(18.0), - wptype(19.0), - wptype(20.0), - wptype(21.0), - wptype(22.0), - wptype(23.0), - wptype(24.0), - wptype(25.0), - ), - ) - - kernel = getkernel(check_mat_equality, suffix=dtype.__name__) - - if register_kernels: - return - - wp.launch(kernel, dim=1, inputs=[], outputs=[], device=device) - - -def test_negation(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_negation( - m2: wp.array(dtype=mat22), - m3: wp.array(dtype=mat33), - m4: wp.array(dtype=mat44), - m5: wp.array(dtype=mat55), - outcomponents: wp.array(dtype=wptype), - ): - mat2 = -m2[0] - mat3 = -m3[0] - mat4 = -m4[0] - mat5 = -m5[0] - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = wptype(2) * mat2[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = wptype(2) * mat3[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = wptype(2) * mat4[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = wptype(2) * mat5[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_negation, suffix=dtype.__name__) + kernel = getkernel(check_mat_negation, suffix=dtype.__name__) if register_kernels: return @@ -1178,1410 +452,8 @@ def check_mat_negation( tape.backward(loss=out) expectedresult = np.zeros((dim, dim), dtype=dtype) expectedresult[i, j] = -2 - assert_np_equal(tape.gradients[input].numpy()[0], expectedresult) - tape.zero() - idx = idx + 1 - - -def test_transpose(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_transpose( - m2: wp.array(dtype=mat22), - m3: wp.array(dtype=mat33), - m4: wp.array(dtype=mat44), - m5: wp.array(dtype=mat55), - m32: wp.array(dtype=mat32), - outcomponents: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - mat2 = wptype(2) * wp.transpose(m2[0]) - mat3 = wptype(2) * wp.transpose(m3[0]) - mat4 = wptype(2) * wp.transpose(m4[0]) - mat5 = wptype(2) * wp.transpose(m5[0]) - mat32 = wptype(2) * wp.transpose(m32[0]) - - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = mat2[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = mat3[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = mat4[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = mat5[i, j] - idx = idx + 1 - - for i in range(2): - for j in range(3): - outcomponents[idx] = mat32[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_transpose, suffix=dtype.__name__) - - if register_kernels: - return - - m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - m32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 2 * 3, dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy()[:4], 2 * m2.numpy()[0].T.reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * m3.numpy()[0].T.reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * m4.numpy()[0].T.reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * m5.numpy()[0].T.reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[54:], 2 * m32.numpy()[0].T.reshape(-1), tol=tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for input in [m2, m3, m4, m5]: - for i in range(input.dtype._shape_[0]): - for j in range(input.dtype._shape_[1]): - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - expectedresult = np.zeros((input.dtype._shape_[1], input.dtype._shape_[0]), dtype=dtype) - expectedresult[j, i] = 2 - assert_np_equal(tape.gradients[input].numpy()[0], expectedresult) - tape.zero() - idx = idx + 1 - - -def test_scalar_multiplication(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_scalar_mul( - s: wp.array(dtype=wptype), - m2: wp.array(dtype=mat22), - m3: wp.array(dtype=mat33), - m4: wp.array(dtype=mat44), - m5: wp.array(dtype=mat55), - outcomponents: wp.array(dtype=wptype), - outcomponents_rightmul: wp.array(dtype=wptype), - ): - m2result = s[0] * m2[0] - m3result = s[0] * m3[0] - m4result = s[0] * m4[0] - m5result = s[0] * m5[0] - - m2resultright = m2[0] * s[0] - m3resultright = m3[0] * s[0] - m4resultright = m4[0] * s[0] - m5resultright = m5[0] * s[0] - - m2result_2 = s[0] * m2[0] - m3result_2 = s[0] * m3[0] - m4result_2 = s[0] * m4[0] - m5result_2 = s[0] * m5[0] - - m2resultright_2 = m2[0] * s[0] - m3resultright_2 = m3[0] * s[0] - m4resultright_2 = m4[0] * s[0] - m5resultright_2 = m5[0] * s[0] - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = wptype(2) * m2result[i, j] - outcomponents_rightmul[idx] = wptype(2) * m2resultright[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = wptype(2) * m3result[i, j] - outcomponents_rightmul[idx] = wptype(2) * m3resultright[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = wptype(2) * m4result[i, j] - outcomponents_rightmul[idx] = wptype(2) * m4resultright[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = wptype(2) * m5result[i, j] - outcomponents_rightmul[idx] = wptype(2) * m5resultright[i, j] - idx = idx + 1 - - for i in range(2): - for j in range(2): - outcomponents[idx] = wptype(2) * m2result_2[i, j] - outcomponents_rightmul[idx] = wptype(2) * m2resultright_2[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = wptype(2) * m3result_2[i, j] - outcomponents_rightmul[idx] = wptype(2) * m3resultright_2[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = wptype(2) * m4result_2[i, j] - outcomponents_rightmul[idx] = wptype(2) * m4resultright_2[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = wptype(2) * m5result_2[i, j] - outcomponents_rightmul[idx] = wptype(2) * m5resultright_2[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_scalar_mul, suffix=dtype.__name__) - - if register_kernels: - return - - s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) - m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * (2 * 2 + 3 * 3 + 4 * 4 + 5 * 5), dtype=wptype, requires_grad=True, device=device) - outcomponents_rightmul = wp.zeros( - 2 * (2 * 2 + 3 * 3 + 4 * 4 + 5 * 5), dtype=wptype, requires_grad=True, device=device - ) - - wp.launch(kernel, dim=1, inputs=[s, m2, m3, m4, m5], outputs=[outcomponents, outcomponents_rightmul], device=device) - - sval = s.numpy()[0] - assert_np_equal(outcomponents.numpy()[:4], 2 * sval * m2.numpy().reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) - - assert_np_equal(outcomponents_rightmul.numpy()[:4], 2 * sval * m2.numpy().reshape(-1), tol=tol) - assert_np_equal(outcomponents_rightmul.numpy()[4:13], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents_rightmul.numpy()[13:29], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents_rightmul.numpy()[29:54], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) - - assert_np_equal(outcomponents.numpy()[54:58], 2 * sval * m2.numpy().reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[58:67], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[67:83], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[83:108], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) - - assert_np_equal(outcomponents_rightmul.numpy()[54:58], 2 * sval * m2.numpy().reshape(-1), tol=tol) - assert_np_equal(outcomponents_rightmul.numpy()[58:67], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents_rightmul.numpy()[67:83], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) - assert_np_equal(outcomponents_rightmul.numpy()[83:108], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, input in [(2, m2), (3, m3), (4, m4), (5, m5)]: - for i in range(dim): - for j in range(dim): - # test left mul gradient: - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[s, m2, m3, m4, m5], - outputs=[outcomponents, outcomponents_rightmul], - device=device, - ) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - expectedresult = np.zeros((dim, dim), dtype=dtype) - expectedresult[i, j] = 2 * sval - assert_np_equal(tape.gradients[input].numpy()[0], expectedresult, tol=10 * tol) - assert_np_equal(tape.gradients[s].numpy()[0], 2 * input.numpy()[0, i, j], tol=10 * tol) - tape.zero() - - # test right mul gradient: - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[s, m2, m3, m4, m5], - outputs=[outcomponents, outcomponents_rightmul], - device=device, - ) - wp.launch( - output_select_kernel, - dim=1, - inputs=[outcomponents_rightmul, idx], - outputs=[out], - device=device, - ) - tape.backward(loss=out) - expectedresult = np.zeros((dim, dim), dtype=dtype) - expectedresult[i, j] = 2 * sval - assert_np_equal(tape.gradients[input].numpy()[0], expectedresult, tol=10 * tol) - assert_np_equal(tape.gradients[s].numpy()[0], 2 * input.numpy()[0, i, j], tol=10 * tol) - tape.zero() - - idx = idx + 1 - - -def test_matvec_multiplication(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 2.0e-2, - np.float32: 5.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_vec_mul( - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v32: wp.array(dtype=vec2), - m2: wp.array(dtype=mat22), - m3: wp.array(dtype=mat33), - m4: wp.array(dtype=mat44), - m5: wp.array(dtype=mat55), - m32: wp.array(dtype=mat32), - outcomponents: wp.array(dtype=wptype), - ): - v2result = m2[0] * v2[0] - v3result = m3[0] * v3[0] - v4result = m4[0] * v4[0] - v5result = m5[0] * v5[0] - v32result = m32[0] * v32[0] - v2result_2 = m2[0] @ v2[0] - v3result_2 = m3[0] @ v3[0] - v4result_2 = m4[0] @ v4[0] - v5result_2 = m5[0] @ v5[0] - v32result_2 = m32[0] @ v32[0] - - idx = 0 - - # multiply outputs by 2 so we've got something to backpropagate: - for i in range(2): - outcomponents[idx] = wptype(2) * v2result[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v3result[i] - idx = idx + 1 - - for i in range(4): - outcomponents[idx] = wptype(2) * v4result[i] - idx = idx + 1 - - for i in range(5): - outcomponents[idx] = wptype(2) * v5result[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v32result[i] - idx = idx + 1 - - for i in range(2): - outcomponents[idx] = wptype(2) * v2result_2[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v3result_2[i] - idx = idx + 1 - - for i in range(4): - outcomponents[idx] = wptype(2) * v4result_2[i] - idx = idx + 1 - - for i in range(5): - outcomponents[idx] = wptype(2) * v5result_2[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v32result_2[i] - idx = idx + 1 - - kernel = getkernel(check_mat_vec_mul, suffix=dtype.__name__) - - if register_kernels: - return - - v2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) - v32 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) - m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - m32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * (2 + 3 + 4 + 5 + 3), dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy()[:2], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[2:5], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[5:9], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[9:14], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[14:17], 2 * np.matmul(m32.numpy()[0], v32.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[17:19], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[19:22], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[22:26], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[26:31], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[31:34], 2 * np.matmul(m32.numpy()[0], v32.numpy()[0]), tol=5 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, invec, inmat in [(2, v2, m2), (3, v3, m3), (4, v4, m4), (5, v5, m5), (3, v32, m32)]: - for i in range(dim): - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], - outputs=[outcomponents], - device=device, - ) - wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) - tape.backward(loss=out) - - assert_np_equal(tape.gradients[invec].numpy()[0], 2 * inmat.numpy()[0, i, :], tol=2 * tol) - expectedresult = np.zeros(inmat.dtype._shape_, dtype=dtype) - expectedresult[i, :] = 2 * invec.numpy()[0] - assert_np_equal(tape.gradients[inmat].numpy()[0], expectedresult, tol=2 * tol) - - tape.zero() - - idx = idx + 1 - - -def test_vecmat_multiplication(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 2.0e-2, - np.float32: 5.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat23 = wp.types.matrix(shape=(2, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_vec_mat_mul( - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v32: wp.array(dtype=vec2), - m2: wp.array(dtype=mat22), - m3: wp.array(dtype=mat33), - m4: wp.array(dtype=mat44), - m5: wp.array(dtype=mat55), - m23: wp.array(dtype=mat23), - outcomponents: wp.array(dtype=wptype), - ): - v2result = v2[0] * m2[0] - v3result = v3[0] * m3[0] - v4result = v4[0] * m4[0] - v5result = v5[0] * m5[0] - v32result = v32[0] * m23[0] - v2result_2 = v2[0] @ m2[0] - v3result_2 = v3[0] @ m3[0] - v4result_2 = v4[0] @ m4[0] - v5result_2 = v5[0] @ m5[0] - v32result_2 = v32[0] @ m23[0] - - idx = 0 - - # multiply outputs by 2 so we've got something to backpropagate: - for i in range(2): - outcomponents[idx] = wptype(2) * v2result[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v3result[i] - idx = idx + 1 - - for i in range(4): - outcomponents[idx] = wptype(2) * v4result[i] - idx = idx + 1 - - for i in range(5): - outcomponents[idx] = wptype(2) * v5result[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v32result[i] - idx = idx + 1 - - for i in range(2): - outcomponents[idx] = wptype(2) * v2result_2[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v3result_2[i] - idx = idx + 1 - - for i in range(4): - outcomponents[idx] = wptype(2) * v4result_2[i] - idx = idx + 1 - - for i in range(5): - outcomponents[idx] = wptype(2) * v5result_2[i] - idx = idx + 1 - - for i in range(3): - outcomponents[idx] = wptype(2) * v32result_2[i] - idx = idx + 1 - - kernel = getkernel(check_vec_mat_mul, suffix=dtype.__name__) - - if register_kernels: - return - - v2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) - v32 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) - m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - m23 = wp.array(randvals(rng, [1, 2, 3], dtype), dtype=mat23, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * (2 + 3 + 4 + 5 + 3), dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m23], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy()[:2], 2 * np.matmul(v2.numpy()[0], m2.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[2:5], 2 * np.matmul(v3.numpy()[0], m3.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[5:9], 2 * np.matmul(v4.numpy()[0], m4.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[9:14], 2 * np.matmul(v5.numpy()[0], m5.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[14:17], 2 * np.matmul(v32.numpy()[0], m23.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[17:19], 2 * np.matmul(v2.numpy()[0], m2.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[19:22], 2 * np.matmul(v3.numpy()[0], m3.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[22:26], 2 * np.matmul(v4.numpy()[0], m4.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[26:31], 2 * np.matmul(v5.numpy()[0], m5.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[31:34], 2 * np.matmul(v32.numpy()[0], m23.numpy()[0]), tol=5 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, inmat, invec in [(2, m2, v2), (3, m3, v3), (4, m4, v4), (5, m5, v5), (3, m23, v32)]: - for i in range(dim): - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m23], - outputs=[outcomponents], - device=device, - ) - wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) - tape.backward(loss=out) - - assert_np_equal(tape.gradients[invec].numpy()[0], 2 * inmat.numpy()[0, :, i], tol=2 * tol) - expectedresult = np.zeros(inmat.dtype._shape_, dtype=dtype) - expectedresult[:, i] = 2 * invec.numpy()[0] - assert_np_equal(tape.gradients[inmat].numpy()[0], expectedresult, tol=2 * tol) - - tape.zero() - - idx = idx + 1 - - -def test_matmat_multiplication(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 2.0e-2, - np.float32: 5.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_mat_mul( - a2: wp.array(dtype=mat22), - a3: wp.array(dtype=mat33), - a4: wp.array(dtype=mat44), - a5: wp.array(dtype=mat55), - a32: wp.array(dtype=mat32), - b2: wp.array(dtype=mat22), - b3: wp.array(dtype=mat33), - b4: wp.array(dtype=mat44), - b5: wp.array(dtype=mat55), - b32: wp.array(dtype=mat32), - outcomponents: wp.array(dtype=wptype), - ): - c2result = b2[0] * a2[0] - c3result = b3[0] * a3[0] - c4result = b4[0] * a4[0] - c5result = b5[0] * a5[0] - c32result = b32[0] * a2[0] - c32result2 = b3[0] * a32[0] - c2result_2 = b2[0] @ a2[0] - c3result_2 = b3[0] @ a3[0] - c4result_2 = b4[0] @ a4[0] - c5result_2 = b5[0] @ a5[0] - c32result_2 = b32[0] @ a2[0] - c32result2_2 = b3[0] @ a32[0] - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = wptype(2) * c2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = wptype(2) * c3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = wptype(2) * c4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = wptype(2) * c5result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(2): - outcomponents[idx] = wptype(2) * c32result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(2): - outcomponents[idx] = wptype(2) * c32result2[i, j] - idx = idx + 1 - - for i in range(2): - for j in range(2): - outcomponents[idx] = wptype(2) * c2result_2[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = wptype(2) * c3result_2[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = wptype(2) * c4result_2[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = wptype(2) * c5result_2[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(2): - outcomponents[idx] = wptype(2) * c32result_2[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(2): - outcomponents[idx] = wptype(2) * c32result2_2[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_mat_mul, suffix=dtype.__name__) - - if register_kernels: - return - - v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - v32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) - m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - m32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) - outcomponents = wp.zeros( - 2 * (2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2 + 3 * 2), dtype=wptype, requires_grad=True, device=device - ) - - wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy()[:4], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=2 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[54:60], 2 * np.matmul(m32.numpy()[0], v2.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[60:66], 2 * np.matmul(m3.numpy()[0], v32.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[66:70], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[70:79], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) - assert_np_equal(outcomponents.numpy()[79:95], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=2 * tol) - assert_np_equal(outcomponents.numpy()[95:120], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[120:126], 2 * np.matmul(m32.numpy()[0], v2.numpy()[0]), tol=5 * tol) - assert_np_equal(outcomponents.numpy()[126:132], 2 * np.matmul(m3.numpy()[0], v32.numpy()[0]), tol=5 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for v, m in [(v2, m2), (v3, m3), (v4, m4), (v5, m5), (v2, m32), (v32, m3)]: - rows, cols = m.dtype._shape_[0], v.dtype._shape_[1] - for i in range(rows): - for j in range(cols): - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], - outputs=[outcomponents], - device=device, - ) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - - expected = np.zeros(v.dtype._shape_, dtype=dtype) - expected[:, j] = 2 * m.numpy()[0, i, :] - assert_np_equal(tape.gradients[v].numpy()[0], expected, tol=10 * tol) - - expected = np.zeros(m.dtype._shape_, dtype=dtype) - expected[i, :] = 2 * v.numpy()[0, :, j] - assert_np_equal(tape.gradients[m].numpy()[0], expected, tol=10 * tol) - - tape.zero() - idx = idx + 1 - - -def test_cw_multiplication(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_cw_mul( - s2: wp.array(dtype=mat22), - s3: wp.array(dtype=mat33), - s4: wp.array(dtype=mat44), - s5: wp.array(dtype=mat55), - v2: wp.array(dtype=mat22), - v3: wp.array(dtype=mat33), - v4: wp.array(dtype=mat44), - v5: wp.array(dtype=mat55), - outcomponents: wp.array(dtype=wptype), - ): - v2result = wptype(2) * wp.cw_mul(v2[0], s2[0]) - v3result = wptype(2) * wp.cw_mul(v3[0], s3[0]) - v4result = wptype(2) * wp.cw_mul(v4[0], s4[0]) - v5result = wptype(2) * wp.cw_mul(v5[0], s5[0]) - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = v2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = v3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = v4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = v5result[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_cw_mul, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[outcomponents], - device=device, - ) - - assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() * s2.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() * s3.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() * s4.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() * s5.numpy()).reshape(-1), tol=50 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, in1, in2 in [(2, s2, v2), (3, s3, v3), (4, s4, v4), (5, s5, v5)]: - for i in range(dim): - for j in range(dim): - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[outcomponents], - device=device, - ) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - expectedresult = np.zeros((dim, dim), dtype=dtype) - expectedresult[i, j] = 2 * in1.numpy()[0][i, j] - assert_np_equal(tape.gradients[in2].numpy()[0], expectedresult, tol=5 * tol) - expectedresult[i, j] = 2 * in2.numpy()[0][i, j] - assert_np_equal(tape.gradients[in1].numpy()[0], expectedresult, tol=5 * tol) - tape.zero() - - idx = idx + 1 - - -def test_cw_division(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_cw_div( - s2: wp.array(dtype=mat22), - s3: wp.array(dtype=mat33), - s4: wp.array(dtype=mat44), - s5: wp.array(dtype=mat55), - v2: wp.array(dtype=mat22), - v3: wp.array(dtype=mat33), - v4: wp.array(dtype=mat44), - v5: wp.array(dtype=mat55), - outcomponents: wp.array(dtype=wptype), - ): - v2result = wptype(2) * wp.cw_div(v2[0], s2[0]) - v3result = wptype(2) * wp.cw_div(v3[0], s3[0]) - v4result = wptype(2) * wp.cw_div(v4[0], s4[0]) - v5result = wptype(2) * wp.cw_div(v5[0], s5[0]) - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = v2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = v3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = v4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = v5result[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_cw_div, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = randvals(rng, [1, 2, 2], dtype) - s3 = randvals(rng, [1, 3, 3], dtype) - s4 = randvals(rng, [1, 4, 4], dtype) - s5 = randvals(rng, [1, 5, 5], dtype) - - # set denominators to 1 if their magnitudes are small - # to prevent divide by zero, or overflows if we're testing - # float16: - s2[np.abs(s2) < 1.0e-2] = 1 - s3[np.abs(s3) < 1.0e-2] = 1 - s4[np.abs(s4) < 1.0e-2] = 1 - s5[np.abs(s5) < 1.0e-2] = 1 - - s2 = wp.array(s2, dtype=mat22, requires_grad=True, device=device) - s3 = wp.array(s3, dtype=mat33, requires_grad=True, device=device) - s4 = wp.array(s4, dtype=mat44, requires_grad=True, device=device) - s5 = wp.array(s5, dtype=mat55, requires_grad=True, device=device) - - v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[outcomponents], - device=device, - ) - - if dtype in np_float_types: - assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() / s2.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() / s3.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() / s4.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() / s5.numpy()).reshape(-1), tol=50 * tol) - else: - assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() // s2.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() // s3.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() // s4.numpy()).reshape(-1), tol=50 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() // s5.numpy()).reshape(-1), tol=50 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, s, v in [(2, s2, v2), (3, s3, v3), (4, s4, v4), (5, s5, v5)]: - for i in range(dim): - for j in range(dim): - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[outcomponents], - device=device, - ) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - - # y = v/s - # dy/dv = 1.0/s - # dy/ds = -v/s^2 - - expectedresult = np.zeros((dim, dim), dtype=dtype) - expectedresult[i, j] = 2.0 / (s.numpy()[0, i, j]) - assert_np_equal(tape.gradients[v].numpy()[0], expectedresult, tol=50 * tol) - expectedresult[i, j] = -2.0 * v.numpy()[0, i, j] / (s.numpy()[0, i, j] ** 2) - assert_np_equal( - tape.gradients[s].numpy()[0], expectedresult, tol=abs(outcomponents.numpy()[idx]) * 50 * tol - ) - tape.zero() - - idx = idx + 1 - - -def test_outer_product(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_outer_product( - s2: wp.array(dtype=vec2), - s3: wp.array(dtype=vec3), - s4: wp.array(dtype=vec4), - s5: wp.array(dtype=vec5), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - outcomponents: wp.array(dtype=wptype), - ): - m22result = wptype(2) * wp.outer(s2[0], v2[0]) - m33result = wptype(2) * wp.outer(s3[0], v3[0]) - m44result = wptype(2) * wp.outer(s4[0], v4[0]) - m55result = wptype(2) * wp.outer(s5[0], v5[0]) - m25result = wptype(2) * wp.outer(s2[0], v5[0]) - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = m22result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = m33result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = m44result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = m55result[i, j] - idx = idx + 1 - - for i in range(2): - for j in range(5): - outcomponents[idx] = m25result[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_outer_product, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) - v2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 2 * 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[s2, s3, s4, s5, v2, v3, v4, v5], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy()[:4], 2 * s2.numpy()[0, :, None] * v2.numpy()[0, None, :], tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * s3.numpy()[0, :, None] * v3.numpy()[0, None, :], tol=10 * tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * s4.numpy()[0, :, None] * v4.numpy()[0, None, :], tol=10 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * s5.numpy()[0, :, None] * v5.numpy()[0, None, :], tol=10 * tol) - assert_np_equal(outcomponents.numpy()[54:], 2 * s2.numpy()[0, :, None] * v5.numpy()[0, None, :], tol=10 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for s, v in [(s2, v2), (s3, v3), (s4, v4), (s5, v5), (s2, v5)]: - rows = s.dtype._length_ - cols = v.dtype._length_ - for i in range(rows): - for j in range(cols): - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[outcomponents], - device=device, - ) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - - # this component's gonna be s_i * v_j, so its s gradient is gonna be nozero - # at the ith component and its v gradient will be nonzero at the jth component: - - expectedresult = np.zeros((rows), dtype=dtype) - expectedresult[i] = 2 * v.numpy()[0, j] - assert_np_equal(tape.gradients[s].numpy()[0], expectedresult, tol=10 * tol) - - expectedresult = np.zeros((cols), dtype=dtype) - expectedresult[j] = 2 * s.numpy()[0, i] - assert_np_equal(tape.gradients[v].numpy()[0], expectedresult, tol=10 * tol) - tape.zero() - - idx = idx + 1 - - -def test_scalar_division(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_scalar_div( - s: wp.array(dtype=wptype), - m2: wp.array(dtype=mat22), - m3: wp.array(dtype=mat33), - m4: wp.array(dtype=mat44), - m5: wp.array(dtype=mat55), - outcomponents: wp.array(dtype=wptype), - ): - m2result = m2[0] / s[0] - m3result = m3[0] / s[0] - m4result = m4[0] / s[0] - m5result = m5[0] / s[0] - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = wptype(2) * m2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = wptype(2) * m3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = wptype(2) * m4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = wptype(2) * m5result[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_scalar_div, suffix=dtype.__name__) - - if register_kernels: - return - - s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) - m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[s, m2, m3, m4, m5], outputs=[outcomponents], device=device) - - sval = s.numpy()[0] - if dtype in np_float_types: - assert_np_equal(outcomponents.numpy()[:4], 2 * m2.numpy().reshape(-1) / sval, tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * m3.numpy().reshape(-1) / sval, tol=10 * tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * m4.numpy().reshape(-1) / sval, tol=10 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * m5.numpy().reshape(-1) / sval, tol=10 * tol) - else: - assert_np_equal(outcomponents.numpy()[:4], 2 * (m2.numpy().reshape(-1) // sval), tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * (m3.numpy().reshape(-1) // sval), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * (m4.numpy().reshape(-1) // sval), tol=10 * tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * (m5.numpy().reshape(-1) // sval), tol=10 * tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, input in [(2, m2), (3, m3), (4, m4), (5, m5)]: - for i in range(dim): - for j in range(dim): - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[s, m2, m3, m4, m5], outputs=[outcomponents], device=device) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - expectedresult = np.zeros((dim, dim), dtype=dtype) - expectedresult[i, j] = 2.0 / sval - assert_np_equal(tape.gradients[input].numpy()[0], expectedresult, tol=10 * tol) - assert_np_equal( - tape.gradients[s].numpy()[0], -2 * input.numpy()[0, i, j] / (sval * sval), tol=10 * tol - ) - tape.zero() - - idx = idx + 1 - - -def test_addition(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 2.0e-2, - np.float32: 5.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_add( - s2: wp.array(dtype=mat22), - s3: wp.array(dtype=mat33), - s4: wp.array(dtype=mat44), - s5: wp.array(dtype=mat55), - v2: wp.array(dtype=mat22), - v3: wp.array(dtype=mat33), - v4: wp.array(dtype=mat44), - v5: wp.array(dtype=mat55), - outcomponents: wp.array(dtype=wptype), - ): - v2result = v2[0] + s2[0] - v3result = v3[0] + s3[0] - v4result = v4[0] + s4[0] - v5result = v5[0] + s5[0] - - # multiply outputs by 2 so we've got something to backpropagate: - idx = 0 - for i in range(2): - for j in range(2): - outcomponents[idx] = wptype(2) * v2result[i, j] - idx = idx + 1 - - for i in range(3): - for j in range(3): - outcomponents[idx] = wptype(2) * v3result[i, j] - idx = idx + 1 - - for i in range(4): - for j in range(4): - outcomponents[idx] = wptype(2) * v4result[i, j] - idx = idx + 1 - - for i in range(5): - for j in range(5): - outcomponents[idx] = wptype(2) * v5result[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_add, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[outcomponents], - device=device, - ) - - assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() + s2.numpy()).reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() + s3.numpy()).reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() + s4.numpy()).reshape(-1), tol=tol) - assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() + s5.numpy()).reshape(-1), tol=tol) - - if dtype in np_float_types: - idx = 0 - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for dim, in1, in2 in [(2, s2, v2), (3, s3, v3), (4, s4, v4), (5, s5, v5)]: - for i in range(dim): - for j in range(dim): - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[outcomponents], - device=device, - ) - wp.launch( - output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device - ) - tape.backward(loss=out) - expectedresult = np.zeros((dim, dim), dtype=dtype) - expectedresult[i, j] = 2 - assert_np_equal(tape.gradients[in2].numpy()[0], expectedresult, tol=10 * tol) - expectedresult[i, j] = 2 - assert_np_equal(tape.gradients[in1].numpy()[0], expectedresult, tol=10 * tol) + assert_np_equal(tape.gradients[input].numpy()[0], expectedresult) tape.zero() - idx = idx + 1 @@ -2715,129 +587,6 @@ def check_mat_sub( idx = idx + 1 -def test_ddot(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - def check_mat_dot( - s2: wp.array(dtype=mat22), - s3: wp.array(dtype=mat33), - s4: wp.array(dtype=mat44), - s5: wp.array(dtype=mat55), - v2: wp.array(dtype=mat22), - v3: wp.array(dtype=mat33), - v4: wp.array(dtype=mat44), - v5: wp.array(dtype=mat55), - dot2: wp.array(dtype=wptype), - dot3: wp.array(dtype=wptype), - dot4: wp.array(dtype=wptype), - dot5: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - dot2[0] = wptype(2) * wp.ddot(v2[0], s2[0]) - dot3[0] = wptype(2) * wp.ddot(v3[0], s3[0]) - dot4[0] = wptype(2) * wp.ddot(v4[0], s4[0]) - dot5[0] = wptype(2) * wp.ddot(v5[0], s5[0]) - - kernel = getkernel(check_mat_dot, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - dot2 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - dot3 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - dot4 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - dot5 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[dot2, dot3, dot4, dot5], - device=device, - ) - - assert_np_equal(dot2.numpy()[0], 2 * (v2.numpy() * s2.numpy()).sum(), tol=10 * tol) - assert_np_equal(dot3.numpy()[0], 2 * (v3.numpy() * s3.numpy()).sum(), tol=10 * tol) - assert_np_equal(dot4.numpy()[0], 2 * (v4.numpy() * s4.numpy()).sum(), tol=50 * tol) - assert_np_equal(dot5.numpy()[0], 2 * (v5.numpy() * s5.numpy()).sum(), tol=200 * tol) - - if dtype in np_float_types: - tape.backward(loss=dot2) - sgrads = tape.gradients[s2].numpy()[0] - expected_grads = 2.0 * v2.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v2].numpy()[0] - expected_grads = 2.0 * s2.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=10 * tol) - - tape.zero() - - tape.backward(loss=dot3) - sgrads = tape.gradients[s3].numpy()[0] - expected_grads = 2.0 * v3.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v3].numpy()[0] - expected_grads = 2.0 * s3.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=10 * tol) - - tape.zero() - - tape.backward(loss=dot4) - sgrads = tape.gradients[s4].numpy()[0] - expected_grads = 2.0 * v4.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v4].numpy()[0] - expected_grads = 2.0 * s4.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=10 * tol) - - tape.zero() - - tape.backward(loss=dot5) - sgrads = tape.gradients[s5].numpy()[0] - expected_grads = 2.0 * v5.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v5].numpy()[0] - expected_grads = 2.0 * s5.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=10 * tol) - - tape.zero() - - def test_determinant(test, device, dtype, register_kernels=False): rng = np.random.default_rng(123) @@ -2978,268 +727,119 @@ def check_mat_det( det4, ], device=device, - ) - dplus = det3.numpy()[0] - v3test[0, i, j] -= 2.0 * dx - wp.launch( - kernel, - dim=1, - inputs=[ - v2, - wp.array(v3test, dtype=v3.dtype, requires_grad=True, device=device), - v4, - ], - outputs=[ - det2, - det3, - det4, - ], - device=device, - ) - dminus = det3.numpy()[0] - assert_np_equal((dplus - dminus) / (2.0 * dx * dplus), v3grads[i, j] / dplus, tol=fdtol) - - for i in range(4): - for j in range(4): - v4test = v4.numpy() - v4test[0, i, j] += dx - wp.launch( - kernel, - dim=1, - inputs=[ - v2, - v3, - wp.array(v4test, dtype=v4.dtype, requires_grad=True, device=device), - ], - outputs=[ - det2, - det3, - det4, - ], - device=device, - ) - dplus = det4.numpy()[0] - v4test[0, i, j] -= 2.0 * dx - wp.launch( - kernel, - dim=1, - inputs=[ - v2, - v3, - wp.array(v4test, dtype=v4.dtype, requires_grad=True, device=device), - ], - outputs=[ - det2, - det3, - det4, - ], - device=device, - ) - dminus = det4.numpy()[0] - assert_np_equal((dplus - dminus) / (2.0 * dx * dplus), v4grads[i, j] / dplus, tol=fdtol) - - -def test_trace(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - def check_mat_trace( - v2: wp.array(dtype=mat22), - v3: wp.array(dtype=mat33), - v4: wp.array(dtype=mat44), - v5: wp.array(dtype=mat55), - tr2: wp.array(dtype=wptype), - tr3: wp.array(dtype=wptype), - tr4: wp.array(dtype=wptype), - tr5: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - tr2[0] = wptype(2) * wp.trace(v2[0]) - tr3[0] = wptype(2) * wp.trace(v3[0]) - tr4[0] = wptype(2) * wp.trace(v4[0]) - tr5[0] = wptype(2) * wp.trace(v5[0]) - - kernel = getkernel(check_mat_trace, suffix=dtype.__name__) - - if register_kernels: - return - - v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) - tr2 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tr3 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tr4 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tr5 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - v2, - v3, - v4, - v5, - ], - outputs=[ - tr2, - tr3, - tr4, - tr5, - ], - device=device, - ) - - assert_np_equal(tr2.numpy()[0], 2 * np.trace(v2.numpy()[0]), tol=10 * tol) - assert_np_equal(tr3.numpy()[0], 2 * np.trace(v3.numpy()[0]), tol=10 * tol) - assert_np_equal(tr4.numpy()[0], 2 * np.trace(v4.numpy()[0]), tol=200 * tol) - assert_np_equal(tr4.numpy()[0], 2 * np.trace(v4.numpy()[0]), tol=200 * tol) - - if dtype in np_float_types: - tape.backward(loss=tr2) - vgrads = tape.gradients[v2].numpy()[0] - assert_np_equal(vgrads, 2.0 * np.eye(2), tol=10 * tol) - tape.zero() - - tape.backward(loss=tr3) - vgrads = tape.gradients[v3].numpy()[0] - assert_np_equal(vgrads, 2.0 * np.eye(3), tol=10 * tol) - tape.zero() - - tape.backward(loss=tr4) - vgrads = tape.gradients[v4].numpy()[0] - assert_np_equal(vgrads, 2.0 * np.eye(4), tol=10 * tol) - tape.zero() - - tape.backward(loss=tr5) - vgrads = tape.gradients[v5].numpy()[0] - assert_np_equal(vgrads, 2.0 * np.eye(5), tol=10 * tol) - tape.zero() - - -def test_diag(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec5 = wp.types.vector(length=5, dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_diag( - s5: wp.array(dtype=vec5), - outcomponents: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - m55result = wptype(2) * wp.diag(s5[0]) - - idx = 0 - for i in range(5): - for j in range(5): - outcomponents[idx] = m55result[i, j] - idx = idx + 1 - - kernel = getkernel(check_mat_diag, suffix=dtype.__name__) - - if register_kernels: - return - - s5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) - outcomponents = wp.zeros(5 * 5, dtype=wptype, requires_grad=True, device=device) - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[s5], outputs=[outcomponents], device=device) - - assert_np_equal(outcomponents.numpy(), 2 * np.diag(s5.numpy()[0]), tol=tol) - - if dtype in np_float_types: - idx = 0 - for i in range(5): - for j in range(5): - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[s5], outputs=[outcomponents], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) - tape.backward(loss=out) - expectedresult = np.zeros(5, dtype=dtype) - if i == j: - expectedresult[i] = 2 - assert_np_equal(tape.gradients[s5].numpy()[0], expectedresult, tol=10 * tol) - tape.zero() - - idx = idx + 1 - - -def test_get_diag(test, device, dtype, register_kernels=False): - tol = { - np.float16: 1.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - mat55 = wp.types.vector(shape=(5, 5), dtype=wptype) - - output_select_kernel = get_select_kernel(wptype) - - def check_mat_diag( - m55: wp.array(dtype=mat55), - outcomponents: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - vec5result = wptype(2) * wp.get_diag(m55[0]) - - idx = 0 - for i in range(5): - outcomponents[idx] = vec5result[i] - idx = idx + 1 - - kernel = getkernel(check_mat_diag, suffix=dtype.__name__) - - if register_kernels: - return - - m55 = wp.array(randvals((1, 5, 5), dtype), dtype=mat55, requires_grad=True, device=device) - outcomponents = wp.zeros(5, dtype=wptype, requires_grad=True, device=device) - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - wp.launch(kernel, dim=1, inputs=[m55], outputs=[outcomponents], device=device) + ) + dplus = det3.numpy()[0] + v3test[0, i, j] -= 2.0 * dx + wp.launch( + kernel, + dim=1, + inputs=[ + v2, + wp.array(v3test, dtype=v3.dtype, requires_grad=True, device=device), + v4, + ], + outputs=[ + det2, + det3, + det4, + ], + device=device, + ) + dminus = det3.numpy()[0] + assert_np_equal((dplus - dminus) / (2.0 * dx * dplus), v3grads[i, j] / dplus, tol=fdtol) - assert_np_equal(outcomponents.numpy(), 2 * np.diag(m55.numpy()[0]), tol=tol) + for i in range(4): + for j in range(4): + v4test = v4.numpy() + v4test[0, i, j] += dx + wp.launch( + kernel, + dim=1, + inputs=[ + v2, + v3, + wp.array(v4test, dtype=v4.dtype, requires_grad=True, device=device), + ], + outputs=[ + det2, + det3, + det4, + ], + device=device, + ) + dplus = det4.numpy()[0] + v4test[0, i, j] -= 2.0 * dx + wp.launch( + kernel, + dim=1, + inputs=[ + v2, + v3, + wp.array(v4test, dtype=v4.dtype, requires_grad=True, device=device), + ], + outputs=[ + det2, + det3, + det4, + ], + device=device, + ) + dminus = det4.numpy()[0] + assert_np_equal((dplus - dminus) / (2.0 * dx * dplus), v4grads[i, j] / dplus, tol=fdtol) - if dtype in np_float_types: - idx = 0 - for i in range(5): - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[m55], outputs=[outcomponents], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) - tape.backward(loss=out) - expectedresult = np.zeros((5, 5), dtype=dtype) - expectedresult[i, i] = 2 - assert_np_equal(tape.gradients[m55].numpy()[0], expectedresult, tol=10 * tol) - tape.zero() - idx = idx + 1 +# Unused. Why? +# def test_get_diag(test, device, dtype, register_kernels=False): +# tol = { +# np.float16: 1.0e-3, +# np.float32: 1.0e-6, +# np.float64: 1.0e-8, +# }.get(dtype, 0) +# +# wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] +# mat55 = wp.types.vector(shape=(5, 5), dtype=wptype) +# +# output_select_kernel = get_select_kernel(wptype) +# +# def check_mat_diag( +# m55: wp.array(dtype=mat55), +# outcomponents: wp.array(dtype=wptype), +# ): +# # multiply outputs by 2 so we've got something to backpropagate: +# vec5result = wptype(2) * wp.get_diag(m55[0]) +# +# idx = 0 +# for i in range(5): +# outcomponents[idx] = vec5result[i] +# idx = idx + 1 +# +# kernel = getkernel(check_mat_diag, suffix=dtype.__name__) +# +# if register_kernels: +# return +# +# m55 = wp.array(randvals((1, 5, 5), dtype), dtype=mat55, requires_grad=True, device=device) +# outcomponents = wp.zeros(5, dtype=wptype, requires_grad=True, device=device) +# out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) +# +# wp.launch(kernel, dim=1, inputs=[m55], outputs=[outcomponents], device=device) +# +# assert_np_equal(outcomponents.numpy(), 2 * np.diag(m55.numpy()[0]), tol=tol) +# +# if dtype in np_float_types: +# idx = 0 +# for i in range(5): +# tape = wp.Tape() +# with tape: +# wp.launch(kernel, dim=1, inputs=[m55], outputs=[outcomponents], device=device) +# wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) +# tape.backward(loss=out) +# expectedresult = np.zeros((5, 5), dtype=dtype) +# expectedresult[i, i] = 2 +# assert_np_equal(tape.gradients[m55].numpy()[0], expectedresult, tol=10 * tol) +# tape.zero() +# +# idx = idx + 1 def test_inverse(test, device, dtype, register_kernels=False): @@ -3978,330 +1578,6 @@ def check_mat_transform_vector( tape.zero() -def test_anon_type_instance(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - def check_scalar_init( - input: wp.array(dtype=wptype), - output: wp.array(dtype=wptype), - ): - m2result = wp.matrix(input[0], shape=(2, 2)) - m3result = wp.matrix(input[1], shape=(3, 3)) - m4result = wp.matrix(input[2], shape=(4, 4)) - m5result = wp.matrix(input[3], shape=(5, 5)) - m32result = wp.matrix(input[4], shape=(3, 2)) - - idx = 0 - for i in range(2): - for j in range(2): - output[idx] = wptype(2) * m2result[i, j] - idx = idx + 1 - for i in range(3): - for j in range(3): - output[idx] = wptype(2) * m3result[i, j] - idx = idx + 1 - for i in range(4): - for j in range(4): - output[idx] = wptype(2) * m4result[i, j] - idx = idx + 1 - for i in range(5): - for j in range(5): - output[idx] = wptype(2) * m5result[i, j] - idx = idx + 1 - for i in range(3): - for j in range(2): - output[idx] = wptype(2) * m32result[i, j] - idx = idx + 1 - - def check_component_init( - input: wp.array(dtype=wptype), - output: wp.array(dtype=wptype), - ): - m2result = wp.matrix(input[0], input[1], input[2], input[3], shape=(2, 2)) - m3result = wp.matrix( - input[4], input[5], input[6], input[7], input[8], input[9], input[10], input[11], input[12], shape=(3, 3) - ) - m4result = wp.matrix( - input[13], - input[14], - input[15], - input[16], - input[17], - input[18], - input[19], - input[20], - input[21], - input[22], - input[23], - input[24], - input[25], - input[26], - input[27], - input[28], - shape=(4, 4), - ) - m5result = wp.matrix( - input[29], - input[30], - input[31], - input[32], - input[33], - input[34], - input[35], - input[36], - input[37], - input[38], - input[39], - input[40], - input[41], - input[42], - input[43], - input[44], - input[45], - input[46], - input[47], - input[48], - input[49], - input[50], - input[51], - input[52], - input[53], - shape=(5, 5), - ) - m32result = wp.matrix(input[54], input[55], input[56], input[57], input[58], input[59], shape=(3, 2)) - - idx = 0 - for i in range(2): - for j in range(2): - output[idx] = wptype(2) * m2result[i, j] - idx = idx + 1 - for i in range(3): - for j in range(3): - output[idx] = wptype(2) * m3result[i, j] - idx = idx + 1 - for i in range(4): - for j in range(4): - output[idx] = wptype(2) * m4result[i, j] - idx = idx + 1 - for i in range(5): - for j in range(5): - output[idx] = wptype(2) * m5result[i, j] - idx = idx + 1 - for i in range(3): - for j in range(2): - output[idx] = wptype(2) * m32result[i, j] - idx = idx + 1 - - scalar_kernel = getkernel(check_scalar_init, suffix=dtype.__name__) - component_kernel = getkernel(check_component_init, suffix=dtype.__name__) - output_select_kernel = get_select_kernel(wptype) - - if register_kernels: - return - - input = wp.array(randvals(rng, [5], dtype), requires_grad=True, device=device) - output = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2, dtype=wptype, requires_grad=True, device=device) - - wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) - - assert_np_equal(output.numpy()[:4], 2 * np.array([input.numpy()[0]] * 2 * 2), tol=1.0e-6) - assert_np_equal(output.numpy()[4:13], 2 * np.array([input.numpy()[1]] * 3 * 3), tol=1.0e-6) - assert_np_equal(output.numpy()[13:29], 2 * np.array([input.numpy()[2]] * 4 * 4), tol=1.0e-6) - assert_np_equal(output.numpy()[29:54], 2 * np.array([input.numpy()[3]] * 5 * 5), tol=1.0e-6) - assert_np_equal(output.numpy()[54:], 2 * np.array([input.numpy()[4]] * 3 * 2), tol=1.0e-6) - - if dtype in np_float_types: - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for i in range(len(output)): - tape = wp.Tape() - with tape: - wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) - - tape.backward(loss=out) - expected = np.zeros_like(input.numpy()) - if i < 4: - expected[0] = 2 - elif i < 13: - expected[1] = 2 - elif i < 29: - expected[2] = 2 - elif i < 54: - expected[3] = 2 - else: - expected[4] = 2 - - assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) - - tape.reset() - tape.zero() - - input = wp.array(randvals(rng, [2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2], dtype), requires_grad=True, device=device) - output = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2, dtype=wptype, requires_grad=True, device=device) - - wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) - - assert_np_equal(output.numpy(), 2 * input.numpy(), tol=1.0e-6) - - if dtype in np_float_types: - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for i in range(len(output)): - tape = wp.Tape() - with tape: - wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) - - tape.backward(loss=out) - expected = np.zeros_like(input.numpy()) - expected[i] = 2 - - assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) - - tape.reset() - tape.zero() - - -def test_identity(test, device, dtype, register_kernels=False): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - def check_identity_mat( - output: wp.array(dtype=wptype), - ): - m2result = wp.identity(dtype=wptype, n=2) - m3result = wp.identity(dtype=wptype, n=3) - m4result = wp.identity(dtype=wptype, n=4) - m5result = wp.identity(dtype=wptype, n=5) - - idx = 0 - for i in range(2): - for j in range(2): - output[idx] = wptype(2) * m2result[i, j] - idx = idx + 1 - for i in range(3): - for j in range(3): - output[idx] = wptype(2) * m3result[i, j] - idx = idx + 1 - for i in range(4): - for j in range(4): - output[idx] = wptype(2) * m4result[i, j] - idx = idx + 1 - for i in range(5): - for j in range(5): - output[idx] = wptype(2) * m5result[i, j] - idx = idx + 1 - - id_kernel = getkernel(check_identity_mat, suffix=dtype.__name__) - - if register_kernels: - return - - output = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) - wp.launch(id_kernel, dim=1, inputs=[], outputs=[output], device=device) - assert_np_equal(output.numpy()[:4], 2 * np.eye(2), tol=1.0e-6) - assert_np_equal(output.numpy()[4:13], 2 * np.eye(3), tol=1.0e-6) - assert_np_equal(output.numpy()[13:29], 2 * np.eye(4), tol=1.0e-6) - assert_np_equal(output.numpy()[29:], 2 * np.eye(5), tol=1.0e-6) - - -def test_equivalent_types(test, device, dtype, register_kernels=False): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - # matrix types - mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) - - # matrix types equivalent to the above - mat22_equiv = wp.types.matrix(shape=(2, 2), dtype=wptype) - mat33_equiv = wp.types.matrix(shape=(3, 3), dtype=wptype) - mat44_equiv = wp.types.matrix(shape=(4, 4), dtype=wptype) - mat55_equiv = wp.types.matrix(shape=(5, 5), dtype=wptype) - - # declare kernel with original types - def check_equivalence( - m2: mat22, - m3: mat33, - m4: mat44, - m5: mat55, - ): - wp.expect_eq(m2, mat22(wptype(42))) - wp.expect_eq(m3, mat33(wptype(43))) - wp.expect_eq(m4, mat44(wptype(44))) - wp.expect_eq(m5, mat55(wptype(45))) - - wp.expect_eq(m2, mat22_equiv(wptype(42))) - wp.expect_eq(m3, mat33_equiv(wptype(43))) - wp.expect_eq(m4, mat44_equiv(wptype(44))) - wp.expect_eq(m5, mat55_equiv(wptype(45))) - - kernel = getkernel(check_equivalence, suffix=dtype.__name__) - - if register_kernels: - return - - # call kernel with equivalent types - m2 = mat22_equiv(42) - m3 = mat33_equiv(43) - m4 = mat44_equiv(44) - m5 = mat55_equiv(45) - - wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5], device=device) - - -def test_conversions(test, device, dtype, register_kernels=False): - def check_matrices_equal( - m0: wp.mat22, - m1: wp.mat22, - m2: wp.mat22, - m3: wp.mat22, - m4: wp.mat22, - m5: wp.mat22, - m6: wp.mat22, - ): - wp.expect_eq(m1, m0) - wp.expect_eq(m2, m0) - wp.expect_eq(m3, m0) - wp.expect_eq(m4, m0) - wp.expect_eq(m5, m0) - wp.expect_eq(m6, m0) - - kernel = getkernel(check_matrices_equal, suffix=dtype.__name__) - - if register_kernels: - return - - m0 = wp.mat22(1, 2, 3, 4) - - # test explicit conversions - constructing matrices from different containers - m1 = wp.mat22(((1, 2), (3, 4))) # nested tuples - m2 = wp.mat22([[1, 2], [3, 4]]) # nested lists - m3 = wp.mat22(np.array([[1, 2], [3, 4]], dtype=dtype)) # 2d array - m4 = wp.mat22((1, 2, 3, 4)) # flat tuple - m5 = wp.mat22([1, 2, 3, 4]) # flat list - m6 = wp.mat22(np.array([1, 2, 3, 4], dtype=dtype)) # 1d array - - wp.launch(kernel, dim=1, inputs=[m0, m1, m2, m3, m4, m5, m6], device=device) - - # test implicit conversions - passing different containers as matrices to wp.launch() - m1 = ((1, 2), (3, 4)) # nested tuples - m2 = [[1, 2], [3, 4]] # nested lists - m3 = np.array([[1, 2], [3, 4]], dtype=dtype) # 2d array - m4 = (1, 2, 3, 4) # flat tuple - m5 = [1, 2, 3, 4] # flat list - m6 = np.array([1, 2, 3, 4], dtype=dtype) # 1d array - - wp.launch(kernel, dim=1, inputs=[m0, m1, m2, m3, m4, m5, m6], device=device) - - # Test matrix constructors using explicit type (float16) # note that these tests are specifically not using generics / closure # args to create kernels dynamically (like the rest of this file) @@ -4328,7 +1604,6 @@ def test_constructors_explicit_precision(): mat32d = wp.mat(shape=(3, 2), dtype=wp.float64) - @wp.kernel def test_matrix_constructor_value_func(): a = wp.mat22() @@ -4404,239 +1679,149 @@ def test_constructors_constant_shape(): m[i, j] = float(i * j) -def register(parent): - devices = get_test_devices() - - class TestMat(parent): - pass - - add_kernel_test(TestMat, test_constructors_explicit_precision, dim=1, devices=devices) - add_kernel_test(TestMat, test_constructors_default_precision, dim=1, devices=devices) - add_kernel_test(TestMat, test_constructors_constant_shape, dim=1, devices=devices) - add_kernel_test(TestMat, test_matrix_constructor_value_func, dim=1, devices=devices) - - mat103 = wp.types.matrix(shape=(10, 3), dtype=float) - add_kernel_test( - TestMat, - test_matrix_mutation, - dim=1, - inputs=[ - mat103( - 1.0, - 2.0, - 3.0, - 2.0, - 4.0, - 6.0, - 3.0, - 6.0, - 9.0, - 4.0, - 8.0, - 12.0, - 5.0, - 10.0, - 15.0, - 6.0, - 12.0, - 18.0, - 7.0, - 14.0, - 21.0, - 8.0, - 16.0, - 24.0, - 9.0, - 18.0, - 27.0, - 10.0, - 20.0, - 30.0, - ) - ], - devices=devices, - ) - - for dtype in np_signed_int_types + np_float_types: - add_function_test_register_kernel( - TestMat, f"test_negation_{dtype.__name__}", test_negation, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_subtraction_{dtype.__name__}", test_subtraction, devices=devices, dtype=dtype +devices = get_test_devices() + + +class TestMat(unittest.TestCase): + pass + + +add_kernel_test(TestMat, test_constructors_explicit_precision, dim=1, devices=devices) +add_kernel_test(TestMat, test_constructors_default_precision, dim=1, devices=devices) +add_kernel_test(TestMat, test_constructors_constant_shape, dim=1, devices=devices) +add_kernel_test(TestMat, test_matrix_constructor_value_func, dim=1, devices=devices) + +mat103 = wp.types.matrix(shape=(10, 3), dtype=float) +add_kernel_test( + TestMat, + test_matrix_mutation, + dim=1, + inputs=[ + mat103( + 1.0, + 2.0, + 3.0, + 2.0, + 4.0, + 6.0, + 3.0, + 6.0, + 9.0, + 4.0, + 8.0, + 12.0, + 5.0, + 10.0, + 15.0, + 6.0, + 12.0, + 18.0, + 7.0, + 14.0, + 21.0, + 8.0, + 16.0, + 24.0, + 9.0, + 18.0, + 27.0, + 10.0, + 20.0, + 30.0, ) + ], + devices=devices, +) - add_function_test( - TestMat, - "test_anon_constructor_error_shape_keyword_missing", - test_anon_constructor_error_shape_keyword_missing, - devices=devices, - ) - add_function_test( - TestMat, - "test_anon_constructor_error_dtype_keyword_missing", - test_anon_constructor_error_dtype_keyword_missing, - devices=devices, +for dtype in np_signed_int_types + np_float_types: + add_function_test_register_kernel( + TestMat, f"test_negation_{dtype.__name__}", test_negation, devices=devices, dtype=dtype ) - add_function_test( - TestMat, - "test_anon_constructor_error_shape_mismatch", - test_anon_constructor_error_shape_mismatch, - devices=devices, + add_function_test_register_kernel( + TestMat, f"test_subtraction_{dtype.__name__}", test_subtraction, devices=devices, dtype=dtype ) + +add_function_test( + TestMat, + "test_anon_constructor_error_shape_keyword_missing", + test_anon_constructor_error_shape_keyword_missing, + devices=devices, +) +add_function_test( + TestMat, + "test_anon_constructor_error_dtype_keyword_missing", + test_anon_constructor_error_dtype_keyword_missing, + devices=devices, +) +add_function_test( + TestMat, + "test_anon_constructor_error_shape_mismatch", + test_anon_constructor_error_shape_mismatch, + devices=devices, +) +add_function_test( + TestMat, + "test_anon_constructor_error_invalid_arg_count", + test_anon_constructor_error_invalid_arg_count, + devices=devices, +) +add_function_test( + TestMat, + "test_tpl_constructor_error_incompatible_sizes", + test_tpl_constructor_error_incompatible_sizes, + devices=devices, +) +add_function_test( + TestMat, + "test_tpl_constructor_error_invalid_scalar_type", + test_tpl_constructor_error_invalid_scalar_type, + devices=devices, +) +add_function_test( + TestMat, + "test_tpl_constructor_error_invalid_vector_count", + test_tpl_constructor_error_invalid_vector_count, + devices=devices, +) +add_function_test( + TestMat, + "test_tpl_constructor_error_invalid_vector_shape", + test_tpl_constructor_error_invalid_vector_shape, + devices=devices, +) +add_function_test( + TestMat, + "test_tpl_constructor_error_invalid_arg_count", + test_tpl_constructor_error_invalid_arg_count, + devices=devices, +) +add_function_test(TestMat, "test_tpl_ops_with_anon", test_tpl_ops_with_anon) + +for dtype in np_float_types: add_function_test( - TestMat, - "test_anon_constructor_error_invalid_arg_count", - test_anon_constructor_error_invalid_arg_count, - devices=devices, + TestMat, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype ) - add_function_test( - TestMat, - "test_tpl_constructor_error_incompatible_sizes", - test_tpl_constructor_error_incompatible_sizes, - devices=devices, + add_function_test_register_kernel( + TestMat, f"test_quat_constructor_{dtype.__name__}", test_quat_constructor, devices=devices, dtype=dtype ) - add_function_test( - TestMat, - "test_tpl_constructor_error_invalid_scalar_type", - test_tpl_constructor_error_invalid_scalar_type, - devices=devices, + add_function_test_register_kernel( + TestMat, f"test_inverse_{dtype.__name__}", test_inverse, devices=devices, dtype=dtype ) - add_function_test( - TestMat, - "test_tpl_constructor_error_invalid_vector_count", - test_tpl_constructor_error_invalid_vector_count, - devices=devices, + add_function_test_register_kernel(TestMat, f"test_svd_{dtype.__name__}", test_svd, devices=devices, dtype=dtype) + add_function_test_register_kernel(TestMat, f"test_qr_{dtype.__name__}", test_qr, devices=devices, dtype=dtype) + add_function_test_register_kernel(TestMat, f"test_eig_{dtype.__name__}", test_eig, devices=devices, dtype=dtype) + add_function_test_register_kernel( + TestMat, f"test_transform_point_{dtype.__name__}", test_transform_point, devices=devices, dtype=dtype ) - add_function_test( - TestMat, - "test_tpl_constructor_error_invalid_vector_shape", - test_tpl_constructor_error_invalid_vector_shape, - devices=devices, + add_function_test_register_kernel( + TestMat, f"test_transform_vector_{dtype.__name__}", test_transform_vector, devices=devices, dtype=dtype ) - add_function_test( - TestMat, - "test_tpl_constructor_error_invalid_arg_count", - test_tpl_constructor_error_invalid_arg_count, - devices=devices, + add_function_test_register_kernel( + TestMat, f"test_determinant_{dtype.__name__}", test_determinant, devices=devices, dtype=dtype ) - add_function_test(TestMat, "test_tpl_ops_with_anon", test_tpl_ops_with_anon) - - for dtype in np_scalar_types: - add_function_test(TestMat, f"test_arrays_{dtype.__name__}", test_arrays, devices=devices, dtype=dtype) - add_function_test(TestMat, f"test_components_{dtype.__name__}", test_components, devices=None, dtype=dtype) - add_function_test_register_kernel( - TestMat, f"test_constructors_{dtype.__name__}", test_constructors, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_anon_type_instance_{dtype.__name__}", test_anon_type_instance, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_identity_{dtype.__name__}", test_identity, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_indexing_{dtype.__name__}", test_indexing, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_equality_{dtype.__name__}", test_equality, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, - f"test_scalar_multiplication_{dtype.__name__}", - test_scalar_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestMat, - f"test_matvec_multiplication_{dtype.__name__}", - test_matvec_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestMat, - f"test_vecmat_multiplication_{dtype.__name__}", - test_vecmat_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestMat, - f"test_matmat_multiplication_{dtype.__name__}", - test_matmat_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestMat, f"test_cw_multiplication_{dtype.__name__}", test_cw_multiplication, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_cw_division_{dtype.__name__}", test_cw_division, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_outer_product_{dtype.__name__}", test_outer_product, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_transpose_{dtype.__name__}", test_transpose, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_scalar_division_{dtype.__name__}", test_scalar_division, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_addition_{dtype.__name__}", test_addition, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_ddot_{dtype.__name__}", test_ddot, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_trace_{dtype.__name__}", test_trace, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_diag_{dtype.__name__}", test_diag, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_get_diag_{dtype.__name__}", test_diag, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_equivalent_types_{dtype.__name__}", test_equivalent_types, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_conversions_{dtype.__name__}", test_conversions, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_constants_{dtype.__name__}", test_constants, devices=devices, dtype=dtype - ) - - for dtype in np_float_types: - add_function_test( - TestMat, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_quat_constructor_{dtype.__name__}", test_quat_constructor, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_inverse_{dtype.__name__}", test_inverse, devices=devices, dtype=dtype - ) - add_function_test_register_kernel(TestMat, f"test_svd_{dtype.__name__}", test_svd, devices=devices, dtype=dtype) - add_function_test_register_kernel(TestMat, f"test_qr_{dtype.__name__}", test_qr, devices=devices, dtype=dtype) - add_function_test_register_kernel(TestMat, f"test_eig_{dtype.__name__}", test_eig, devices=devices, dtype=dtype) - add_function_test_register_kernel( - TestMat, f"test_transform_point_{dtype.__name__}", test_transform_point, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_transform_vector_{dtype.__name__}", test_transform_vector, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_determinant_{dtype.__name__}", test_determinant, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestMat, f"test_skew_{dtype.__name__}", test_skew, devices=devices, dtype=dtype - ) - - return TestMat + add_function_test_register_kernel(TestMat, f"test_skew_{dtype.__name__}", test_skew, devices=devices, dtype=dtype) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_mat_lite.py b/warp/tests/test_mat_lite.py index f894dde09..9e2d436cf 100644 --- a/warp/tests/test_mat_lite.py +++ b/warp/tests/test_mat_lite.py @@ -1,4 +1,4 @@ -# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. # NVIDIA CORPORATION and its licensors retain all intellectual property # and proprietary rights in and to this software, related documentation # and any modifications thereto. Any use, reproduction, disclosure or @@ -7,9 +7,8 @@ import unittest -import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -99,20 +98,18 @@ def test_matrix_mutation(expected: wp.types.matrix(shape=(10, 3), dtype=float)): wp.expect_eq(m, expected) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestMat(parent): - pass - add_kernel_test(TestMat, test_matrix_constructor_value_func, dim=1, devices=devices) - add_kernel_test(TestMat, test_constructors_explicit_precision, dim=1, devices=devices) - add_kernel_test(TestMat, test_constructors_default_precision, dim=1, devices=devices) +class TestMatLite(unittest.TestCase): + pass - return TestMat + +add_kernel_test(TestMatLite, test_matrix_constructor_value_func, dim=1, devices=devices) +add_kernel_test(TestMatLite, test_constructors_explicit_precision, dim=1, devices=devices) +add_kernel_test(TestMatLite, test_constructors_default_precision, dim=1, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_mat_scalar_ops.py b/warp/tests/test_mat_scalar_ops.py new file mode 100644 index 000000000..2d5930c6c --- /dev/null +++ b/warp/tests/test_mat_scalar_ops.py @@ -0,0 +1,2889 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +import unittest + +import numpy as np + +import warp as wp +from warp.tests.unittest_utils import * + +wp.init() + +np_signed_int_types = [ + np.int8, + np.int16, + np.int32, + np.int64, + np.byte, +] + +np_unsigned_int_types = [ + np.uint8, + np.uint16, + np.uint32, + np.uint64, + np.ubyte, +] + +np_int_types = np_signed_int_types + np_unsigned_int_types + +np_float_types = [np.float16, np.float32, np.float64] + +np_scalar_types = np_int_types + np_float_types + + +def randvals(rng, shape, dtype): + if dtype in np_float_types: + return rng.standard_normal(size=shape).astype(dtype) + elif dtype in [np.int8, np.uint8, np.byte, np.ubyte]: + return rng.integers(1, high=3, size=shape, dtype=dtype) + return rng.integers(1, high=5, size=shape, dtype=dtype) + + +kernel_cache = dict() + + +def getkernel(func, suffix=""): + key = func.__name__ + "_" + suffix + if key not in kernel_cache: + kernel_cache[key] = wp.Kernel(func=func, key=key) + return kernel_cache[key] + + +def get_select_kernel(dtype): + def output_select_kernel_fn( + input: wp.array(dtype=dtype), + index: int, + out: wp.array(dtype=dtype), + ): + out[0] = input[index] + + return getkernel(output_select_kernel_fn, suffix=dtype.__name__) + + wp.launch(kernel, dim=1, inputs=[]) + + +def test_arrays(test, device, dtype): + rng = np.random.default_rng(123) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) + + v2_np = randvals(rng, [10, 2, 2], dtype) + v3_np = randvals(rng, [10, 3, 3], dtype) + v4_np = randvals(rng, [10, 4, 4], dtype) + v5_np = randvals(rng, [10, 5, 5], dtype) + v32_np = randvals(rng, [10, 3, 2], dtype) + + v2 = wp.array(v2_np, dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(v3_np, dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(v4_np, dtype=mat44, requires_grad=True, device=device) + v5 = wp.array(v5_np, dtype=mat55, requires_grad=True, device=device) + v32 = wp.array(v32_np, dtype=mat32, requires_grad=True, device=device) + + assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) + assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) + assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) + assert_np_equal(v5.numpy(), v5_np, tol=1.0e-6) + assert_np_equal(v32.numpy(), v32_np, tol=1.0e-6) + + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + + v2 = wp.array(v2_np, dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(v3_np, dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(v4_np, dtype=mat44, requires_grad=True, device=device) + + assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) + assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) + assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) + + +def test_components(test, device, dtype): + # test accessing matrix components from Python - this is especially important + # for float16, which requires special handling internally + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat23 = wp.types.matrix(shape=(2, 3), dtype=wptype) + + m = mat23(1, 2, 3, 4, 5, 6) + + # test __getitem__ for row vectors + r0 = m[0] + r1 = m[1] + test.assertEqual(r0[0], 1) + test.assertEqual(r0[1], 2) + test.assertEqual(r0[2], 3) + test.assertEqual(r1[0], 4) + test.assertEqual(r1[1], 5) + test.assertEqual(r1[2], 6) + + # test __getitem__ for individual components + test.assertEqual(m[0, 0], 1) + test.assertEqual(m[0, 1], 2) + test.assertEqual(m[0, 2], 3) + test.assertEqual(m[1, 0], 4) + test.assertEqual(m[1, 1], 5) + test.assertEqual(m[1, 2], 6) + + # test __setitem__ for row vectors + m[0] = [7, 8, 9] + m[1] = [10, 11, 12] + test.assertEqual(m[0, 0], 7) + test.assertEqual(m[0, 1], 8) + test.assertEqual(m[0, 2], 9) + test.assertEqual(m[1, 0], 10) + test.assertEqual(m[1, 1], 11) + test.assertEqual(m[1, 2], 12) + + # test __setitem__ for individual components + m[0, 0] = 13 + m[0, 1] = 14 + m[0, 2] = 15 + m[1, 0] = 16 + m[1, 1] = 17 + m[1, 2] = 18 + test.assertEqual(m[0, 0], 13) + test.assertEqual(m[0, 1], 14) + test.assertEqual(m[0, 2], 15) + test.assertEqual(m[1, 0], 16) + test.assertEqual(m[1, 1], 17) + test.assertEqual(m[1, 2], 18) + + +def test_constants(test, device, dtype, register_kernels=False): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) + + cm22 = wp.constant(mat22(22)) + cm33 = wp.constant(mat33(33)) + cm44 = wp.constant(mat44(44)) + cm55 = wp.constant(mat55(55)) + cm32 = wp.constant(mat32(32)) + + def check_matrix_constants(): + wp.expect_eq(cm22, mat22(wptype(22))) + wp.expect_eq(cm33, mat33(wptype(33))) + wp.expect_eq(cm44, mat44(wptype(44))) + wp.expect_eq(cm55, mat55(wptype(55))) + wp.expect_eq(cm32, mat32(wptype(32))) + + kernel = getkernel(check_matrix_constants, suffix=dtype.__name__) + + if register_kernels: + return + + +def test_constructors(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_scalar_mat_constructor( + input: wp.array(dtype=wptype), + outcomponents: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + m2result = wptype(2) * mat22(input[0]) + m3result = wptype(2) * mat33(input[0]) + m4result = wptype(2) * mat44(input[0]) + m5result = wptype(2) * mat55(input[0]) + + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = m2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = m3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = m4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = m5result[i, j] + idx = idx + 1 + + def check_component_mat_constructor( + input: wp.array(dtype=wptype), + outcomponents: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + m2result = wptype(2) * mat22(input[0], input[1], input[2], input[3]) + m3result = wptype(2) * mat33( + input[4], + input[5], + input[6], + input[7], + input[8], + input[9], + input[10], + input[11], + input[12], + ) + m4result = wptype(2) * mat44( + input[13], + input[14], + input[15], + input[16], + input[17], + input[18], + input[19], + input[20], + input[21], + input[22], + input[23], + input[24], + input[25], + input[26], + input[27], + input[28], + ) + m5result = wptype(2) * mat55( + input[29], + input[30], + input[31], + input[32], + input[33], + input[34], + input[35], + input[36], + input[37], + input[38], + input[39], + input[40], + input[41], + input[42], + input[43], + input[44], + input[45], + input[46], + input[47], + input[48], + input[49], + input[50], + input[51], + input[52], + input[53], + ) + + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = m2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = m3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = m4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = m5result[i, j] + idx = idx + 1 + + def check_vector_mat_constructor( + input: wp.array(dtype=wptype), + outcomponents: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + m2result = wptype(2) * mat22(vec2(input[0], input[2]), vec2(input[1], input[3])) + m3result = wptype(2) * mat33( + vec3(input[4], input[7], input[10]), + vec3(input[5], input[8], input[11]), + vec3(input[6], input[9], input[12]), + ) + m4result = wptype(2) * mat44( + vec4(input[13], input[17], input[21], input[25]), + vec4(input[14], input[18], input[22], input[26]), + vec4(input[15], input[19], input[23], input[27]), + vec4(input[16], input[20], input[24], input[28]), + ) + m5result = wptype(2) * mat55( + vec5(input[29], input[34], input[39], input[44], input[49]), + vec5(input[30], input[35], input[40], input[45], input[50]), + vec5(input[31], input[36], input[41], input[46], input[51]), + vec5(input[32], input[37], input[42], input[47], input[52]), + vec5(input[33], input[38], input[43], input[48], input[53]), + ) + + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = m2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = m3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = m4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = m5result[i, j] + idx = idx + 1 + + kernel = getkernel(check_scalar_mat_constructor, suffix=dtype.__name__) + compkernel = getkernel(check_component_mat_constructor, suffix=dtype.__name__) + veckernel = getkernel(check_vector_mat_constructor, suffix=dtype.__name__) + + if register_kernels: + return + + input = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) + val = input.numpy()[0] + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:4], 2 * val * np.ones(2 * 2), tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * val * np.ones(3 * 3), tol=tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * val * np.ones(4 * 4), tol=tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * val * np.ones(5 * 5), tol=tol) + + if dtype in np_float_types: + for idx in range(len(outcomponents)): + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) + tape.backward(loss=out) + test.assertEqual(tape.gradients[input].numpy()[0], 2) + tape.zero() + + input = wp.array(randvals(rng, [2 * 2 + 3 * 3 + 4 * 4 + 5 * 5], dtype), requires_grad=True, device=device) + + wp.launch(compkernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) + assert_np_equal(2 * input.numpy(), outcomponents.numpy(), tol=10 * tol) + + if dtype in np_float_types: + for idx in range(len(outcomponents)): + tape = wp.Tape() + with tape: + wp.launch(compkernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) + tape.backward(loss=out) + expectedgrads = np.zeros(len(input)) + expectedgrads[idx] = 2 + assert_np_equal(tape.gradients[input].numpy(), expectedgrads) + tape.zero() + + wp.launch(veckernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) + assert_np_equal(2 * input.numpy(), outcomponents.numpy(), tol=10 * tol) + + if dtype in np_float_types: + for idx in range(len(outcomponents)): + tape = wp.Tape() + with tape: + wp.launch(veckernel, dim=1, inputs=[input], outputs=[outcomponents], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) + tape.backward(loss=out) + expectedgrads = np.zeros(len(input)) + expectedgrads[idx] = 2 + assert_np_equal(tape.gradients[input].numpy(), expectedgrads) + tape.zero() + + +def test_anon_type_instance(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def check_scalar_init( + input: wp.array(dtype=wptype), + output: wp.array(dtype=wptype), + ): + m2result = wp.matrix(input[0], shape=(2, 2)) + m3result = wp.matrix(input[1], shape=(3, 3)) + m4result = wp.matrix(input[2], shape=(4, 4)) + m5result = wp.matrix(input[3], shape=(5, 5)) + m32result = wp.matrix(input[4], shape=(3, 2)) + + idx = 0 + for i in range(2): + for j in range(2): + output[idx] = wptype(2) * m2result[i, j] + idx = idx + 1 + for i in range(3): + for j in range(3): + output[idx] = wptype(2) * m3result[i, j] + idx = idx + 1 + for i in range(4): + for j in range(4): + output[idx] = wptype(2) * m4result[i, j] + idx = idx + 1 + for i in range(5): + for j in range(5): + output[idx] = wptype(2) * m5result[i, j] + idx = idx + 1 + for i in range(3): + for j in range(2): + output[idx] = wptype(2) * m32result[i, j] + idx = idx + 1 + + def check_component_init( + input: wp.array(dtype=wptype), + output: wp.array(dtype=wptype), + ): + m2result = wp.matrix(input[0], input[1], input[2], input[3], shape=(2, 2)) + m3result = wp.matrix( + input[4], input[5], input[6], input[7], input[8], input[9], input[10], input[11], input[12], shape=(3, 3) + ) + m4result = wp.matrix( + input[13], + input[14], + input[15], + input[16], + input[17], + input[18], + input[19], + input[20], + input[21], + input[22], + input[23], + input[24], + input[25], + input[26], + input[27], + input[28], + shape=(4, 4), + ) + m5result = wp.matrix( + input[29], + input[30], + input[31], + input[32], + input[33], + input[34], + input[35], + input[36], + input[37], + input[38], + input[39], + input[40], + input[41], + input[42], + input[43], + input[44], + input[45], + input[46], + input[47], + input[48], + input[49], + input[50], + input[51], + input[52], + input[53], + shape=(5, 5), + ) + m32result = wp.matrix(input[54], input[55], input[56], input[57], input[58], input[59], shape=(3, 2)) + + idx = 0 + for i in range(2): + for j in range(2): + output[idx] = wptype(2) * m2result[i, j] + idx = idx + 1 + for i in range(3): + for j in range(3): + output[idx] = wptype(2) * m3result[i, j] + idx = idx + 1 + for i in range(4): + for j in range(4): + output[idx] = wptype(2) * m4result[i, j] + idx = idx + 1 + for i in range(5): + for j in range(5): + output[idx] = wptype(2) * m5result[i, j] + idx = idx + 1 + for i in range(3): + for j in range(2): + output[idx] = wptype(2) * m32result[i, j] + idx = idx + 1 + + scalar_kernel = getkernel(check_scalar_init, suffix=dtype.__name__) + component_kernel = getkernel(check_component_init, suffix=dtype.__name__) + output_select_kernel = get_select_kernel(wptype) + + if register_kernels: + return + + input = wp.array(randvals(rng, [5], dtype), requires_grad=True, device=device) + output = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2, dtype=wptype, requires_grad=True, device=device) + + wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) + + assert_np_equal(output.numpy()[:4], 2 * np.array([input.numpy()[0]] * 2 * 2), tol=1.0e-6) + assert_np_equal(output.numpy()[4:13], 2 * np.array([input.numpy()[1]] * 3 * 3), tol=1.0e-6) + assert_np_equal(output.numpy()[13:29], 2 * np.array([input.numpy()[2]] * 4 * 4), tol=1.0e-6) + assert_np_equal(output.numpy()[29:54], 2 * np.array([input.numpy()[3]] * 5 * 5), tol=1.0e-6) + assert_np_equal(output.numpy()[54:], 2 * np.array([input.numpy()[4]] * 3 * 2), tol=1.0e-6) + + if dtype in np_float_types: + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for i in range(len(output)): + tape = wp.Tape() + with tape: + wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) + + tape.backward(loss=out) + expected = np.zeros_like(input.numpy()) + if i < 4: + expected[0] = 2 + elif i < 13: + expected[1] = 2 + elif i < 29: + expected[2] = 2 + elif i < 54: + expected[3] = 2 + else: + expected[4] = 2 + + assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) + + tape.reset() + tape.zero() + + input = wp.array(randvals(rng, [2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2], dtype), requires_grad=True, device=device) + output = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2, dtype=wptype, requires_grad=True, device=device) + + wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) + + assert_np_equal(output.numpy(), 2 * input.numpy(), tol=1.0e-6) + + if dtype in np_float_types: + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for i in range(len(output)): + tape = wp.Tape() + with tape: + wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) + + tape.backward(loss=out) + expected = np.zeros_like(input.numpy()) + expected[i] = 2 + + assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) + + tape.reset() + tape.zero() + + +def test_identity(test, device, dtype, register_kernels=False): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def check_identity_mat( + output: wp.array(dtype=wptype), + ): + m2result = wp.identity(dtype=wptype, n=2) + m3result = wp.identity(dtype=wptype, n=3) + m4result = wp.identity(dtype=wptype, n=4) + m5result = wp.identity(dtype=wptype, n=5) + + idx = 0 + for i in range(2): + for j in range(2): + output[idx] = wptype(2) * m2result[i, j] + idx = idx + 1 + for i in range(3): + for j in range(3): + output[idx] = wptype(2) * m3result[i, j] + idx = idx + 1 + for i in range(4): + for j in range(4): + output[idx] = wptype(2) * m4result[i, j] + idx = idx + 1 + for i in range(5): + for j in range(5): + output[idx] = wptype(2) * m5result[i, j] + idx = idx + 1 + + id_kernel = getkernel(check_identity_mat, suffix=dtype.__name__) + + if register_kernels: + return + + output = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) + wp.launch(id_kernel, dim=1, inputs=[], outputs=[output], device=device) + assert_np_equal(output.numpy()[:4], 2 * np.eye(2), tol=1.0e-6) + assert_np_equal(output.numpy()[4:13], 2 * np.eye(3), tol=1.0e-6) + assert_np_equal(output.numpy()[13:29], 2 * np.eye(4), tol=1.0e-6) + assert_np_equal(output.numpy()[29:], 2 * np.eye(5), tol=1.0e-6) + + +def test_indexing(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_indexing( + m2: wp.array(dtype=mat22), + m3: wp.array(dtype=mat33), + m4: wp.array(dtype=mat44), + m5: wp.array(dtype=mat55), + outcomponents: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = wptype(2) * m2[0][i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = wptype(2) * m3[0][i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = wptype(2) * m4[0][i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = wptype(2) * m5[0][i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_indexing, suffix=dtype.__name__) + + if register_kernels: + return + + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:4], 2 * m2.numpy().reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * m3.numpy().reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * m4.numpy().reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * m5.numpy().reshape(-1), tol=tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, input in [(2, m2), (3, m3), (4, m4), (5, m5)]: + for i in range(dim): + for j in range(dim): + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5], outputs=[outcomponents], device=device) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + expectedresult = np.zeros((dim, dim), dtype=dtype) + expectedresult[i, j] = 2 + assert_np_equal(tape.gradients[input].numpy()[0], expectedresult) + tape.zero() + idx = idx + 1 + + +def test_equality(test, device, dtype, register_kernels=False): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + def check_mat_equality(): + wp.expect_eq( + mat22(wptype(1.0), wptype(2.0), wptype(3.0), wptype(4.0)), + mat22(wptype(1.0), wptype(2.0), wptype(3.0), wptype(4.0)), + ) + wp.expect_neq( + mat22(wptype(1.0), wptype(2.0), wptype(3.0), -wptype(4.0)), + mat22(wptype(1.0), wptype(2.0), wptype(3.0), wptype(4.0)), + ) + + wp.expect_eq( + mat33( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + ), + mat33( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + ), + ) + wp.expect_neq( + mat33( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + ), + mat33( + wptype(1.0), + wptype(2.0), + wptype(3.0), + -wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + ), + ) + + wp.expect_eq( + mat44( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + ), + mat44( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + ), + ) + + wp.expect_neq( + mat44( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + ), + mat44( + -wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + ), + ) + + wp.expect_eq( + mat55( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + wptype(17.0), + wptype(18.0), + wptype(19.0), + wptype(20.0), + wptype(21.0), + wptype(22.0), + wptype(23.0), + wptype(24.0), + wptype(25.0), + ), + mat55( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + wptype(17.0), + wptype(18.0), + wptype(19.0), + wptype(20.0), + wptype(21.0), + wptype(22.0), + wptype(23.0), + wptype(24.0), + wptype(25.0), + ), + ) + + wp.expect_neq( + mat55( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + wptype(17.0), + wptype(18.0), + wptype(19.0), + wptype(20.0), + wptype(21.0), + wptype(22.0), + wptype(23.0), + wptype(24.0), + wptype(25.0), + ), + mat55( + wptype(1.0), + wptype(2.0), + wptype(3.0), + wptype(4.0), + wptype(5.0), + wptype(6.0), + wptype(7.0), + wptype(8.0), + wptype(9.0), + wptype(10.0), + wptype(11.0), + wptype(12.0), + wptype(13.0), + wptype(14.0), + wptype(15.0), + wptype(16.0), + -wptype(17.0), + wptype(18.0), + wptype(19.0), + wptype(20.0), + wptype(21.0), + wptype(22.0), + wptype(23.0), + wptype(24.0), + wptype(25.0), + ), + ) + + kernel = getkernel(check_mat_equality, suffix=dtype.__name__) + + if register_kernels: + return + + wp.launch(kernel, dim=1, inputs=[], outputs=[], device=device) + + +def test_scalar_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-2, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_scalar_mul( + s: wp.array(dtype=wptype), + m2: wp.array(dtype=mat22), + m3: wp.array(dtype=mat33), + m4: wp.array(dtype=mat44), + m5: wp.array(dtype=mat55), + outcomponents: wp.array(dtype=wptype), + outcomponents_rightmul: wp.array(dtype=wptype), + ): + m2result = s[0] * m2[0] + m3result = s[0] * m3[0] + m4result = s[0] * m4[0] + m5result = s[0] * m5[0] + + m2resultright = m2[0] * s[0] + m3resultright = m3[0] * s[0] + m4resultright = m4[0] * s[0] + m5resultright = m5[0] * s[0] + + m2result_2 = s[0] * m2[0] + m3result_2 = s[0] * m3[0] + m4result_2 = s[0] * m4[0] + m5result_2 = s[0] * m5[0] + + m2resultright_2 = m2[0] * s[0] + m3resultright_2 = m3[0] * s[0] + m4resultright_2 = m4[0] * s[0] + m5resultright_2 = m5[0] * s[0] + + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = wptype(2) * m2result[i, j] + outcomponents_rightmul[idx] = wptype(2) * m2resultright[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = wptype(2) * m3result[i, j] + outcomponents_rightmul[idx] = wptype(2) * m3resultright[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = wptype(2) * m4result[i, j] + outcomponents_rightmul[idx] = wptype(2) * m4resultright[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = wptype(2) * m5result[i, j] + outcomponents_rightmul[idx] = wptype(2) * m5resultright[i, j] + idx = idx + 1 + + for i in range(2): + for j in range(2): + outcomponents[idx] = wptype(2) * m2result_2[i, j] + outcomponents_rightmul[idx] = wptype(2) * m2resultright_2[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = wptype(2) * m3result_2[i, j] + outcomponents_rightmul[idx] = wptype(2) * m3resultright_2[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = wptype(2) * m4result_2[i, j] + outcomponents_rightmul[idx] = wptype(2) * m4resultright_2[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = wptype(2) * m5result_2[i, j] + outcomponents_rightmul[idx] = wptype(2) * m5resultright_2[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_scalar_mul, suffix=dtype.__name__) + + if register_kernels: + return + + s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * (2 * 2 + 3 * 3 + 4 * 4 + 5 * 5), dtype=wptype, requires_grad=True, device=device) + outcomponents_rightmul = wp.zeros( + 2 * (2 * 2 + 3 * 3 + 4 * 4 + 5 * 5), dtype=wptype, requires_grad=True, device=device + ) + + wp.launch(kernel, dim=1, inputs=[s, m2, m3, m4, m5], outputs=[outcomponents, outcomponents_rightmul], device=device) + + sval = s.numpy()[0] + assert_np_equal(outcomponents.numpy()[:4], 2 * sval * m2.numpy().reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) + + assert_np_equal(outcomponents_rightmul.numpy()[:4], 2 * sval * m2.numpy().reshape(-1), tol=tol) + assert_np_equal(outcomponents_rightmul.numpy()[4:13], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents_rightmul.numpy()[13:29], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents_rightmul.numpy()[29:54], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) + + assert_np_equal(outcomponents.numpy()[54:58], 2 * sval * m2.numpy().reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[58:67], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[67:83], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[83:108], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) + + assert_np_equal(outcomponents_rightmul.numpy()[54:58], 2 * sval * m2.numpy().reshape(-1), tol=tol) + assert_np_equal(outcomponents_rightmul.numpy()[58:67], 2 * sval * m3.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents_rightmul.numpy()[67:83], 2 * sval * m4.numpy().reshape(-1), tol=10 * tol) + assert_np_equal(outcomponents_rightmul.numpy()[83:108], 2 * sval * m5.numpy().reshape(-1), tol=10 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, input in [(2, m2), (3, m3), (4, m4), (5, m5)]: + for i in range(dim): + for j in range(dim): + # test left mul gradient: + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[s, m2, m3, m4, m5], + outputs=[outcomponents, outcomponents_rightmul], + device=device, + ) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + expectedresult = np.zeros((dim, dim), dtype=dtype) + expectedresult[i, j] = 2 * sval + assert_np_equal(tape.gradients[input].numpy()[0], expectedresult, tol=10 * tol) + assert_np_equal(tape.gradients[s].numpy()[0], 2 * input.numpy()[0, i, j], tol=10 * tol) + tape.zero() + + # test right mul gradient: + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[s, m2, m3, m4, m5], + outputs=[outcomponents, outcomponents_rightmul], + device=device, + ) + wp.launch( + output_select_kernel, + dim=1, + inputs=[outcomponents_rightmul, idx], + outputs=[out], + device=device, + ) + tape.backward(loss=out) + expectedresult = np.zeros((dim, dim), dtype=dtype) + expectedresult[i, j] = 2 * sval + assert_np_equal(tape.gradients[input].numpy()[0], expectedresult, tol=10 * tol) + assert_np_equal(tape.gradients[s].numpy()[0], 2 * input.numpy()[0, i, j], tol=10 * tol) + tape.zero() + + idx = idx + 1 + + +def test_matvec_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 2.0e-2, + np.float32: 5.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_vec_mul( + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v32: wp.array(dtype=vec2), + m2: wp.array(dtype=mat22), + m3: wp.array(dtype=mat33), + m4: wp.array(dtype=mat44), + m5: wp.array(dtype=mat55), + m32: wp.array(dtype=mat32), + outcomponents: wp.array(dtype=wptype), + ): + v2result = m2[0] * v2[0] + v3result = m3[0] * v3[0] + v4result = m4[0] * v4[0] + v5result = m5[0] * v5[0] + v32result = m32[0] * v32[0] + v2result_2 = m2[0] @ v2[0] + v3result_2 = m3[0] @ v3[0] + v4result_2 = m4[0] @ v4[0] + v5result_2 = m5[0] @ v5[0] + v32result_2 = m32[0] @ v32[0] + + idx = 0 + + # multiply outputs by 2 so we've got something to backpropagate: + for i in range(2): + outcomponents[idx] = wptype(2) * v2result[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v3result[i] + idx = idx + 1 + + for i in range(4): + outcomponents[idx] = wptype(2) * v4result[i] + idx = idx + 1 + + for i in range(5): + outcomponents[idx] = wptype(2) * v5result[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v32result[i] + idx = idx + 1 + + for i in range(2): + outcomponents[idx] = wptype(2) * v2result_2[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v3result_2[i] + idx = idx + 1 + + for i in range(4): + outcomponents[idx] = wptype(2) * v4result_2[i] + idx = idx + 1 + + for i in range(5): + outcomponents[idx] = wptype(2) * v5result_2[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v32result_2[i] + idx = idx + 1 + + kernel = getkernel(check_mat_vec_mul, suffix=dtype.__name__) + + if register_kernels: + return + + v2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) + v32 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + m32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * (2 + 3 + 4 + 5 + 3), dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:2], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[2:5], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[5:9], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[9:14], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[14:17], 2 * np.matmul(m32.numpy()[0], v32.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[17:19], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[19:22], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[22:26], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[26:31], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[31:34], 2 * np.matmul(m32.numpy()[0], v32.numpy()[0]), tol=5 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, invec, inmat in [(2, v2, m2), (3, v3, m3), (4, v4, m4), (5, v5, m5), (3, v32, m32)]: + for i in range(dim): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], + outputs=[outcomponents], + device=device, + ) + wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) + tape.backward(loss=out) + + assert_np_equal(tape.gradients[invec].numpy()[0], 2 * inmat.numpy()[0, i, :], tol=2 * tol) + expectedresult = np.zeros(inmat.dtype._shape_, dtype=dtype) + expectedresult[i, :] = 2 * invec.numpy()[0] + assert_np_equal(tape.gradients[inmat].numpy()[0], expectedresult, tol=2 * tol) + + tape.zero() + + idx = idx + 1 + + +def test_vecmat_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 2.0e-2, + np.float32: 5.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat23 = wp.types.matrix(shape=(2, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_vec_mat_mul( + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v32: wp.array(dtype=vec2), + m2: wp.array(dtype=mat22), + m3: wp.array(dtype=mat33), + m4: wp.array(dtype=mat44), + m5: wp.array(dtype=mat55), + m23: wp.array(dtype=mat23), + outcomponents: wp.array(dtype=wptype), + ): + v2result = v2[0] * m2[0] + v3result = v3[0] * m3[0] + v4result = v4[0] * m4[0] + v5result = v5[0] * m5[0] + v32result = v32[0] * m23[0] + v2result_2 = v2[0] @ m2[0] + v3result_2 = v3[0] @ m3[0] + v4result_2 = v4[0] @ m4[0] + v5result_2 = v5[0] @ m5[0] + v32result_2 = v32[0] @ m23[0] + + idx = 0 + + # multiply outputs by 2 so we've got something to backpropagate: + for i in range(2): + outcomponents[idx] = wptype(2) * v2result[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v3result[i] + idx = idx + 1 + + for i in range(4): + outcomponents[idx] = wptype(2) * v4result[i] + idx = idx + 1 + + for i in range(5): + outcomponents[idx] = wptype(2) * v5result[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v32result[i] + idx = idx + 1 + + for i in range(2): + outcomponents[idx] = wptype(2) * v2result_2[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v3result_2[i] + idx = idx + 1 + + for i in range(4): + outcomponents[idx] = wptype(2) * v4result_2[i] + idx = idx + 1 + + for i in range(5): + outcomponents[idx] = wptype(2) * v5result_2[i] + idx = idx + 1 + + for i in range(3): + outcomponents[idx] = wptype(2) * v32result_2[i] + idx = idx + 1 + + kernel = getkernel(check_vec_mat_mul, suffix=dtype.__name__) + + if register_kernels: + return + + v2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) + v32 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + m23 = wp.array(randvals(rng, [1, 2, 3], dtype), dtype=mat23, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * (2 + 3 + 4 + 5 + 3), dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m23], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:2], 2 * np.matmul(v2.numpy()[0], m2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[2:5], 2 * np.matmul(v3.numpy()[0], m3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[5:9], 2 * np.matmul(v4.numpy()[0], m4.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[9:14], 2 * np.matmul(v5.numpy()[0], m5.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[14:17], 2 * np.matmul(v32.numpy()[0], m23.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[17:19], 2 * np.matmul(v2.numpy()[0], m2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[19:22], 2 * np.matmul(v3.numpy()[0], m3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[22:26], 2 * np.matmul(v4.numpy()[0], m4.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[26:31], 2 * np.matmul(v5.numpy()[0], m5.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[31:34], 2 * np.matmul(v32.numpy()[0], m23.numpy()[0]), tol=5 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, inmat, invec in [(2, m2, v2), (3, m3, v3), (4, m4, v4), (5, m5, v5), (3, m23, v32)]: + for i in range(dim): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m23], + outputs=[outcomponents], + device=device, + ) + wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) + tape.backward(loss=out) + + assert_np_equal(tape.gradients[invec].numpy()[0], 2 * inmat.numpy()[0, :, i], tol=2 * tol) + expectedresult = np.zeros(inmat.dtype._shape_, dtype=dtype) + expectedresult[:, i] = 2 * invec.numpy()[0] + assert_np_equal(tape.gradients[inmat].numpy()[0], expectedresult, tol=2 * tol) + + tape.zero() + + idx = idx + 1 + + +def test_matmat_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 2.0e-2, + np.float32: 5.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_mat_mul( + a2: wp.array(dtype=mat22), + a3: wp.array(dtype=mat33), + a4: wp.array(dtype=mat44), + a5: wp.array(dtype=mat55), + a32: wp.array(dtype=mat32), + b2: wp.array(dtype=mat22), + b3: wp.array(dtype=mat33), + b4: wp.array(dtype=mat44), + b5: wp.array(dtype=mat55), + b32: wp.array(dtype=mat32), + outcomponents: wp.array(dtype=wptype), + ): + c2result = b2[0] * a2[0] + c3result = b3[0] * a3[0] + c4result = b4[0] * a4[0] + c5result = b5[0] * a5[0] + c32result = b32[0] * a2[0] + c32result2 = b3[0] * a32[0] + c2result_2 = b2[0] @ a2[0] + c3result_2 = b3[0] @ a3[0] + c4result_2 = b4[0] @ a4[0] + c5result_2 = b5[0] @ a5[0] + c32result_2 = b32[0] @ a2[0] + c32result2_2 = b3[0] @ a32[0] + + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = wptype(2) * c2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = wptype(2) * c3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = wptype(2) * c4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = wptype(2) * c5result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(2): + outcomponents[idx] = wptype(2) * c32result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(2): + outcomponents[idx] = wptype(2) * c32result2[i, j] + idx = idx + 1 + + for i in range(2): + for j in range(2): + outcomponents[idx] = wptype(2) * c2result_2[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = wptype(2) * c3result_2[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = wptype(2) * c4result_2[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = wptype(2) * c5result_2[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(2): + outcomponents[idx] = wptype(2) * c32result_2[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(2): + outcomponents[idx] = wptype(2) * c32result2_2[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_mat_mul, suffix=dtype.__name__) + + if register_kernels: + return + + v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + v32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + m32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) + outcomponents = wp.zeros( + 2 * (2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 3 * 2 + 3 * 2), dtype=wptype, requires_grad=True, device=device + ) + + wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:4], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=2 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[54:60], 2 * np.matmul(m32.numpy()[0], v2.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[60:66], 2 * np.matmul(m3.numpy()[0], v32.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[66:70], 2 * np.matmul(m2.numpy()[0], v2.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[70:79], 2 * np.matmul(m3.numpy()[0], v3.numpy()[0]), tol=tol) + assert_np_equal(outcomponents.numpy()[79:95], 2 * np.matmul(m4.numpy()[0], v4.numpy()[0]), tol=2 * tol) + assert_np_equal(outcomponents.numpy()[95:120], 2 * np.matmul(m5.numpy()[0], v5.numpy()[0]), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[120:126], 2 * np.matmul(m32.numpy()[0], v2.numpy()[0]), tol=5 * tol) + assert_np_equal(outcomponents.numpy()[126:132], 2 * np.matmul(m3.numpy()[0], v32.numpy()[0]), tol=5 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for v, m in [(v2, m2), (v3, m3), (v4, m4), (v5, m5), (v2, m32), (v32, m3)]: + rows, cols = m.dtype._shape_[0], v.dtype._shape_[1] + for i in range(rows): + for j in range(cols): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[v2, v3, v4, v5, v32, m2, m3, m4, m5, m32], + outputs=[outcomponents], + device=device, + ) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + + expected = np.zeros(v.dtype._shape_, dtype=dtype) + expected[:, j] = 2 * m.numpy()[0, i, :] + assert_np_equal(tape.gradients[v].numpy()[0], expected, tol=10 * tol) + + expected = np.zeros(m.dtype._shape_, dtype=dtype) + expected[i, :] = 2 * v.numpy()[0, :, j] + assert_np_equal(tape.gradients[m].numpy()[0], expected, tol=10 * tol) + + tape.zero() + idx = idx + 1 + + +def test_cw_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-2, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_cw_mul( + s2: wp.array(dtype=mat22), + s3: wp.array(dtype=mat33), + s4: wp.array(dtype=mat44), + s5: wp.array(dtype=mat55), + v2: wp.array(dtype=mat22), + v3: wp.array(dtype=mat33), + v4: wp.array(dtype=mat44), + v5: wp.array(dtype=mat55), + outcomponents: wp.array(dtype=wptype), + ): + v2result = wptype(2) * wp.cw_mul(v2[0], s2[0]) + v3result = wptype(2) * wp.cw_mul(v3[0], s3[0]) + v4result = wptype(2) * wp.cw_mul(v4[0], s4[0]) + v5result = wptype(2) * wp.cw_mul(v5[0], s5[0]) + + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = v2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = v3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = v4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = v5result[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_cw_mul, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[outcomponents], + device=device, + ) + + assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() * s2.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() * s3.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() * s4.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() * s5.numpy()).reshape(-1), tol=50 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, in1, in2 in [(2, s2, v2), (3, s3, v3), (4, s4, v4), (5, s5, v5)]: + for i in range(dim): + for j in range(dim): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[outcomponents], + device=device, + ) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + expectedresult = np.zeros((dim, dim), dtype=dtype) + expectedresult[i, j] = 2 * in1.numpy()[0][i, j] + assert_np_equal(tape.gradients[in2].numpy()[0], expectedresult, tol=5 * tol) + expectedresult[i, j] = 2 * in2.numpy()[0][i, j] + assert_np_equal(tape.gradients[in1].numpy()[0], expectedresult, tol=5 * tol) + tape.zero() + + idx = idx + 1 + + +def test_cw_division(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-2, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_cw_div( + s2: wp.array(dtype=mat22), + s3: wp.array(dtype=mat33), + s4: wp.array(dtype=mat44), + s5: wp.array(dtype=mat55), + v2: wp.array(dtype=mat22), + v3: wp.array(dtype=mat33), + v4: wp.array(dtype=mat44), + v5: wp.array(dtype=mat55), + outcomponents: wp.array(dtype=wptype), + ): + v2result = wptype(2) * wp.cw_div(v2[0], s2[0]) + v3result = wptype(2) * wp.cw_div(v3[0], s3[0]) + v4result = wptype(2) * wp.cw_div(v4[0], s4[0]) + v5result = wptype(2) * wp.cw_div(v5[0], s5[0]) + + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = v2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = v3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = v4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = v5result[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_cw_div, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = randvals(rng, [1, 2, 2], dtype) + s3 = randvals(rng, [1, 3, 3], dtype) + s4 = randvals(rng, [1, 4, 4], dtype) + s5 = randvals(rng, [1, 5, 5], dtype) + + # set denominators to 1 if their magnitudes are small + # to prevent divide by zero, or overflows if we're testing + # float16: + s2[np.abs(s2) < 1.0e-2] = 1 + s3[np.abs(s3) < 1.0e-2] = 1 + s4[np.abs(s4) < 1.0e-2] = 1 + s5[np.abs(s5) < 1.0e-2] = 1 + + s2 = wp.array(s2, dtype=mat22, requires_grad=True, device=device) + s3 = wp.array(s3, dtype=mat33, requires_grad=True, device=device) + s4 = wp.array(s4, dtype=mat44, requires_grad=True, device=device) + s5 = wp.array(s5, dtype=mat55, requires_grad=True, device=device) + + v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[outcomponents], + device=device, + ) + + if dtype in np_float_types: + assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() / s2.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() / s3.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() / s4.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() / s5.numpy()).reshape(-1), tol=50 * tol) + else: + assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() // s2.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() // s3.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() // s4.numpy()).reshape(-1), tol=50 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() // s5.numpy()).reshape(-1), tol=50 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, s, v in [(2, s2, v2), (3, s3, v3), (4, s4, v4), (5, s5, v5)]: + for i in range(dim): + for j in range(dim): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[outcomponents], + device=device, + ) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + + # y = v/s + # dy/dv = 1.0/s + # dy/ds = -v/s^2 + + expectedresult = np.zeros((dim, dim), dtype=dtype) + expectedresult[i, j] = 2.0 / (s.numpy()[0, i, j]) + assert_np_equal(tape.gradients[v].numpy()[0], expectedresult, tol=50 * tol) + expectedresult[i, j] = -2.0 * v.numpy()[0, i, j] / (s.numpy()[0, i, j] ** 2) + assert_np_equal( + tape.gradients[s].numpy()[0], expectedresult, tol=abs(outcomponents.numpy()[idx]) * 50 * tol + ) + tape.zero() + + idx = idx + 1 + + +def test_outer_product(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_outer_product( + s2: wp.array(dtype=vec2), + s3: wp.array(dtype=vec3), + s4: wp.array(dtype=vec4), + s5: wp.array(dtype=vec5), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + outcomponents: wp.array(dtype=wptype), + ): + m22result = wptype(2) * wp.outer(s2[0], v2[0]) + m33result = wptype(2) * wp.outer(s3[0], v3[0]) + m44result = wptype(2) * wp.outer(s4[0], v4[0]) + m55result = wptype(2) * wp.outer(s5[0], v5[0]) + m25result = wptype(2) * wp.outer(s2[0], v5[0]) + + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = m22result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = m33result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = m44result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = m55result[i, j] + idx = idx + 1 + + for i in range(2): + for j in range(5): + outcomponents[idx] = m25result[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_outer_product, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, [1, 2], dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3], dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4], dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 2 * 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[s2, s3, s4, s5, v2, v3, v4, v5], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:4], 2 * s2.numpy()[0, :, None] * v2.numpy()[0, None, :], tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * s3.numpy()[0, :, None] * v3.numpy()[0, None, :], tol=10 * tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * s4.numpy()[0, :, None] * v4.numpy()[0, None, :], tol=10 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * s5.numpy()[0, :, None] * v5.numpy()[0, None, :], tol=10 * tol) + assert_np_equal(outcomponents.numpy()[54:], 2 * s2.numpy()[0, :, None] * v5.numpy()[0, None, :], tol=10 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for s, v in [(s2, v2), (s3, v3), (s4, v4), (s5, v5), (s2, v5)]: + rows = s.dtype._length_ + cols = v.dtype._length_ + for i in range(rows): + for j in range(cols): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[outcomponents], + device=device, + ) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + + # this component's gonna be s_i * v_j, so its s gradient is gonna be nozero + # at the ith component and its v gradient will be nonzero at the jth component: + + expectedresult = np.zeros((rows), dtype=dtype) + expectedresult[i] = 2 * v.numpy()[0, j] + assert_np_equal(tape.gradients[s].numpy()[0], expectedresult, tol=10 * tol) + + expectedresult = np.zeros((cols), dtype=dtype) + expectedresult[j] = 2 * s.numpy()[0, i] + assert_np_equal(tape.gradients[v].numpy()[0], expectedresult, tol=10 * tol) + tape.zero() + + idx = idx + 1 + + +def test_transpose(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-2, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat32 = wp.types.matrix(shape=(3, 2), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_transpose( + m2: wp.array(dtype=mat22), + m3: wp.array(dtype=mat33), + m4: wp.array(dtype=mat44), + m5: wp.array(dtype=mat55), + m32: wp.array(dtype=mat32), + outcomponents: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + mat2 = wptype(2) * wp.transpose(m2[0]) + mat3 = wptype(2) * wp.transpose(m3[0]) + mat4 = wptype(2) * wp.transpose(m4[0]) + mat5 = wptype(2) * wp.transpose(m5[0]) + mat32 = wptype(2) * wp.transpose(m32[0]) + + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = mat2[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = mat3[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = mat4[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = mat5[i, j] + idx = idx + 1 + + for i in range(2): + for j in range(3): + outcomponents[idx] = mat32[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_transpose, suffix=dtype.__name__) + + if register_kernels: + return + + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + m32 = wp.array(randvals(rng, [1, 3, 2], dtype), dtype=mat32, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5 + 2 * 3, dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy()[:4], 2 * m2.numpy()[0].T.reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * m3.numpy()[0].T.reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * m4.numpy()[0].T.reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * m5.numpy()[0].T.reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[54:], 2 * m32.numpy()[0].T.reshape(-1), tol=tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for input in [m2, m3, m4, m5]: + for i in range(input.dtype._shape_[0]): + for j in range(input.dtype._shape_[1]): + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5, m32], outputs=[outcomponents], device=device) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + expectedresult = np.zeros((input.dtype._shape_[1], input.dtype._shape_[0]), dtype=dtype) + expectedresult[j, i] = 2 + assert_np_equal(tape.gradients[input].numpy()[0], expectedresult) + tape.zero() + idx = idx + 1 + + +def test_scalar_division(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-2, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_scalar_div( + s: wp.array(dtype=wptype), + m2: wp.array(dtype=mat22), + m3: wp.array(dtype=mat33), + m4: wp.array(dtype=mat44), + m5: wp.array(dtype=mat55), + outcomponents: wp.array(dtype=wptype), + ): + m2result = m2[0] / s[0] + m3result = m3[0] / s[0] + m4result = m4[0] / s[0] + m5result = m5[0] / s[0] + + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = wptype(2) * m2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = wptype(2) * m3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = wptype(2) * m4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = wptype(2) * m5result[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_scalar_div, suffix=dtype.__name__) + + if register_kernels: + return + + s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) + m2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + m3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + m4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + m5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[s, m2, m3, m4, m5], outputs=[outcomponents], device=device) + + sval = s.numpy()[0] + if dtype in np_float_types: + assert_np_equal(outcomponents.numpy()[:4], 2 * m2.numpy().reshape(-1) / sval, tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * m3.numpy().reshape(-1) / sval, tol=10 * tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * m4.numpy().reshape(-1) / sval, tol=10 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * m5.numpy().reshape(-1) / sval, tol=10 * tol) + else: + assert_np_equal(outcomponents.numpy()[:4], 2 * (m2.numpy().reshape(-1) // sval), tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * (m3.numpy().reshape(-1) // sval), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * (m4.numpy().reshape(-1) // sval), tol=10 * tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * (m5.numpy().reshape(-1) // sval), tol=10 * tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, input in [(2, m2), (3, m3), (4, m4), (5, m5)]: + for i in range(dim): + for j in range(dim): + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[s, m2, m3, m4, m5], outputs=[outcomponents], device=device) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + expectedresult = np.zeros((dim, dim), dtype=dtype) + expectedresult[i, j] = 2.0 / sval + assert_np_equal(tape.gradients[input].numpy()[0], expectedresult, tol=10 * tol) + assert_np_equal( + tape.gradients[s].numpy()[0], -2 * input.numpy()[0, i, j] / (sval * sval), tol=10 * tol + ) + tape.zero() + + idx = idx + 1 + + +def test_addition(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 2.0e-2, + np.float32: 5.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_add( + s2: wp.array(dtype=mat22), + s3: wp.array(dtype=mat33), + s4: wp.array(dtype=mat44), + s5: wp.array(dtype=mat55), + v2: wp.array(dtype=mat22), + v3: wp.array(dtype=mat33), + v4: wp.array(dtype=mat44), + v5: wp.array(dtype=mat55), + outcomponents: wp.array(dtype=wptype), + ): + v2result = v2[0] + s2[0] + v3result = v3[0] + s3[0] + v4result = v4[0] + s4[0] + v5result = v5[0] + s5[0] + + # multiply outputs by 2 so we've got something to backpropagate: + idx = 0 + for i in range(2): + for j in range(2): + outcomponents[idx] = wptype(2) * v2result[i, j] + idx = idx + 1 + + for i in range(3): + for j in range(3): + outcomponents[idx] = wptype(2) * v3result[i, j] + idx = idx + 1 + + for i in range(4): + for j in range(4): + outcomponents[idx] = wptype(2) * v4result[i, j] + idx = idx + 1 + + for i in range(5): + for j in range(5): + outcomponents[idx] = wptype(2) * v5result[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_add, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + outcomponents = wp.zeros(2 * 2 + 3 * 3 + 4 * 4 + 5 * 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[outcomponents], + device=device, + ) + + assert_np_equal(outcomponents.numpy()[:4], 2 * (v2.numpy() + s2.numpy()).reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[4:13], 2 * (v3.numpy() + s3.numpy()).reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[13:29], 2 * (v4.numpy() + s4.numpy()).reshape(-1), tol=tol) + assert_np_equal(outcomponents.numpy()[29:54], 2 * (v5.numpy() + s5.numpy()).reshape(-1), tol=tol) + + if dtype in np_float_types: + idx = 0 + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for dim, in1, in2 in [(2, s2, v2), (3, s3, v3), (4, s4, v4), (5, s5, v5)]: + for i in range(dim): + for j in range(dim): + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[outcomponents], + device=device, + ) + wp.launch( + output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device + ) + tape.backward(loss=out) + expectedresult = np.zeros((dim, dim), dtype=dtype) + expectedresult[i, j] = 2 + assert_np_equal(tape.gradients[in2].numpy()[0], expectedresult, tol=10 * tol) + expectedresult[i, j] = 2 + assert_np_equal(tape.gradients[in1].numpy()[0], expectedresult, tol=10 * tol) + tape.zero() + + idx = idx + 1 + + +def test_ddot(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + def check_mat_dot( + s2: wp.array(dtype=mat22), + s3: wp.array(dtype=mat33), + s4: wp.array(dtype=mat44), + s5: wp.array(dtype=mat55), + v2: wp.array(dtype=mat22), + v3: wp.array(dtype=mat33), + v4: wp.array(dtype=mat44), + v5: wp.array(dtype=mat55), + dot2: wp.array(dtype=wptype), + dot3: wp.array(dtype=wptype), + dot4: wp.array(dtype=wptype), + dot5: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + dot2[0] = wptype(2) * wp.ddot(v2[0], s2[0]) + dot3[0] = wptype(2) * wp.ddot(v3[0], s3[0]) + dot4[0] = wptype(2) * wp.ddot(v4[0], s4[0]) + dot5[0] = wptype(2) * wp.ddot(v5[0], s5[0]) + + kernel = getkernel(check_mat_dot, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + dot2 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + dot3 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + dot4 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + dot5 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[dot2, dot3, dot4, dot5], + device=device, + ) + + assert_np_equal(dot2.numpy()[0], 2 * (v2.numpy() * s2.numpy()).sum(), tol=10 * tol) + assert_np_equal(dot3.numpy()[0], 2 * (v3.numpy() * s3.numpy()).sum(), tol=10 * tol) + assert_np_equal(dot4.numpy()[0], 2 * (v4.numpy() * s4.numpy()).sum(), tol=50 * tol) + assert_np_equal(dot5.numpy()[0], 2 * (v5.numpy() * s5.numpy()).sum(), tol=200 * tol) + + if dtype in np_float_types: + tape.backward(loss=dot2) + sgrads = tape.gradients[s2].numpy()[0] + expected_grads = 2.0 * v2.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v2].numpy()[0] + expected_grads = 2.0 * s2.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=10 * tol) + + tape.zero() + + tape.backward(loss=dot3) + sgrads = tape.gradients[s3].numpy()[0] + expected_grads = 2.0 * v3.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v3].numpy()[0] + expected_grads = 2.0 * s3.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=10 * tol) + + tape.zero() + + tape.backward(loss=dot4) + sgrads = tape.gradients[s4].numpy()[0] + expected_grads = 2.0 * v4.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v4].numpy()[0] + expected_grads = 2.0 * s4.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=10 * tol) + + tape.zero() + + tape.backward(loss=dot5) + sgrads = tape.gradients[s5].numpy()[0] + expected_grads = 2.0 * v5.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v5].numpy()[0] + expected_grads = 2.0 * s5.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=10 * tol) + + tape.zero() + + +def test_trace(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + def check_mat_trace( + v2: wp.array(dtype=mat22), + v3: wp.array(dtype=mat33), + v4: wp.array(dtype=mat44), + v5: wp.array(dtype=mat55), + tr2: wp.array(dtype=wptype), + tr3: wp.array(dtype=wptype), + tr4: wp.array(dtype=wptype), + tr5: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + tr2[0] = wptype(2) * wp.trace(v2[0]) + tr3[0] = wptype(2) * wp.trace(v3[0]) + tr4[0] = wptype(2) * wp.trace(v4[0]) + tr5[0] = wptype(2) * wp.trace(v5[0]) + + kernel = getkernel(check_mat_trace, suffix=dtype.__name__) + + if register_kernels: + return + + v2 = wp.array(randvals(rng, [1, 2, 2], dtype), dtype=mat22, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, [1, 3, 3], dtype), dtype=mat33, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, [1, 4, 4], dtype), dtype=mat44, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, [1, 5, 5], dtype), dtype=mat55, requires_grad=True, device=device) + tr2 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tr3 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tr4 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tr5 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + v2, + v3, + v4, + v5, + ], + outputs=[ + tr2, + tr3, + tr4, + tr5, + ], + device=device, + ) + + assert_np_equal(tr2.numpy()[0], 2 * np.trace(v2.numpy()[0]), tol=10 * tol) + assert_np_equal(tr3.numpy()[0], 2 * np.trace(v3.numpy()[0]), tol=10 * tol) + assert_np_equal(tr4.numpy()[0], 2 * np.trace(v4.numpy()[0]), tol=200 * tol) + assert_np_equal(tr4.numpy()[0], 2 * np.trace(v4.numpy()[0]), tol=200 * tol) + + if dtype in np_float_types: + tape.backward(loss=tr2) + vgrads = tape.gradients[v2].numpy()[0] + assert_np_equal(vgrads, 2.0 * np.eye(2), tol=10 * tol) + tape.zero() + + tape.backward(loss=tr3) + vgrads = tape.gradients[v3].numpy()[0] + assert_np_equal(vgrads, 2.0 * np.eye(3), tol=10 * tol) + tape.zero() + + tape.backward(loss=tr4) + vgrads = tape.gradients[v4].numpy()[0] + assert_np_equal(vgrads, 2.0 * np.eye(4), tol=10 * tol) + tape.zero() + + tape.backward(loss=tr5) + vgrads = tape.gradients[v5].numpy()[0] + assert_np_equal(vgrads, 2.0 * np.eye(5), tol=10 * tol) + tape.zero() + + +def test_diag(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec5 = wp.types.vector(length=5, dtype=wptype) + + output_select_kernel = get_select_kernel(wptype) + + def check_mat_diag( + s5: wp.array(dtype=vec5), + outcomponents: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + m55result = wptype(2) * wp.diag(s5[0]) + + idx = 0 + for i in range(5): + for j in range(5): + outcomponents[idx] = m55result[i, j] + idx = idx + 1 + + kernel = getkernel(check_mat_diag, suffix=dtype.__name__) + + if register_kernels: + return + + s5 = wp.array(randvals(rng, [1, 5], dtype), dtype=vec5, requires_grad=True, device=device) + outcomponents = wp.zeros(5 * 5, dtype=wptype, requires_grad=True, device=device) + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + + wp.launch(kernel, dim=1, inputs=[s5], outputs=[outcomponents], device=device) + + assert_np_equal(outcomponents.numpy(), 2 * np.diag(s5.numpy()[0]), tol=tol) + + if dtype in np_float_types: + idx = 0 + for i in range(5): + for j in range(5): + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[s5], outputs=[outcomponents], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[outcomponents, idx], outputs=[out], device=device) + tape.backward(loss=out) + expectedresult = np.zeros(5, dtype=dtype) + if i == j: + expectedresult[i] = 2 + assert_np_equal(tape.gradients[s5].numpy()[0], expectedresult, tol=10 * tol) + tape.zero() + + idx = idx + 1 + + +def test_equivalent_types(test, device, dtype, register_kernels=False): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + # matrix types + mat22 = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33 = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44 = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55 = wp.types.matrix(shape=(5, 5), dtype=wptype) + + # matrix types equivalent to the above + mat22_equiv = wp.types.matrix(shape=(2, 2), dtype=wptype) + mat33_equiv = wp.types.matrix(shape=(3, 3), dtype=wptype) + mat44_equiv = wp.types.matrix(shape=(4, 4), dtype=wptype) + mat55_equiv = wp.types.matrix(shape=(5, 5), dtype=wptype) + + # declare kernel with original types + def check_equivalence( + m2: mat22, + m3: mat33, + m4: mat44, + m5: mat55, + ): + wp.expect_eq(m2, mat22(wptype(42))) + wp.expect_eq(m3, mat33(wptype(43))) + wp.expect_eq(m4, mat44(wptype(44))) + wp.expect_eq(m5, mat55(wptype(45))) + + wp.expect_eq(m2, mat22_equiv(wptype(42))) + wp.expect_eq(m3, mat33_equiv(wptype(43))) + wp.expect_eq(m4, mat44_equiv(wptype(44))) + wp.expect_eq(m5, mat55_equiv(wptype(45))) + + kernel = getkernel(check_equivalence, suffix=dtype.__name__) + + if register_kernels: + return + + # call kernel with equivalent types + m2 = mat22_equiv(42) + m3 = mat33_equiv(43) + m4 = mat44_equiv(44) + m5 = mat55_equiv(45) + + wp.launch(kernel, dim=1, inputs=[m2, m3, m4, m5], device=device) + + +def test_conversions(test, device, dtype, register_kernels=False): + def check_matrices_equal( + m0: wp.mat22, + m1: wp.mat22, + m2: wp.mat22, + m3: wp.mat22, + m4: wp.mat22, + m5: wp.mat22, + m6: wp.mat22, + ): + wp.expect_eq(m1, m0) + wp.expect_eq(m2, m0) + wp.expect_eq(m3, m0) + wp.expect_eq(m4, m0) + wp.expect_eq(m5, m0) + wp.expect_eq(m6, m0) + + kernel = getkernel(check_matrices_equal, suffix=dtype.__name__) + + if register_kernels: + return + + m0 = wp.mat22(1, 2, 3, 4) + + # test explicit conversions - constructing matrices from different containers + m1 = wp.mat22(((1, 2), (3, 4))) # nested tuples + m2 = wp.mat22([[1, 2], [3, 4]]) # nested lists + m3 = wp.mat22(np.array([[1, 2], [3, 4]], dtype=dtype)) # 2d array + m4 = wp.mat22((1, 2, 3, 4)) # flat tuple + m5 = wp.mat22([1, 2, 3, 4]) # flat list + m6 = wp.mat22(np.array([1, 2, 3, 4], dtype=dtype)) # 1d array + + wp.launch(kernel, dim=1, inputs=[m0, m1, m2, m3, m4, m5, m6], device=device) + + # test implicit conversions - passing different containers as matrices to wp.launch() + m1 = ((1, 2), (3, 4)) # nested tuples + m2 = [[1, 2], [3, 4]] # nested lists + m3 = np.array([[1, 2], [3, 4]], dtype=dtype) # 2d array + m4 = (1, 2, 3, 4) # flat tuple + m5 = [1, 2, 3, 4] # flat list + m6 = np.array([1, 2, 3, 4], dtype=dtype) # 1d array + + wp.launch(kernel, dim=1, inputs=[m0, m1, m2, m3, m4, m5, m6], device=device) + + +devices = get_test_devices() + + +class TestMatScalarOps(unittest.TestCase): + pass + + +for dtype in np_scalar_types: + add_function_test(TestMatScalarOps, f"test_arrays_{dtype.__name__}", test_arrays, devices=devices, dtype=dtype) + add_function_test(TestMatScalarOps, f"test_components_{dtype.__name__}", test_components, devices=None, dtype=dtype) + add_function_test_register_kernel( + TestMatScalarOps, f"test_constructors_{dtype.__name__}", test_constructors, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, + f"test_anon_type_instance_{dtype.__name__}", + test_anon_type_instance, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_identity_{dtype.__name__}", test_identity, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_indexing_{dtype.__name__}", test_indexing, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_equality_{dtype.__name__}", test_equality, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, + f"test_scalar_multiplication_{dtype.__name__}", + test_scalar_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestMatScalarOps, + f"test_matvec_multiplication_{dtype.__name__}", + test_matvec_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestMatScalarOps, + f"test_vecmat_multiplication_{dtype.__name__}", + test_vecmat_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestMatScalarOps, + f"test_matmat_multiplication_{dtype.__name__}", + test_matmat_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestMatScalarOps, + f"test_cw_multiplication_{dtype.__name__}", + test_cw_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_cw_division_{dtype.__name__}", test_cw_division, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_outer_product_{dtype.__name__}", test_outer_product, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_transpose_{dtype.__name__}", test_transpose, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_scalar_division_{dtype.__name__}", test_scalar_division, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_addition_{dtype.__name__}", test_addition, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_ddot_{dtype.__name__}", test_ddot, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_trace_{dtype.__name__}", test_trace, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_diag_{dtype.__name__}", test_diag, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_get_diag_{dtype.__name__}", test_diag, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_equivalent_types_{dtype.__name__}", test_equivalent_types, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_conversions_{dtype.__name__}", test_conversions, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestMatScalarOps, f"test_constants_{dtype.__name__}", test_constants, devices=devices, dtype=dtype + ) + + +if __name__ == "__main__": + wp.build.clear_kernel_cache() + unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_math.py b/warp/tests/test_math.py index 018dde5f5..84f896c32 100644 --- a/warp/tests/test_math.py +++ b/warp/tests/test_math.py @@ -5,13 +5,13 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -from typing import NamedTuple import unittest +from typing import NamedTuple import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -176,19 +176,18 @@ def test_mat_type(test, device): raise ValueError("mat to string error") -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + + +class TestMath(unittest.TestCase): + pass - class TestMath(parent): - pass - add_function_test(TestMath, "test_scalar_math", test_scalar_math, devices=devices) - add_function_test(TestMath, "test_vec_type", test_vec_type, devices=devices) - add_function_test(TestMath, "test_mat_type", test_mat_type, devices=devices) - return TestMath +add_function_test(TestMath, "test_scalar_math", test_scalar_math, devices=devices) +add_function_test(TestMath, "test_vec_type", test_vec_type, devices=devices) +add_function_test(TestMath, "test_mat_type", test_mat_type, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_matmul.py b/warp/tests/test_matmul.py index 225770b12..1a4bb4cdc 100644 --- a/warp/tests/test_matmul.py +++ b/warp/tests/test_matmul.py @@ -1,11 +1,21 @@ -import numpy as np +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest +import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() +from warp.context import runtime # noqa: E402 + class gemm_test_bed_runner: def __init__(self, dtype, device): @@ -21,63 +31,54 @@ def alloc(self, m, n, k, batch_count): np.ceil(rng.uniform(low=low, high=high, size=(m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(m, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) - D = wp.array2d( - np.zeros((m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True) + D = wp.array2d(np.zeros((m, n)), dtype=self.dtype, device=self.device, requires_grad=True) else: A = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), dtype=self.dtype, device=self.device, - requires_grad=True - ) - D = wp.array3d( - np.zeros((batch_count, m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True + requires_grad=True, ) + D = wp.array3d(np.zeros((batch_count, m, n)), dtype=self.dtype, device=self.device, requires_grad=True) return A, B, C, D def run_and_verify(self, m, n, k, batch_count, alpha, beta): A, B, C, D = self.alloc(m, n, k, batch_count) ones = wp.zeros_like(D) ones.fill_(1.0) - + if batch_count == 1: tape = wp.Tape() with tape: wp.matmul(A, B, C, D, alpha, beta, False, self.device) - tape.backward(grads={D : ones}) - + tape.backward(grads={D: ones}) + D_np = alpha * (A.numpy() @ B.numpy()) + beta * C.numpy() assert np.array_equal(D_np, D.numpy()) @@ -89,8 +90,8 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): tape = wp.Tape() with tape: wp.batched_matmul(A, B, C, D, alpha, beta, False, self.device) - tape.backward(grads={D : ones}) - + tape.backward(grads={D: ones}) + D_np = alpha * np.matmul(A.numpy(), B.numpy()) + beta * C.numpy() assert np.array_equal(D_np, D.numpy()) @@ -132,75 +133,45 @@ def alloc(self, m, n, k, batch_count): np.ceil(rng.uniform(low=low, high=high, size=(m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(m, n))), dtype=self.dtype, device=self.device, - requires_grad=True - ) - D = wp.array2d( - np.zeros((m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - AT = wp.array2d( - A.numpy().transpose([1, 0]), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - BT = wp.array2d( - B.numpy().transpose([1, 0]), - dtype=self.dtype, - device=self.device, - requires_grad=True + requires_grad=True, ) + D = wp.array2d(np.zeros((m, n)), dtype=self.dtype, device=self.device, requires_grad=True) + AT = wp.array2d(A.numpy().transpose([1, 0]), dtype=self.dtype, device=self.device, requires_grad=True) + BT = wp.array2d(B.numpy().transpose([1, 0]), dtype=self.dtype, device=self.device, requires_grad=True) else: A = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), dtype=self.dtype, device=self.device, - requires_grad=True - ) - D = wp.array3d( - np.zeros((batch_count, m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - AT = wp.array3d( - A.numpy().transpose([0, 2, 1]), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - BT = wp.array3d( - B.numpy().transpose([0, 2, 1]), - dtype=self.dtype, - device=self.device, - requires_grad=True + requires_grad=True, ) + D = wp.array3d(np.zeros((batch_count, m, n)), dtype=self.dtype, device=self.device, requires_grad=True) + AT = wp.array3d(A.numpy().transpose([0, 2, 1]), dtype=self.dtype, device=self.device, requires_grad=True) + BT = wp.array3d(B.numpy().transpose([0, 2, 1]), dtype=self.dtype, device=self.device, requires_grad=True) return A, B, C, D, AT, BT def run_and_verify(self, m, n, k, batch_count, alpha, beta): @@ -219,17 +190,17 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): ones3.fill_(1.0) if batch_count == 1: - ATT1 = AT1.transpose([1, 0]) + ATT1 = AT1.transpose([1, 0]) BTT1 = BT1.transpose([1, 0]) - ATT2 = AT2.transpose([1, 0]) + ATT2 = AT2.transpose([1, 0]) BTT2 = BT2.transpose([1, 0]) tape = wp.Tape() with tape: wp.matmul(A, BTT1, C1, D1, alpha, beta, False, self.device) wp.matmul(ATT1, B, C2, D2, alpha, beta, False, self.device) wp.matmul(ATT2, BTT2, C3, D3, alpha, beta, False, self.device) - tape.backward(grads={D1 : ones1, D2 : ones2, D3 : ones3}) - + tape.backward(grads={D1: ones1, D2: ones2, D3: ones3}) + D_np = alpha * (A.numpy() @ B.numpy()) + beta * C1.numpy() assert np.array_equal(D_np, D1.numpy()) assert np.array_equal(D_np, D2.numpy()) @@ -240,7 +211,7 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): adj_C_np = beta * ones1.numpy() else: - ATT1 = AT1.transpose([0, 2, 1]) + ATT1 = AT1.transpose([0, 2, 1]) BTT1 = BT1.transpose([0, 2, 1]) ATT2 = AT2.transpose([0, 2, 1]) BTT2 = BT2.transpose([0, 2, 1]) @@ -249,8 +220,8 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): wp.batched_matmul(A, BTT1, C1, D1, alpha, beta, False, self.device) wp.batched_matmul(ATT1, B, C2, D2, alpha, beta, False, self.device) wp.batched_matmul(ATT2, BTT2, C3, D3, alpha, beta, False, self.device) - tape.backward(grads={D1 : ones1, D2 : ones2, D3 : ones3}) - + tape.backward(grads={D1: ones1, D2: ones2, D3: ones3}) + D_np = alpha * np.matmul(A.numpy(), B.numpy()) + beta * C1.numpy() assert np.array_equal(D_np, D1.numpy()) assert np.array_equal(D_np, D2.numpy()) @@ -288,11 +259,13 @@ def test_f16(test, device): gemm_test_bed_runner_transpose(wp.float16, device).run() +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_f32(test, device): gemm_test_bed_runner(wp.float32, device).run() gemm_test_bed_runner_transpose(wp.float32, device).run() +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_f64(test, device): gemm_test_bed_runner(wp.float64, device).run() gemm_test_bed_runner_transpose(wp.float64, device).run() @@ -304,6 +277,7 @@ def matrix_sum_kernel(arr: wp.array2d(dtype=float), loss: wp.array(dtype=float)) wp.atomic_add(loss, 0, arr[i, j]) +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_tape(test, device): rng = np.random.default_rng(42) low = -4.5 @@ -343,6 +317,7 @@ def test_tape(test, device): assert_array_equal(A.grad, wp.zeros_like(A)) +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_operator(test, device): rng = np.random.default_rng(42) low = -4.5 @@ -378,6 +353,7 @@ def test_operator(test, device): assert_array_equal(A.grad, wp.zeros_like(A)) +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_large_batch_count(test, device): rng = np.random.default_rng(42) low = -4.5 @@ -387,31 +363,38 @@ def test_large_batch_count(test, device): k = 4 batch_count = 65535 * 2 + int(65535 / 2) A = wp.array3d( - np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), dtype=float, device=device, requires_grad=True + np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), + dtype=float, + device=device, + requires_grad=True, ) B = wp.array3d( - np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), dtype=float, device=device, requires_grad=True + np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), + dtype=float, + device=device, + requires_grad=True, ) C = wp.array3d( - np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), dtype=float, device=device, requires_grad=True - ) - D = wp.array3d( - np.zeros((batch_count, m, n)), dtype=float, device=device, requires_grad=True + np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), + dtype=float, + device=device, + requires_grad=True, ) + D = wp.array3d(np.zeros((batch_count, m, n)), dtype=float, device=device, requires_grad=True) ones = wp.zeros_like(D) ones.fill_(1.0) alpha = 1.0 beta = 1.0 - + tape = wp.Tape() with tape: wp.batched_matmul(A, B, C, D, alpha=alpha, beta=beta, allow_tf32x3_arith=False, device=device) - tape.backward(grads={D : ones}) + tape.backward(grads={D: ones}) D_np = alpha * np.matmul(A.numpy(), B.numpy()) + beta * C.numpy() assert np.array_equal(D_np, D.numpy()) - + adj_A_np = alpha * np.matmul(ones.numpy(), B.numpy().transpose((0, 2, 1))) adj_B_np = alpha * np.matmul(A.numpy().transpose((0, 2, 1)), ones.numpy()) adj_C_np = beta * ones.numpy() @@ -449,31 +432,22 @@ def test_adjoint_accumulation(test, device): assert np.array_equal(c_wp.grad.numpy(), np.ones(shape=(2,2))) -def register(parent): - devices = [d for d in get_test_devices()] +devices = get_test_devices() - class TestMatmul(parent): - pass - if devices: - # check if CUTLASS is available - from warp.context import runtime +class TestMatmul(unittest.TestCase): + pass - if runtime.core.is_cutlass_enabled(): - # add_function_test(TestMatmul, "test_f16", test_f16, devices=devices) - add_function_test(TestMatmul, "test_f32", test_f32, devices=devices) - add_function_test(TestMatmul, "test_f64", test_f64, devices=devices) - add_function_test(TestMatmul, "test_tape", test_tape, devices=devices) - add_function_test(TestMatmul, "test_operator", test_operator, devices=devices) - add_function_test(TestMatmul, "test_large_batch_count", test_large_batch_count, devices=devices) - add_function_test(TestMatmul, "test_adjoint_accumulation", test_adjoint_accumulation, devices=devices) - else: - print("Skipping matmul tests because CUTLASS is not supported in this build") - return TestMatmul +# add_function_test(TestMatmul, "test_f16", test_f16, devices=devices) +add_function_test(TestMatmul, "test_f32", test_f32, devices=devices) +add_function_test(TestMatmul, "test_f64", test_f64, devices=devices) +add_function_test(TestMatmul, "test_tape", test_tape, devices=devices) +add_function_test(TestMatmul, "test_operator", test_operator, devices=devices) +add_function_test(TestMatmul, "test_large_batch_count", test_large_batch_count, devices=devices) +add_function_test(TestMatmul, "test_adjoint_accumulation", test_adjoint_accumulation, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_matmul_lite.py b/warp/tests/test_matmul_lite.py index 55e995af5..d3e00d5a8 100644 --- a/warp/tests/test_matmul_lite.py +++ b/warp/tests/test_matmul_lite.py @@ -1,11 +1,21 @@ -import numpy as np +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest +import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() +from warp.context import runtime # noqa: E402 + class gemm_test_bed_runner: def __init__(self, dtype, device): @@ -21,63 +31,54 @@ def alloc(self, m, n, k, batch_count): np.ceil(rng.uniform(low=low, high=high, size=(m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(m, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) - D = wp.array2d( - np.zeros((m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True) + D = wp.array2d(np.zeros((m, n)), dtype=self.dtype, device=self.device, requires_grad=True) else: A = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), dtype=self.dtype, device=self.device, - requires_grad=True - ) - D = wp.array3d( - np.zeros((batch_count, m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True + requires_grad=True, ) + D = wp.array3d(np.zeros((batch_count, m, n)), dtype=self.dtype, device=self.device, requires_grad=True) return A, B, C, D def run_and_verify(self, m, n, k, batch_count, alpha, beta): A, B, C, D = self.alloc(m, n, k, batch_count) ones = wp.zeros_like(D) ones.fill_(1.0) - + if batch_count == 1: tape = wp.Tape() with tape: wp.matmul(A, B, C, D, alpha, beta, False, self.device) - tape.backward(grads={D : ones}) - + tape.backward(grads={D: ones}) + D_np = alpha * (A.numpy() @ B.numpy()) + beta * C.numpy() assert np.array_equal(D_np, D.numpy()) @@ -89,8 +90,8 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): tape = wp.Tape() with tape: wp.batched_matmul(A, B, C, D, alpha, beta, False, self.device) - tape.backward(grads={D : ones}) - + tape.backward(grads={D: ones}) + D_np = alpha * np.matmul(A.numpy(), B.numpy()) + beta * C.numpy() assert np.array_equal(D_np, D.numpy()) @@ -132,75 +133,45 @@ def alloc(self, m, n, k, batch_count): np.ceil(rng.uniform(low=low, high=high, size=(m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array2d( np.ceil(rng.uniform(low=low, high=high, size=(m, n))), dtype=self.dtype, device=self.device, - requires_grad=True - ) - D = wp.array2d( - np.zeros((m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - AT = wp.array2d( - A.numpy().transpose([1, 0]), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - BT = wp.array2d( - B.numpy().transpose([1, 0]), - dtype=self.dtype, - device=self.device, - requires_grad=True + requires_grad=True, ) + D = wp.array2d(np.zeros((m, n)), dtype=self.dtype, device=self.device, requires_grad=True) + AT = wp.array2d(A.numpy().transpose([1, 0]), dtype=self.dtype, device=self.device, requires_grad=True) + BT = wp.array2d(B.numpy().transpose([1, 0]), dtype=self.dtype, device=self.device, requires_grad=True) else: A = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) B = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), dtype=self.dtype, device=self.device, - requires_grad=True + requires_grad=True, ) C = wp.array3d( np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), dtype=self.dtype, device=self.device, - requires_grad=True - ) - D = wp.array3d( - np.zeros((batch_count, m, n)), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - AT = wp.array3d( - A.numpy().transpose([0, 2, 1]), - dtype=self.dtype, - device=self.device, - requires_grad=True - ) - BT = wp.array3d( - B.numpy().transpose([0, 2, 1]), - dtype=self.dtype, - device=self.device, - requires_grad=True + requires_grad=True, ) + D = wp.array3d(np.zeros((batch_count, m, n)), dtype=self.dtype, device=self.device, requires_grad=True) + AT = wp.array3d(A.numpy().transpose([0, 2, 1]), dtype=self.dtype, device=self.device, requires_grad=True) + BT = wp.array3d(B.numpy().transpose([0, 2, 1]), dtype=self.dtype, device=self.device, requires_grad=True) return A, B, C, D, AT, BT def run_and_verify(self, m, n, k, batch_count, alpha, beta): @@ -219,17 +190,17 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): ones3.fill_(1.0) if batch_count == 1: - ATT1 = AT1.transpose([1, 0]) + ATT1 = AT1.transpose([1, 0]) BTT1 = BT1.transpose([1, 0]) - ATT2 = AT2.transpose([1, 0]) + ATT2 = AT2.transpose([1, 0]) BTT2 = BT2.transpose([1, 0]) tape = wp.Tape() with tape: wp.matmul(A, BTT1, C1, D1, alpha, beta, False, self.device) wp.matmul(ATT1, B, C2, D2, alpha, beta, False, self.device) wp.matmul(ATT2, BTT2, C3, D3, alpha, beta, False, self.device) - tape.backward(grads={D1 : ones1, D2 : ones2, D3 : ones3}) - + tape.backward(grads={D1: ones1, D2: ones2, D3: ones3}) + D_np = alpha * (A.numpy() @ B.numpy()) + beta * C1.numpy() assert np.array_equal(D_np, D1.numpy()) assert np.array_equal(D_np, D2.numpy()) @@ -240,7 +211,7 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): adj_C_np = beta * ones1.numpy() else: - ATT1 = AT1.transpose([0, 2, 1]) + ATT1 = AT1.transpose([0, 2, 1]) BTT1 = BT1.transpose([0, 2, 1]) ATT2 = AT2.transpose([0, 2, 1]) BTT2 = BT2.transpose([0, 2, 1]) @@ -249,8 +220,8 @@ def run_and_verify(self, m, n, k, batch_count, alpha, beta): wp.batched_matmul(A, BTT1, C1, D1, alpha, beta, False, self.device) wp.batched_matmul(ATT1, B, C2, D2, alpha, beta, False, self.device) wp.batched_matmul(ATT2, BTT2, C3, D3, alpha, beta, False, self.device) - tape.backward(grads={D1 : ones1, D2 : ones2, D3 : ones3}) - + tape.backward(grads={D1: ones1, D2: ones2, D3: ones3}) + D_np = alpha * np.matmul(A.numpy(), B.numpy()) + beta * C1.numpy() assert np.array_equal(D_np, D1.numpy()) assert np.array_equal(D_np, D2.numpy()) @@ -282,6 +253,7 @@ def run(self): self.run_and_verify(m, n, k, batch_count, alpha, beta) +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_f32(test, device): gemm_test_bed_runner(wp.float32, device).run() gemm_test_bed_runner_transpose(wp.float32, device).run() @@ -293,6 +265,7 @@ def matrix_sum_kernel(arr: wp.array2d(dtype=float), loss: wp.array(dtype=float)) wp.atomic_add(loss, 0, arr[i, j]) +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_tape(test, device): rng = np.random.default_rng(42) low = -4.5 @@ -331,6 +304,7 @@ def test_tape(test, device): assert_array_equal(A.grad, wp.zeros_like(A)) +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_operator(test, device): rng = np.random.default_rng(42) low = -4.5 @@ -366,6 +340,7 @@ def test_operator(test, device): assert_array_equal(A.grad, wp.zeros_like(A)) +@unittest.skipUnless(runtime.core.is_cutlass_enabled(), "Warp was not built with CUTLASS support") def test_large_batch_count(test, device): rng = np.random.default_rng(42) low = -4.5 @@ -375,31 +350,38 @@ def test_large_batch_count(test, device): k = 4 batch_count = 65535 * 2 + int(65535 / 2) A = wp.array3d( - np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), dtype=float, device=device, requires_grad=True + np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, k))), + dtype=float, + device=device, + requires_grad=True, ) B = wp.array3d( - np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), dtype=float, device=device, requires_grad=True + np.ceil(rng.uniform(low=low, high=high, size=(batch_count, k, n))), + dtype=float, + device=device, + requires_grad=True, ) C = wp.array3d( - np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), dtype=float, device=device, requires_grad=True - ) - D = wp.array3d( - np.zeros((batch_count, m, n)), dtype=float, device=device, requires_grad=True + np.ceil(rng.uniform(low=low, high=high, size=(batch_count, m, n))), + dtype=float, + device=device, + requires_grad=True, ) + D = wp.array3d(np.zeros((batch_count, m, n)), dtype=float, device=device, requires_grad=True) ones = wp.zeros_like(D) ones.fill_(1.0) alpha = 1.0 beta = 1.0 - + tape = wp.Tape() with tape: wp.batched_matmul(A, B, C, D, alpha=alpha, beta=beta, allow_tf32x3_arith=False, device=device) - tape.backward(grads={D : ones}) + tape.backward(grads={D: ones}) D_np = alpha * np.matmul(A.numpy(), B.numpy()) + beta * C.numpy() assert np.array_equal(D_np, D.numpy()) - + adj_A_np = alpha * np.matmul(ones.numpy(), B.numpy().transpose((0, 2, 1))) adj_B_np = alpha * np.matmul(A.numpy().transpose((0, 2, 1)), ones.numpy()) adj_C_np = beta * ones.numpy() @@ -409,28 +391,19 @@ def test_large_batch_count(test, device): assert np.array_equal(adj_C_np, C.grad.numpy()) -def register(parent): - devices = [d for d in get_test_devices()] +devices = get_test_devices() - class TestMatmul(parent): - pass - if devices: - # check if CUTLASS is available - from warp.context import runtime +class TestMatmulLite(unittest.TestCase): + pass - if runtime.core.is_cutlass_enabled(): - add_function_test(TestMatmul, "test_f32", test_f32, devices=devices) - add_function_test(TestMatmul, "test_tape", test_tape, devices=devices) - add_function_test(TestMatmul, "test_operator", test_operator, devices=devices) - add_function_test(TestMatmul, "test_large_batch_count", test_large_batch_count, devices=devices) - else: - print("Skipping matmul tests because CUTLASS is not supported in this build") - return TestMatmul +add_function_test(TestMatmulLite, "test_f32", test_f32, devices=devices) +add_function_test(TestMatmulLite, "test_tape", test_tape, devices=devices) +add_function_test(TestMatmulLite, "test_operator", test_operator, devices=devices) +add_function_test(TestMatmulLite, "test_large_batch_count", test_large_batch_count, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_mesh.py b/warp/tests/test_mesh.py index fc08f7eec..c586072ee 100644 --- a/warp/tests/test_mesh.py +++ b/warp/tests/test_mesh.py @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * # fmt: off @@ -222,9 +222,9 @@ def query_ray_kernel( def test_mesh_query_ray(test, device): - points = wp.array(POINT_POSITIONS, dtype=wp.vec3) + points = wp.array(POINT_POSITIONS, dtype=wp.vec3, device=device) - indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int) + indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int, device=device) mesh = wp.Mesh(points=points, indices=indices) expected_sign = -1.0 wp.launch( @@ -234,9 +234,10 @@ def test_mesh_query_ray(test, device): mesh.id, expected_sign, ], + device=device, ) - indices = wp.array(LEFT_HANDED_FACE_VERTEX_INDICES, dtype=int) + indices = wp.array(LEFT_HANDED_FACE_VERTEX_INDICES, dtype=int, device=device) mesh = wp.Mesh(points=points, indices=indices) expected_sign = 1.0 wp.launch( @@ -246,76 +247,78 @@ def test_mesh_query_ray(test, device): mesh.id, expected_sign, ], + device=device, ) def test_mesh_refit_graph(test, device): - points = wp.array(POINT_POSITIONS, dtype=wp.vec3) + points = wp.array(POINT_POSITIONS, dtype=wp.vec3, device=device) - indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int) + indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int, device=device) mesh = wp.Mesh(points=points, indices=indices) - wp.capture_begin() - - mesh.refit() - - graph = wp.capture_end() + wp.capture_begin(device, force_module_load=False) + try: + mesh.refit() + finally: + graph = wp.capture_end(device) # replay num_iters = 10 for _ in range(num_iters): wp.capture_launch(graph) + wp.synchronize_device(device) + def test_mesh_exceptions(test, device): # points and indices must be on same device with test.assertRaises(RuntimeError): points = wp.array(POINT_POSITIONS, dtype=wp.vec3, device="cpu") - indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int) + indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int, device=device) wp.Mesh(points=points, indices=indices) # points must be vec3 with test.assertRaises(RuntimeError): - points = wp.array(POINT_POSITIONS, dtype=wp.vec3d) - indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int) + points = wp.array(POINT_POSITIONS, dtype=wp.vec3d, device=device) + indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int, device=device) wp.Mesh(points=points, indices=indices) # velocities must be vec3 with test.assertRaises(RuntimeError): - points = wp.array(POINT_POSITIONS, dtype=wp.vec3) - velocities = wp.zeros(points.shape, dtype=wp.vec3d) - indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int) + points = wp.array(POINT_POSITIONS, dtype=wp.vec3, device=device) + velocities = wp.zeros(points.shape, dtype=wp.vec3d, device=device) + indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int, device=device) wp.Mesh(points=points, indices=indices, velocities=velocities) # indices must be int32 with test.assertRaises(RuntimeError): - points = wp.array(POINT_POSITIONS, dtype=wp.vec3) - indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=wp.int64) + points = wp.array(POINT_POSITIONS, dtype=wp.vec3, device=device) + indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=wp.int64, device=device) wp.Mesh(points=points, indices=indices) # indices must be 1d with test.assertRaises(RuntimeError): - points = wp.array(POINT_POSITIONS, dtype=wp.vec3) - indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int) + points = wp.array(POINT_POSITIONS, dtype=wp.vec3, device=device) + indices = wp.array(RIGHT_HANDED_FACE_VERTEX_INDICES, dtype=int, device=device) indices = indices.reshape((3, -1)) wp.Mesh(points=points, indices=indices) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + + +class TestMesh(unittest.TestCase): + pass - class TestMesh(parent): - pass - add_function_test(TestMesh, "test_mesh_read_properties", test_mesh_read_properties, devices=devices) - add_function_test(TestMesh, "test_mesh_query_point", test_mesh_query_point, devices=devices) - add_function_test(TestMesh, "test_mesh_query_ray", test_mesh_query_ray, devices=devices) - add_function_test(TestMesh, "test_mesh_refit_graph", test_mesh_refit_graph, devices=wp.get_cuda_devices()) - add_function_test(TestMesh, "test_mesh_exceptions", test_mesh_exceptions, devices=wp.get_cuda_devices()) - return TestMesh +add_function_test(TestMesh, "test_mesh_read_properties", test_mesh_read_properties, devices=devices) +add_function_test(TestMesh, "test_mesh_query_point", test_mesh_query_point, devices=devices) +add_function_test(TestMesh, "test_mesh_query_ray", test_mesh_query_ray, devices=devices) +add_function_test(TestMesh, "test_mesh_refit_graph", test_mesh_refit_graph, devices=get_unique_cuda_test_devices()) +add_function_test(TestMesh, "test_mesh_exceptions", test_mesh_exceptions, devices=get_unique_cuda_test_devices()) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_mesh_query_aabb.py b/warp/tests/test_mesh_query_aabb.py index 3536e9c6b..9feeb21d2 100644 --- a/warp/tests/test_mesh_query_aabb.py +++ b/warp/tests/test_mesh_query_aabb.py @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -98,7 +98,6 @@ def test_compute_bounds(test, device): lower_view = lowers.numpy() upper_view = uppers.numpy() - wp.synchronize() # Confirm the bounds of each triangle are correct. test.assertTrue(lower_view[0][0] == 0) @@ -150,8 +149,6 @@ def test_mesh_query_aabb_count_overlap(test, device): device=device, ) - wp.synchronize() - view = counts.numpy() # 2 triangles that share a vertex having overlapping AABBs. @@ -190,8 +187,6 @@ def test_mesh_query_aabb_count_nonoverlap(test, device): device=device, ) - wp.synchronize() - view = counts.numpy() # AABB query only returns one triangle at a time, the triangles are not close enough to overlap. @@ -199,30 +194,28 @@ def test_mesh_query_aabb_count_nonoverlap(test, device): test.assertTrue(c == 1) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestMeshQueryAABBMethods(parent): - pass - add_function_test(TestMeshQueryAABBMethods, "test_compute_bounds", test_compute_bounds, devices=devices) - add_function_test( - TestMeshQueryAABBMethods, - "test_mesh_query_aabb_count_overlap", - test_mesh_query_aabb_count_overlap, - devices=devices, - ) - add_function_test( - TestMeshQueryAABBMethods, - "test_mesh_query_aabb_count_nonoverlap", - test_mesh_query_aabb_count_nonoverlap, - devices=devices, - ) +class TestMeshQueryAABBMethods(unittest.TestCase): + pass + - return TestMeshQueryAABBMethods +add_function_test(TestMeshQueryAABBMethods, "test_compute_bounds", test_compute_bounds, devices=devices) +add_function_test( + TestMeshQueryAABBMethods, + "test_mesh_query_aabb_count_overlap", + test_mesh_query_aabb_count_overlap, + devices=devices, +) +add_function_test( + TestMeshQueryAABBMethods, + "test_mesh_query_aabb_count_nonoverlap", + test_mesh_query_aabb_count_nonoverlap, + devices=devices, +) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_mesh_query_point.py b/warp/tests/test_mesh_query_point.py index 9650287ed..21bd85fb3 100644 --- a/warp/tests/test_mesh_query_point.py +++ b/warp/tests/test_mesh_query_point.py @@ -5,14 +5,13 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. +import math import unittest import numpy as np -import math import warp as wp -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() @@ -288,6 +287,7 @@ def triangulate(face_counts, face_indices): return tri_indices +@unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") def test_mesh_query_point(test, device): from pxr import Usd, UsdGeom @@ -503,6 +503,7 @@ def mesh_query_point_loss( loss[tid] = dist +@unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") def test_adj_mesh_query_point(test, device): from pxr import Usd, UsdGeom @@ -621,6 +622,7 @@ def sample_furthest_points_brute( query_result[tid] = max_dist_sq +@unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") def test_mesh_query_furthest_point(test, device): from pxr import Usd, UsdGeom @@ -654,32 +656,18 @@ def test_mesh_query_furthest_point(test, device): assert_np_equal(dist_query.numpy(), dist_brute.numpy(), tol=1.0e-3) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestMeshQuery(parent): - pass - # USD import failures should not count as a test failure - try: - from pxr import Usd, UsdGeom +class TestMeshQueryPoint(unittest.TestCase): + pass - have_usd = True - except: - have_usd = False - if have_usd: - add_function_test(TestMeshQuery, "test_mesh_query_point", test_mesh_query_point, devices=devices) - add_function_test( - TestMeshQuery, "test_mesh_query_furthest_point", test_mesh_query_furthest_point, devices=devices - ) - add_function_test(TestMeshQuery, "test_adj_mesh_query_point", test_adj_mesh_query_point, devices=devices) - - return TestMeshQuery +add_function_test(TestMeshQueryPoint, "test_mesh_query_point", test_mesh_query_point, devices=devices) +add_function_test(TestMeshQueryPoint, "test_mesh_query_furthest_point", test_mesh_query_furthest_point, devices=devices) +add_function_test(TestMeshQueryPoint, "test_adj_mesh_query_point", test_adj_mesh_query_point, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) - unittest.main(verbosity=2) diff --git a/warp/tests/test_mesh_query_ray.py b/warp/tests/test_mesh_query_ray.py index 029204678..12d547d61 100644 --- a/warp/tests/test_mesh_query_ray.py +++ b/warp/tests/test_mesh_query_ray.py @@ -10,8 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() @@ -66,8 +65,9 @@ def mesh_query_ray_loss( loss[tid] = l +@unittest.skipUnless(USD_AVAILABLE, "Requires usd-core") def test_mesh_query_ray_grad(test, device): - from pxr import Usd, UsdGeom, Gf, Sdf + from pxr import Usd, UsdGeom # test tri # print("Testing Single Triangle") @@ -209,7 +209,7 @@ def raycast_kernel( sign = float(0.0) # hit face sign n = wp.vec3() # hit face normal f = int(0) # hit face index - max_dist = 1e6 # max raycast disance + max_dist = 1e6 # max raycast distance # ray cast against the mesh tid = wp.tid() @@ -258,29 +258,17 @@ def test_mesh_query_ray_edge(test, device): test.assertEqual(counts.numpy()[0], n) -def register(parent): - devices = get_test_devices() - - class TestMeshQueryRay(parent): - pass - - add_function_test(TestMeshQueryRay, "test_mesh_query_ray_edge", test_mesh_query_ray_edge, devices=devices) +devices = get_test_devices() - # USD import failures should not count as a test failure - try: - from pxr import Usd, UsdGeom - have_usd = True - except: - have_usd = False +class TestMeshQueryRay(unittest.TestCase): + pass - if have_usd: - add_function_test(TestMeshQueryRay, "test_mesh_query_ray_grad", test_mesh_query_ray_grad, devices=devices) - return TestMeshQueryRay +add_function_test(TestMeshQueryRay, "test_mesh_query_ray_edge", test_mesh_query_ray_edge, devices=devices) +add_function_test(TestMeshQueryRay, "test_mesh_query_ray_grad", test_mesh_query_ray_grad, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_mlp.py b/warp/tests/test_mlp.py index ef241cc3e..2af60f470 100644 --- a/warp/tests/test_mlp.py +++ b/warp/tests/test_mlp.py @@ -8,8 +8,9 @@ import unittest import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -259,19 +260,17 @@ def profile_mlp_warp(device): # profile_mlp_torch("cuda") -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestMLP(parent): - pass +class TestMLP(unittest.TestCase): + pass - add_function_test(TestMLP, "test_mlp", test_mlp, devices=devices) - add_function_test(TestMLP, "test_mlp_grad", test_mlp_grad, devices=devices) - return TestMLP +add_function_test(TestMLP, "test_mlp", test_mlp, devices=devices) +add_function_test(TestMLP, "test_mlp_grad", test_mlp_grad, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_model.py b/warp/tests/test_model.py index f88e96657..b5caeb547 100644 --- a/warp/tests/test_model.py +++ b/warp/tests/test_model.py @@ -7,108 +7,104 @@ import unittest +import numpy as np + import warp as wp -from warp.tests.test_base import * from warp.sim import ModelBuilder - -import numpy as np +from warp.tests.unittest_utils import * wp.init() -def register(parent): - class TestModel(parent): - def test_add_triangles(self): - rng = np.random.default_rng(123) - - pts = np.array( - [ - [-0.00585869, 0.34189449, -1.17415233], - [-1.894547, 0.1788074, 0.9251329], - [-1.26141048, 0.16140787, 0.08823282], - [-0.08609255, -0.82722546, 0.65995427], - [0.78827592, -1.77375711, -0.55582718], - ] - ) - tris = np.array([[0, 3, 4], [0, 2, 3], [2, 1, 3], [1, 4, 3]]) - - builder1 = ModelBuilder() - builder2 = ModelBuilder() - for pt in pts: - builder1.add_particle(wp.vec3(pt), wp.vec3(), 1.0) - builder2.add_particle(wp.vec3(pt), wp.vec3(), 1.0) - - # test add_triangle(s) with default arguments: - areas = builder2.add_triangles(tris[:, 0], tris[:, 1], tris[:, 2]) - for i, t in enumerate(tris): - area = builder1.add_triangle(t[0], t[1], t[2]) - self.assertAlmostEqual(area, areas[i], places=6) - - # test add_triangle(s) with non default arguments: - tri_ke = rng.standard_normal(size=pts.shape[0]) - tri_ka = rng.standard_normal(size=pts.shape[0]) - tri_kd = rng.standard_normal(size=pts.shape[0]) - tri_drag = rng.standard_normal(size=pts.shape[0]) - tri_lift = rng.standard_normal(size=pts.shape[0]) - for i, t in enumerate(tris): - builder1.add_triangle( - t[0], - t[1], - t[2], - tri_ke[i], - tri_ka[i], - tri_kd[i], - tri_drag[i], - tri_lift[i], - ) - builder2.add_triangles(tris[:, 0], tris[:, 1], tris[:, 2], tri_ke, tri_ka, tri_kd, tri_drag, tri_lift) - - assert_np_equal(np.array(builder1.tri_indices), np.array(builder2.tri_indices)) - assert_np_equal(np.array(builder1.tri_poses), np.array(builder2.tri_poses), tol=1.0e-6) - assert_np_equal(np.array(builder1.tri_activations), np.array(builder2.tri_activations)) - assert_np_equal(np.array(builder1.tri_materials), np.array(builder2.tri_materials)) - - def test_add_edges(self): - rng = np.random.default_rng(123) - - pts = np.array( - [ - [-0.00585869, 0.34189449, -1.17415233], - [-1.894547, 0.1788074, 0.9251329], - [-1.26141048, 0.16140787, 0.08823282], - [-0.08609255, -0.82722546, 0.65995427], - [0.78827592, -1.77375711, -0.55582718], - ] +class TestModel(unittest.TestCase): + def test_add_triangles(self): + rng = np.random.default_rng(123) + + pts = np.array( + [ + [-0.00585869, 0.34189449, -1.17415233], + [-1.894547, 0.1788074, 0.9251329], + [-1.26141048, 0.16140787, 0.08823282], + [-0.08609255, -0.82722546, 0.65995427], + [0.78827592, -1.77375711, -0.55582718], + ] + ) + tris = np.array([[0, 3, 4], [0, 2, 3], [2, 1, 3], [1, 4, 3]]) + + builder1 = ModelBuilder() + builder2 = ModelBuilder() + for pt in pts: + builder1.add_particle(wp.vec3(pt), wp.vec3(), 1.0) + builder2.add_particle(wp.vec3(pt), wp.vec3(), 1.0) + + # test add_triangle(s) with default arguments: + areas = builder2.add_triangles(tris[:, 0], tris[:, 1], tris[:, 2]) + for i, t in enumerate(tris): + area = builder1.add_triangle(t[0], t[1], t[2]) + self.assertAlmostEqual(area, areas[i], places=6) + + # test add_triangle(s) with non default arguments: + tri_ke = rng.standard_normal(size=pts.shape[0]) + tri_ka = rng.standard_normal(size=pts.shape[0]) + tri_kd = rng.standard_normal(size=pts.shape[0]) + tri_drag = rng.standard_normal(size=pts.shape[0]) + tri_lift = rng.standard_normal(size=pts.shape[0]) + for i, t in enumerate(tris): + builder1.add_triangle( + t[0], + t[1], + t[2], + tri_ke[i], + tri_ka[i], + tri_kd[i], + tri_drag[i], + tri_lift[i], ) - edges = np.array([[0, 4, 3, 1], [3, 2, 4, 1]]) - - builder1 = ModelBuilder() - builder2 = ModelBuilder() - for pt in pts: - builder1.add_particle(wp.vec3(pt), wp.vec3(), 1.0) - builder2.add_particle(wp.vec3(pt), wp.vec3(), 1.0) - - # test defaults: - for i in range(2): - builder1.add_edge(edges[i, 0], edges[i, 1], edges[i, 2], edges[i, 3]) - builder2.add_edges(edges[:, 0], edges[:, 1], edges[:, 2], edges[:, 3]) - - # test non defaults: - rest = rng.standard_normal(size=2) - edge_ke = rng.standard_normal(size=2) - edge_kd = rng.standard_normal(size=2) - for i in range(2): - builder1.add_edge(edges[i, 0], edges[i, 1], edges[i, 2], edges[i, 3], rest[i], edge_ke[i], edge_kd[i]) - builder2.add_edges(edges[:, 0], edges[:, 1], edges[:, 2], edges[:, 3], rest, edge_ke, edge_kd) - - assert_np_equal(np.array(builder1.edge_indices), np.array(builder2.edge_indices)) - assert_np_equal(np.array(builder1.edge_rest_angle), np.array(builder2.edge_rest_angle), tol=1.0e-4) - assert_np_equal(np.array(builder1.edge_bending_properties), np.array(builder2.edge_bending_properties)) - - return TestModel + builder2.add_triangles(tris[:, 0], tris[:, 1], tris[:, 2], tri_ke, tri_ka, tri_kd, tri_drag, tri_lift) + + assert_np_equal(np.array(builder1.tri_indices), np.array(builder2.tri_indices)) + assert_np_equal(np.array(builder1.tri_poses), np.array(builder2.tri_poses), tol=1.0e-6) + assert_np_equal(np.array(builder1.tri_activations), np.array(builder2.tri_activations)) + assert_np_equal(np.array(builder1.tri_materials), np.array(builder2.tri_materials)) + + def test_add_edges(self): + rng = np.random.default_rng(123) + + pts = np.array( + [ + [-0.00585869, 0.34189449, -1.17415233], + [-1.894547, 0.1788074, 0.9251329], + [-1.26141048, 0.16140787, 0.08823282], + [-0.08609255, -0.82722546, 0.65995427], + [0.78827592, -1.77375711, -0.55582718], + ] + ) + edges = np.array([[0, 4, 3, 1], [3, 2, 4, 1]]) + + builder1 = ModelBuilder() + builder2 = ModelBuilder() + for pt in pts: + builder1.add_particle(wp.vec3(pt), wp.vec3(), 1.0) + builder2.add_particle(wp.vec3(pt), wp.vec3(), 1.0) + + # test defaults: + for i in range(2): + builder1.add_edge(edges[i, 0], edges[i, 1], edges[i, 2], edges[i, 3]) + builder2.add_edges(edges[:, 0], edges[:, 1], edges[:, 2], edges[:, 3]) + + # test non defaults: + rest = rng.standard_normal(size=2) + edge_ke = rng.standard_normal(size=2) + edge_kd = rng.standard_normal(size=2) + for i in range(2): + builder1.add_edge(edges[i, 0], edges[i, 1], edges[i, 2], edges[i, 3], rest[i], edge_ke[i], edge_kd[i]) + builder2.add_edges(edges[:, 0], edges[:, 1], edges[:, 2], edges[:, 3], rest, edge_ke, edge_kd) + + assert_np_equal(np.array(builder1.edge_indices), np.array(builder2.edge_indices)) + assert_np_equal(np.array(builder1.edge_rest_angle), np.array(builder2.edge_rest_angle), tol=1.0e-4) + assert_np_equal(np.array(builder1.edge_bending_properties), np.array(builder2.edge_bending_properties)) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_modules_lite.py b/warp/tests/test_modules_lite.py index b35a2ae1f..b12983f11 100644 --- a/warp/tests/test_modules_lite.py +++ b/warp/tests/test_modules_lite.py @@ -8,42 +8,32 @@ import unittest import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() -def test_module_lite_load(test, device): - # Load current module - wp.load_module() +devices = get_test_devices() - # Load named module - wp.load_module(wp.config) - # Load named module (string) - wp.load_module(wp.config, recursive=True) +class TestModuleLite(unittest.TestCase): + def test_module_lite_load(self): + # Load current module + wp.load_module() + # Load named module + wp.load_module(wp.config) -def test_module_lite_options(test, device): - wp.set_module_options({"max_unroll": 8}) - module_options = wp.get_module_options() - test.assertIsInstance(module_options, dict) - test.assertEqual(module_options["max_unroll"], 8) + # Load named module (string) + wp.load_module(wp.config, recursive=True) - -def register(parent): - devices = get_test_devices() - - class TestModuleLite(parent): - pass - - add_function_test(TestModuleLite, "test_module_lite_load", test_module_lite_load, devices=devices) - add_function_test(TestModuleLite, "test_module_lite_get_options", test_module_lite_options, devices=devices) - - return TestModuleLite + def test_module_lite_options(self): + wp.set_module_options({"max_unroll": 8}) + module_options = wp.get_module_options() + self.assertIsInstance(module_options, dict) + self.assertEqual(module_options["max_unroll"], 8) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_multigpu.py b/warp/tests/test_multigpu.py index 42216f2bb..533cf35c1 100644 --- a/warp/tests/test_multigpu.py +++ b/warp/tests/test_multigpu.py @@ -5,16 +5,12 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import numpy as np -import warp as wp +import unittest -import math +import numpy as np import warp as wp -from warp.tests.test_base import * - -import unittest - +from warp.tests.unittest_utils import * wp.init() @@ -31,157 +27,134 @@ def arange(start: int, step: int, a: wp.array(dtype=int)): a[tid] = start + step * tid -def test_multigpu_set_device(test, device): - assert len(wp.get_cuda_devices()) > 1, "At least two CUDA devices are required" - - # save default device - saved_device = wp.get_device() - - n = 32 - - wp.set_device("cuda:0") - a0 = wp.empty(n, dtype=int) - wp.launch(arange, dim=a0.size, inputs=[0, 1, a0]) - - wp.set_device("cuda:1") - a1 = wp.empty(n, dtype=int) - wp.launch(arange, dim=a1.size, inputs=[0, 1, a1]) - - # restore default device - wp.set_device(saved_device) +class TestMultiGPU(unittest.TestCase): + @unittest.skipUnless(len(wp.get_cuda_devices()) > 1, "Requires at least two CUDA devices") + def test_multigpu_set_device(self): + # save default device + saved_device = wp.get_device() - assert a0.device == "cuda:0" - assert a1.device == "cuda:1" + n = 32 - expected = np.arange(n, dtype=int) - - assert_np_equal(a0.numpy(), expected) - assert_np_equal(a1.numpy(), expected) - - -def test_multigpu_scoped_device(test, device): - assert len(wp.get_cuda_devices()) > 1, "At least two CUDA devices are required" - - n = 32 - - with wp.ScopedDevice("cuda:0"): + wp.set_device("cuda:0") a0 = wp.empty(n, dtype=int) wp.launch(arange, dim=a0.size, inputs=[0, 1, a0]) - with wp.ScopedDevice("cuda:1"): + wp.set_device("cuda:1") a1 = wp.empty(n, dtype=int) wp.launch(arange, dim=a1.size, inputs=[0, 1, a1]) - assert a0.device == "cuda:0" - assert a1.device == "cuda:1" - - expected = np.arange(n, dtype=int) + # restore default device + wp.set_device(saved_device) - assert_np_equal(a0.numpy(), expected) - assert_np_equal(a1.numpy(), expected) + assert a0.device == "cuda:0" + assert a1.device == "cuda:1" + expected = np.arange(n, dtype=int) -def test_multigpu_nesting(test, device): - assert len(wp.get_cuda_devices()) > 1, "At least two CUDA devices are required" + assert_np_equal(a0.numpy(), expected) + assert_np_equal(a1.numpy(), expected) - initial_device = wp.get_device() - initial_cuda_device = wp.get_cuda_device() - - with wp.ScopedDevice("cuda:1"): - assert wp.get_device() == "cuda:1" - assert wp.get_cuda_device() == "cuda:1" + @unittest.skipUnless(len(wp.get_cuda_devices()) > 1, "Requires at least two CUDA devices") + def test_multigpu_scoped_device(self): + n = 32 with wp.ScopedDevice("cuda:0"): - assert wp.get_device() == "cuda:0" - assert wp.get_cuda_device() == "cuda:0" - - with wp.ScopedDevice("cpu"): - assert wp.get_device() == "cpu" - assert wp.get_cuda_device() == "cuda:0" + a0 = wp.empty(n, dtype=int) + wp.launch(arange, dim=a0.size, inputs=[0, 1, a0]) - wp.set_device("cuda:1") + with wp.ScopedDevice("cuda:1"): + a1 = wp.empty(n, dtype=int) + wp.launch(arange, dim=a1.size, inputs=[0, 1, a1]) - assert wp.get_device() == "cuda:1" - assert wp.get_cuda_device() == "cuda:1" + assert a0.device == "cuda:0" + assert a1.device == "cuda:1" - assert wp.get_device() == "cuda:0" - assert wp.get_cuda_device() == "cuda:0" + expected = np.arange(n, dtype=int) - assert wp.get_device() == "cuda:1" - assert wp.get_cuda_device() == "cuda:1" + assert_np_equal(a0.numpy(), expected) + assert_np_equal(a1.numpy(), expected) - assert wp.get_device() == initial_device - assert wp.get_cuda_device() == initial_cuda_device + @unittest.skipUnless(len(wp.get_cuda_devices()) > 1, "Requires at least two CUDA devices") + def test_multigpu_nesting(self): + initial_device = wp.get_device() + initial_cuda_device = wp.get_cuda_device() + with wp.ScopedDevice("cuda:1"): + assert wp.get_device() == "cuda:1" + assert wp.get_cuda_device() == "cuda:1" -def test_multigpu_pingpong(test, device): - assert len(wp.get_cuda_devices()) > 1, "At least two CUDA devices are required" + with wp.ScopedDevice("cuda:0"): + assert wp.get_device() == "cuda:0" + assert wp.get_cuda_device() == "cuda:0" - n = 1024 * 1024 + with wp.ScopedDevice("cpu"): + assert wp.get_device() == "cpu" + assert wp.get_cuda_device() == "cuda:0" - a0 = wp.zeros(n, dtype=float, device="cuda:0") - a1 = wp.zeros(n, dtype=float, device="cuda:1") + wp.set_device("cuda:1") - iters = 10 + assert wp.get_device() == "cuda:1" + assert wp.get_cuda_device() == "cuda:1" - for _ in range(iters): - wp.launch(inc, dim=a0.size, inputs=[a0], device=a0.device) - wp.synchronize_device(a0.device) - wp.copy(a1, a0) + assert wp.get_device() == "cuda:0" + assert wp.get_cuda_device() == "cuda:0" - wp.launch(inc, dim=a1.size, inputs=[a1], device=a1.device) - wp.synchronize_device(a1.device) - wp.copy(a0, a1) + assert wp.get_device() == "cuda:1" + assert wp.get_cuda_device() == "cuda:1" - expected = np.full(n, iters * 2, dtype=np.float32) + assert wp.get_device() == initial_device + assert wp.get_cuda_device() == initial_cuda_device - assert_np_equal(a0.numpy(), expected) - assert_np_equal(a1.numpy(), expected) + @unittest.skipUnless(len(wp.get_cuda_devices()) > 1, "Requires at least two CUDA devices") + def test_multigpu_pingpong(self): + n = 1024 * 1024 + a0 = wp.zeros(n, dtype=float, device="cuda:0") + a1 = wp.zeros(n, dtype=float, device="cuda:1") -def test_multigpu_pingpong_streams(test, device): - assert len(wp.get_cuda_devices()) > 1, "At least two CUDA devices are required" + iters = 10 - n = 1024 * 1024 + for _ in range(iters): + wp.launch(inc, dim=a0.size, inputs=[a0], device=a0.device) + wp.synchronize_device(a0.device) + wp.copy(a1, a0) - a0 = wp.zeros(n, dtype=float, device="cuda:0") - a1 = wp.zeros(n, dtype=float, device="cuda:1") + wp.launch(inc, dim=a1.size, inputs=[a1], device=a1.device) + wp.synchronize_device(a1.device) + wp.copy(a0, a1) - stream0 = wp.get_stream("cuda:0") - stream1 = wp.get_stream("cuda:1") + expected = np.full(n, iters * 2, dtype=np.float32) - iters = 10 + assert_np_equal(a0.numpy(), expected) + assert_np_equal(a1.numpy(), expected) - for _ in range(iters): - wp.launch(inc, dim=a0.size, inputs=[a0], stream=stream0) - stream1.wait_stream(stream0) - wp.copy(a1, a0, stream=stream1) + @unittest.skipUnless(len(wp.get_cuda_devices()) > 1, "Requires at least two CUDA devices") + def test_multigpu_pingpong_streams(self): + n = 1024 * 1024 - wp.launch(inc, dim=a1.size, inputs=[a1], stream=stream1) - stream0.wait_stream(stream1) - wp.copy(a0, a1, stream=stream0) + a0 = wp.zeros(n, dtype=float, device="cuda:0") + a1 = wp.zeros(n, dtype=float, device="cuda:1") - expected = np.full(n, iters * 2, dtype=np.float32) + stream0 = wp.get_stream("cuda:0") + stream1 = wp.get_stream("cuda:1") - assert_np_equal(a0.numpy(), expected) - assert_np_equal(a1.numpy(), expected) + iters = 10 + for _ in range(iters): + wp.launch(inc, dim=a0.size, inputs=[a0], stream=stream0) + stream1.wait_stream(stream0) + wp.copy(a1, a0, stream=stream1) -def register(parent): - class TestMultigpu(parent): - pass + wp.launch(inc, dim=a1.size, inputs=[a1], stream=stream1) + stream0.wait_stream(stream1) + wp.copy(a0, a1, stream=stream0) - if wp.get_cuda_device_count() > 1: - add_function_test(TestMultigpu, "test_multigpu_set_device", test_multigpu_set_device) - add_function_test(TestMultigpu, "test_multigpu_scoped_device", test_multigpu_scoped_device) - add_function_test(TestMultigpu, "test_multigpu_nesting", test_multigpu_nesting) - add_function_test(TestMultigpu, "test_multigpu_pingpong", test_multigpu_pingpong) - add_function_test(TestMultigpu, "test_multigpu_pingpong_streams", test_multigpu_pingpong_streams) + expected = np.full(n, iters * 2, dtype=np.float32) - return TestMultigpu + assert_np_equal(a0.numpy(), expected) + assert_np_equal(a1.numpy(), expected) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_noise.py b/warp/tests/test_noise.py index 99e682f8a..4f0d4cdcd 100644 --- a/warp/tests/test_noise.py +++ b/warp/tests/test_noise.py @@ -7,11 +7,11 @@ import unittest -import warp as wp -from warp.tests.test_base import * - import numpy as np +import warp as wp +from warp.tests.unittest_utils import * + # import matplotlib.pyplot as plt wp.init() @@ -231,20 +231,18 @@ def test_adj_noise(test, device): test.assertTrue(err < 1.0e-8) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestNoise(parent): - pass +class TestNoise(unittest.TestCase): + pass - add_function_test(TestNoise, "test_pnoise", test_pnoise, devices=devices) - add_function_test(TestNoise, "test_curlnoise", test_curlnoise, devices=devices) - add_function_test(TestNoise, "test_adj_noise", test_adj_noise, devices=devices) - return TestNoise +add_function_test(TestNoise, "test_pnoise", test_pnoise, devices=devices) +add_function_test(TestNoise, "test_curlnoise", test_curlnoise, devices=devices) +add_function_test(TestNoise, "test_adj_noise", test_adj_noise, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_operators.py b/warp/tests/test_operators.py index c4c729bda..7f8ab7017 100644 --- a/warp/tests/test_operators.py +++ b/warp/tests/test_operators.py @@ -7,11 +7,8 @@ import unittest -import numpy as np -import math - import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -229,29 +226,25 @@ def test_operators_mat44(): expect_eq(r0[3], wp.vec4(39.0, 42.0, 45.0, 48.0)) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestOperators(parent): - pass +class TestOperators(unittest.TestCase): + pass - add_kernel_test(TestOperators, test_operators_scalar_float, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_scalar_int, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_matrix_index, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_vector_index, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_vec3, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_vec4, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_mat22, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_mat33, dim=1, devices=devices) - add_kernel_test(TestOperators, test_operators_mat44, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_scalar_float, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_scalar_int, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_matrix_index, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_vector_index, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_vec3, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_vec4, dim=1, devices=devices) - return TestOperators +add_kernel_test(TestOperators, test_operators_mat22, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_mat33, dim=1, devices=devices) +add_kernel_test(TestOperators, test_operators_mat44, dim=1, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - wp.force_load() - - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_options.py b/warp/tests/test_options.py index 1d1d32bed..ae92d66df 100644 --- a/warp/tests/test_options.py +++ b/warp/tests/test_options.py @@ -8,7 +8,7 @@ import unittest import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -93,20 +93,19 @@ def test_options_4(test, device): assert_np_equal(tape.gradients[x].numpy(), np.array(0.0)) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestOptions(parent): - pass - add_function_test(TestOptions, "test_options_1", test_options_1, devices=devices) - add_function_test(TestOptions, "test_options_2", test_options_2, devices=devices) - add_function_test(TestOptions, "test_options_3", test_options_3, devices=devices) - add_function_test(TestOptions, "test_options_4", test_options_4, devices=devices) - return TestOptions +class TestOptions(unittest.TestCase): + pass + + +add_function_test(TestOptions, "test_options_1", test_options_1, devices=devices) +add_function_test(TestOptions, "test_options_2", test_options_2, devices=devices) +add_function_test(TestOptions, "test_options_3", test_options_3, devices=devices) +add_function_test(TestOptions, "test_options_4", test_options_4, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_pinned.py b/warp/tests/test_pinned.py index c3908101a..81f781194 100644 --- a/warp/tests/test_pinned.py +++ b/warp/tests/test_pinned.py @@ -5,16 +5,17 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. +import unittest + import numpy as np -import warp as wp -from warp.tests.test_base import * -import unittest +import warp as wp +from warp.tests.unittest_utils import * wp.init() -def test_pinned(test, device): +def test_pinned(test: unittest.TestCase, device): assert wp.get_device(device).is_cuda, "Test device must be a CUDA device" n = 1024 * 1024 @@ -25,20 +26,20 @@ def test_pinned(test, device): a_pageable1 = wp.array(ones, dtype=float, device="cpu") a_pageable2 = wp.zeros_like(a_pageable1) - assert a_pageable1.pinned == False - assert a_pageable2.pinned == False + test.assertFalse(a_pageable1.pinned) + test.assertFalse(a_pageable2.pinned) # pinned host arrays for asynchronous transfers a_pinned1 = wp.array(ones, dtype=float, device="cpu", pinned=True) a_pinned2 = wp.zeros_like(a_pinned1) - assert a_pinned1.pinned == True - assert a_pinned2.pinned == True + test.assertTrue(a_pinned1.pinned) + test.assertTrue(a_pinned2.pinned) # device array a_device = wp.zeros(n, dtype=float, device=device) - assert a_device.pinned == False + test.assertFalse(a_device.pinned) wp.synchronize_device(device) @@ -59,22 +60,19 @@ def test_pinned(test, device): assert_np_equal(a_pinned2.numpy(), ones) # ensure that launching asynchronous transfers took less CPU time - assert pinned_timer.elapsed < pageable_timer.elapsed, "Pinned transfers did not take less CPU time" + test.assertTrue(pinned_timer.elapsed < pageable_timer.elapsed, "Pinned transfers did not take less CPU time") + +devices = get_unique_cuda_test_devices() -def register(parent): - cuda_devices = wp.get_cuda_devices() - class TestPinned(parent): - pass +class TestPinned(unittest.TestCase): + pass - if cuda_devices: - add_function_test(TestPinned, "test_pinned", test_pinned, devices=cuda_devices) - return TestPinned +add_function_test(TestPinned, "test_pinned", test_pinned, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_print.py b/warp/tests/test_print.py index d5c33a445..c90ad4722 100644 --- a/warp/tests/test_print.py +++ b/warp/tests/test_print.py @@ -5,13 +5,10 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import os import unittest import warp as wp - -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() @@ -25,33 +22,32 @@ def test_print_kernel(): def test_print(test, device): + wp.load_module(device=device) capture = StdOutCapture() capture.begin() wp.launch(kernel=test_print_kernel, dim=1, inputs=[], device=device) - wp.synchronize() + wp.synchronize_device(device) s = capture.end() - test.assertRegex( - s, - rf"1{os.linesep}" - rf"this is a string{os.linesep}" - rf"this is a float 457\.500000{os.linesep}" - rf"this is an int 123", - ) + # The CPU kernel printouts don't get captured by StdOutCapture() + if device.is_cuda: + test.assertRegex( + s, + rf"1{os.linesep}" + rf"this is a string{os.linesep}" + rf"this is a float 457\.500000{os.linesep}" + rf"this is an int 123", + ) -def register(parent): - devices = get_test_devices() - devices = tuple(x for x in devices if not x.is_cpu) +class TestPrint(unittest.TestCase): + pass - class TestPrint(parent): - pass - add_function_test(TestPrint, "test_print", test_print, devices=devices, check_output=False) - return TestPrint +devices = get_test_devices() +add_function_test(TestPrint, "test_print", test_print, devices=devices, check_output=False) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_quat.py b/warp/tests/test_quat.py index b7828ece7..fea6955ca 100644 --- a/warp/tests/test_quat.py +++ b/warp/tests/test_quat.py @@ -1,9 +1,16 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -1957,102 +1964,100 @@ def make_quat(*args): test.assertSequenceEqual(wptype(24) / v, make_quat(12, 6, 4, 3)) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestQuat(parent): - pass - add_kernel_test(TestQuat, test_constructor_default, dim=1, devices=devices) +class TestQuat(unittest.TestCase): + pass - for dtype in np_float_types: - add_function_test_register_kernel( - TestQuat, f"test_constructors_{dtype.__name__}", test_constructors, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, - f"test_casting_constructors_{dtype.__name__}", - test_casting_constructors, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestQuat, f"test_anon_type_instance_{dtype.__name__}", test_anon_type_instance, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_inverse_{dtype.__name__}", test_inverse, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_quat_identity_{dtype.__name__}", test_quat_identity, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_dotproduct_{dtype.__name__}", test_dotproduct, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_length_{dtype.__name__}", test_length, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_normalize_{dtype.__name__}", test_normalize, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_addition_{dtype.__name__}", test_addition, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_subtraction_{dtype.__name__}", test_subtraction, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, - f"test_scalar_multiplication_{dtype.__name__}", - test_scalar_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestQuat, f"test_scalar_division_{dtype.__name__}", test_scalar_division, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, - f"test_quat_multiplication_{dtype.__name__}", - test_quat_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestQuat, f"test_indexing_{dtype.__name__}", test_indexing, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_quat_lerp_{dtype.__name__}", test_quat_lerp, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, - f"test_quat_to_axis_angle_grad_{dtype.__name__}", - test_quat_to_axis_angle_grad, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestQuat, f"test_slerp_grad_{dtype.__name__}", test_slerp_grad, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_quat_rpy_grad_{dtype.__name__}", test_quat_rpy_grad, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_quat_from_matrix_{dtype.__name__}", test_quat_from_matrix, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_quat_rotate_{dtype.__name__}", test_quat_rotate, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestQuat, f"test_quat_to_matrix_{dtype.__name__}", test_quat_to_matrix, devices=devices, dtype=dtype - ) - add_function_test( - TestQuat, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype - ) - return TestQuat +add_kernel_test(TestQuat, test_constructor_default, dim=1, devices=devices) + +for dtype in np_float_types: + add_function_test_register_kernel( + TestQuat, f"test_constructors_{dtype.__name__}", test_constructors, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, + f"test_casting_constructors_{dtype.__name__}", + test_casting_constructors, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestQuat, f"test_anon_type_instance_{dtype.__name__}", test_anon_type_instance, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_inverse_{dtype.__name__}", test_inverse, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_quat_identity_{dtype.__name__}", test_quat_identity, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_dotproduct_{dtype.__name__}", test_dotproduct, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_length_{dtype.__name__}", test_length, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_normalize_{dtype.__name__}", test_normalize, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_addition_{dtype.__name__}", test_addition, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_subtraction_{dtype.__name__}", test_subtraction, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, + f"test_scalar_multiplication_{dtype.__name__}", + test_scalar_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestQuat, f"test_scalar_division_{dtype.__name__}", test_scalar_division, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, + f"test_quat_multiplication_{dtype.__name__}", + test_quat_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestQuat, f"test_indexing_{dtype.__name__}", test_indexing, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_quat_lerp_{dtype.__name__}", test_quat_lerp, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, + f"test_quat_to_axis_angle_grad_{dtype.__name__}", + test_quat_to_axis_angle_grad, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestQuat, f"test_slerp_grad_{dtype.__name__}", test_slerp_grad, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_quat_rpy_grad_{dtype.__name__}", test_quat_rpy_grad, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_quat_from_matrix_{dtype.__name__}", test_quat_from_matrix, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_quat_rotate_{dtype.__name__}", test_quat_rotate, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestQuat, f"test_quat_to_matrix_{dtype.__name__}", test_quat_to_matrix, devices=devices, dtype=dtype + ) + add_function_test( + TestQuat, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype + ) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_rand.py b/warp/tests/test_rand.py index 4fe21f58c..2f169329e 100644 --- a/warp/tests/test_rand.py +++ b/warp/tests/test_rand.py @@ -9,10 +9,11 @@ import numpy as np +import warp as wp +from warp.tests.unittest_utils import * + # import matplotlib.pyplot as plt -import warp as wp -from warp.tests.test_base import * wp.init() @@ -62,7 +63,7 @@ def test_rand(test, device): wp.copy(int_ab_host, int_ab_device) wp.copy(float_01_host, float_01_device) wp.copy(float_ab_host, float_ab_device) - wp.synchronize() + wp.synchronize_device(device) int_a = int_a_host.numpy() int_ab = int_ab_host.numpy() @@ -269,21 +270,19 @@ def test_poisson(test, device): test.assertTrue(np.abs(poisson_high_std - np_poisson_high_std) <= 2e-1) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestNoise(parent): - pass +class TestRand(unittest.TestCase): + pass - add_function_test(TestNoise, "test_rand", test_rand, devices=devices) - add_function_test(TestNoise, "test_sample_cdf", test_sample_cdf, devices=devices) - add_function_test(TestNoise, "test_sampling_methods", test_sampling_methods, devices=devices) - add_function_test(TestNoise, "test_poisson", test_poisson, devices=devices) - return TestNoise +add_function_test(TestRand, "test_rand", test_rand, devices=devices) +add_function_test(TestRand, "test_sample_cdf", test_sample_cdf, devices=devices) +add_function_test(TestRand, "test_sampling_methods", test_sampling_methods, devices=devices) +add_function_test(TestRand, "test_poisson", test_poisson, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_reload.py b/warp/tests/test_reload.py index bb301e9d5..4694c1587 100644 --- a/warp/tests/test_reload.py +++ b/warp/tests/test_reload.py @@ -5,25 +5,22 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import numpy as np -import warp as wp +import importlib +import os +import unittest -import math +import numpy as np import warp as wp -from warp.tests.test_base import * -import unittest -import importlib -import os +# dummy modules used for testing reload with dependencies +import warp.tests.aux_test_dependent as test_dependent +import warp.tests.aux_test_reference as test_reference +import warp.tests.aux_test_reference_reference as test_reference_reference # dummy module used for testing reload -import warp.tests.test_square as test_square - -# dummy modules used for testing reload with dependencies -import warp.tests.test_dependent as test_dependent -import warp.tests.test_reference as test_reference -import warp.tests.test_reference_reference as test_reference_reference +import warp.tests.aux_test_square as test_square +from warp.tests.unittest_utils import * wp.init() @@ -110,7 +107,7 @@ def run(expect, device): def test_reload(test, device): # write out the module python and import it - f = open(os.path.abspath(os.path.join(os.path.dirname(__file__), "test_square.py")), "w") + f = open(os.path.abspath(os.path.join(os.path.dirname(__file__), "aux_test_square.py")), "w") f.writelines(square_two) f.flush() f.close() @@ -118,7 +115,7 @@ def test_reload(test, device): reload_module(test_square) test_square.run(expect=4.0, device=device) # 2*2=4 - f = open(os.path.abspath(os.path.join(os.path.dirname(__file__), "test_square.py")), "w") + f = open(os.path.abspath(os.path.join(os.path.dirname(__file__), "aux_test_square.py")), "w") f.writelines(square_four) f.flush() f.close() @@ -130,12 +127,12 @@ def test_reload(test, device): def test_reload_class(test, device): def test_func(): - import warp.tests.test_class_kernel - from warp.tests.test_class_kernel import ClassKernelTest - import importlib as imp - imp.reload(warp.tests.test_class_kernel) + import warp.tests.aux_test_class_kernel + from warp.tests.aux_test_class_kernel import ClassKernelTest + + imp.reload(warp.tests.aux_test_class_kernel) ctest = ClassKernelTest(device) expected = np.zeros((10, 3, 3), dtype=np.float32) @@ -149,7 +146,7 @@ def test_func(): template_ref = """# This file is used to test reloading module references. import warp as wp -import warp.tests.test_reference_reference as refref +import warp.tests.aux_test_reference_reference as refref wp.init() @@ -173,8 +170,8 @@ def more_magic(): def test_reload_references(test, device): - path_ref = os.path.abspath(os.path.join(os.path.dirname(__file__), "test_reference.py")) - path_refref = os.path.abspath(os.path.join(os.path.dirname(__file__), "test_reference_reference.py")) + path_ref = os.path.abspath(os.path.join(os.path.dirname(__file__), "aux_test_reference.py")) + path_refref = os.path.abspath(os.path.join(os.path.dirname(__file__), "aux_test_reference_reference.py")) # rewrite both dependency modules and reload them with open(path_ref, "w") as f: @@ -202,21 +199,19 @@ def test_reload_references(test, device): test_dependent.run(expect=4.0, device=device) # 2 * 2 = 4 -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestReload(parent): - pass +class TestReload(unittest.TestCase): + pass - add_function_test(TestReload, "test_redefine", test_redefine, devices=devices) - add_function_test(TestReload, "test_reload", test_reload, devices=devices) - add_function_test(TestReload, "test_reload_class", test_reload_class, devices=devices) - add_function_test(TestReload, "test_reload_references", test_reload_references, devices=devices) - return TestReload +add_function_test(TestReload, "test_redefine", test_redefine, devices=devices) +add_function_test(TestReload, "test_reload", test_reload, devices=devices) +add_function_test(TestReload, "test_reload_class", test_reload_class, devices=devices) +add_function_test(TestReload, "test_reload_references", test_reload_references, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=False) diff --git a/warp/tests/test_rounding.py b/warp/tests/test_rounding.py index 31c9b4671..999a59056 100644 --- a/warp/tests/test_rounding.py +++ b/warp/tests/test_rounding.py @@ -7,11 +7,11 @@ import unittest -import warp as wp -from warp.tests.test_base import * - import numpy as np +import warp as wp +from warp.tests.unittest_utils import * + compare_to_numpy = False print_results = False @@ -165,18 +165,15 @@ def test_rounding(test, device): print("----------------------------------------------") -def register(parent): - class TestRounding(parent): - pass +class TestRounding(unittest.TestCase): + pass - devices = get_test_devices() - add_function_test(TestRounding, "test_rounding", test_rounding, devices=devices) +devices = get_test_devices() - return TestRounding +add_function_test(TestRounding, "test_rounding", test_rounding, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_runlength_encode.py b/warp/tests/test_runlength_encode.py index a7f29fe09..49b7e3946 100644 --- a/warp/tests/test_runlength_encode.py +++ b/warp/tests/test_runlength_encode.py @@ -1,11 +1,18 @@ -from functools import partial +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest +from functools import partial import numpy as np -import warp as wp +import warp as wp +from warp.tests.unittest_utils import * from warp.utils import runlength_encode -from warp.tests.test_base import * wp.init() @@ -29,39 +36,10 @@ def test_runlength_encode_int(test, device, n): assert_np_equal(unique_counts.numpy()[:run_count], unique_counts_np[:run_count]) -def test_runlength_encode_error_devices_mismatch(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty_like(values, device="cuda:0") - run_lengths = wp.empty_like(values, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"Array storage devices do not match$", - ): - runlength_encode(values, run_values, run_lengths) - - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty_like(values, device="cpu") - run_lengths = wp.empty_like(values, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"Array storage devices do not match$", - ): - runlength_encode(values, run_values, run_lengths) - - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty_like(values, device="cuda:0") - run_lengths = wp.empty_like(values, device="cpu") - with test.assertRaisesRegex( - RuntimeError, - r"Array storage devices do not match$", - ): - runlength_encode(values, run_values, run_lengths) - - def test_runlength_encode_error_insufficient_storage(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty(1, dtype=int, device="cpu") - run_lengths = wp.empty(123, dtype=int, device="cpu") + values = wp.zeros(123, dtype=int, device=device) + run_values = wp.empty(1, dtype=int, device=device) + run_lengths = wp.empty(123, dtype=int, device=device) with test.assertRaisesRegex( RuntimeError, r"Output array storage sizes must be at least equal to value_count$", @@ -79,9 +57,9 @@ def test_runlength_encode_error_insufficient_storage(test, device): def test_runlength_encode_error_dtypes_mismatch(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty(123, dtype=float, device="cpu") - run_lengths = wp.empty_like(values) + values = wp.zeros(123, dtype=int, device=device) + run_values = wp.empty(123, dtype=float, device=device) + run_lengths = wp.empty_like(values, device=device) with test.assertRaisesRegex( RuntimeError, r"values and run_values data types do not match$", @@ -90,9 +68,9 @@ def test_runlength_encode_error_dtypes_mismatch(test, device): def test_runlength_encode_error_run_length_unsupported_dtype(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty(123, dtype=int, device="cpu") - run_lengths = wp.empty(123, dtype=float, device="cpu") + values = wp.zeros(123, dtype=int, device=device) + run_values = wp.empty(123, dtype=int, device=device) + run_lengths = wp.empty(123, dtype=float, device=device) with test.assertRaisesRegex( RuntimeError, r"run_lengths array must be of type int32$", @@ -100,23 +78,11 @@ def test_runlength_encode_error_run_length_unsupported_dtype(test, device): runlength_encode(values, run_values, run_lengths) -def test_runlength_encode_error_run_count_device_mismatch(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty_like(values, device="cpu") - run_lengths = wp.empty_like(values, device="cpu") - run_count = wp.empty(shape=(1,), dtype=int, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"run_count storage device does not match other arrays$", - ): - runlength_encode(values, run_values, run_lengths, run_count=run_count) - - def test_runlength_encode_error_run_count_unsupported_dtype(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - run_values = wp.empty_like(values, device="cpu") - run_lengths = wp.empty_like(values, device="cpu") - run_count = wp.empty(shape=(1,), dtype=float, device="cpu") + values = wp.zeros(123, dtype=int, device=device) + run_values = wp.empty_like(values, device=device) + run_lengths = wp.empty_like(values, device=device) + run_count = wp.empty(shape=(1,), dtype=float, device=device) with test.assertRaisesRegex( RuntimeError, r"run_count array must be of type int32$", @@ -135,57 +101,90 @@ def test_runlength_encode_error_unsupported_dtype(test, device): runlength_encode(values, run_values, run_lengths) -def register(parent): - devices = get_test_devices() - - class TestRunlengthEncode(parent): - pass - - add_function_test( - TestRunlengthEncode, "test_runlength_encode_int", partial(test_runlength_encode_int, n=100), devices=devices - ) - add_function_test( - TestRunlengthEncode, "test_runlength_encode_empty", partial(test_runlength_encode_int, n=0), devices=devices - ) - add_function_test( - TestRunlengthEncode, - "test_runlength_encode_error_devices_mismatch", - test_runlength_encode_error_devices_mismatch, - ) - add_function_test( - TestRunlengthEncode, - "test_runlength_encode_error_insufficient_storage", - test_runlength_encode_error_insufficient_storage, - ) - add_function_test( - TestRunlengthEncode, "test_runlength_encode_error_dtypes_mismatch", test_runlength_encode_error_dtypes_mismatch - ) - add_function_test( - TestRunlengthEncode, - "test_runlength_encode_error_run_length_unsupported_dtype", - test_runlength_encode_error_run_length_unsupported_dtype, - ) - add_function_test( - TestRunlengthEncode, - "test_runlength_encode_error_run_count_device_mismatch", - test_runlength_encode_error_run_count_device_mismatch, - ) - add_function_test( - TestRunlengthEncode, - "test_runlength_encode_error_run_count_unsupported_dtype", - test_runlength_encode_error_run_count_unsupported_dtype, - ) - add_function_test( - TestRunlengthEncode, - "test_runlength_encode_error_unsupported_dtype", - test_runlength_encode_error_unsupported_dtype, - devices=devices, - ) - - return TestRunlengthEncode +devices = get_test_devices() + + +class TestRunlengthEncode(unittest.TestCase): + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_runlength_encode_error_devices_mismatch(self): + values = wp.zeros(123, dtype=int, device="cpu") + run_values = wp.empty_like(values, device="cuda:0") + run_lengths = wp.empty_like(values, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"Array storage devices do not match$", + ): + runlength_encode(values, run_values, run_lengths) + + values = wp.zeros(123, dtype=int, device="cpu") + run_values = wp.empty_like(values, device="cpu") + run_lengths = wp.empty_like(values, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"Array storage devices do not match$", + ): + runlength_encode(values, run_values, run_lengths) + + values = wp.zeros(123, dtype=int, device="cpu") + run_values = wp.empty_like(values, device="cuda:0") + run_lengths = wp.empty_like(values, device="cpu") + with self.assertRaisesRegex( + RuntimeError, + r"Array storage devices do not match$", + ): + runlength_encode(values, run_values, run_lengths) + + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_runlength_encode_error_run_count_device_mismatch(self): + values = wp.zeros(123, dtype=int, device="cpu") + run_values = wp.empty_like(values, device="cpu") + run_lengths = wp.empty_like(values, device="cpu") + run_count = wp.empty(shape=(1,), dtype=int, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"run_count storage device does not match other arrays$", + ): + runlength_encode(values, run_values, run_lengths, run_count=run_count) + + +add_function_test( + TestRunlengthEncode, "test_runlength_encode_int", partial(test_runlength_encode_int, n=100), devices=devices +) +add_function_test( + TestRunlengthEncode, "test_runlength_encode_empty", partial(test_runlength_encode_int, n=0), devices=devices +) +add_function_test( + TestRunlengthEncode, + "test_runlength_encode_error_insufficient_storage", + test_runlength_encode_error_insufficient_storage, + devices=devices, +) +add_function_test( + TestRunlengthEncode, + "test_runlength_encode_error_dtypes_mismatch", + test_runlength_encode_error_dtypes_mismatch, + devices=devices, +) +add_function_test( + TestRunlengthEncode, + "test_runlength_encode_error_run_length_unsupported_dtype", + test_runlength_encode_error_run_length_unsupported_dtype, + devices=devices, +) +add_function_test( + TestRunlengthEncode, + "test_runlength_encode_error_run_count_unsupported_dtype", + test_runlength_encode_error_run_count_unsupported_dtype, + devices=devices, +) +add_function_test( + TestRunlengthEncode, + "test_runlength_encode_error_unsupported_dtype", + test_runlength_encode_error_unsupported_dtype, + devices=devices, +) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_smoothstep.py b/warp/tests/test_smoothstep.py index 2f1070716..d12b9718f 100644 --- a/warp/tests/test_smoothstep.py +++ b/warp/tests/test_smoothstep.py @@ -5,14 +5,14 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. +import unittest from dataclasses import dataclass from typing import Any -import unittest import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * @dataclass @@ -153,17 +153,16 @@ def fn( ) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + + +class TestSmoothstep(unittest.TestCase): + pass - class TestSmoothstep(parent): - pass - add_function_test(TestSmoothstep, "test_smoothstep", test_smoothstep, devices=devices) - return TestSmoothstep +add_function_test(TestSmoothstep, "test_smoothstep", test_smoothstep, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_snippet.py b/warp/tests/test_snippet.py index d1205a6ef..299150a9f 100644 --- a/warp/tests/test_snippet.py +++ b/warp/tests/test_snippet.py @@ -1,8 +1,10 @@ -import warp as wp -from warp.tests.test_base import * -import numpy as np import unittest +import numpy as np + +import warp as wp +from warp.tests.unittest_utils import * + wp.init() @@ -101,11 +103,11 @@ def reverse_kernel(d: wp.array(dtype=int), N: int): def test_cpu_snippet(test, device): - snippet = """ int inc = 1; out[tid] = x[tid] + inc; """ + @wp.func_native(snippet) def increment_snippet( x: wp.array(dtype=wp.int32), @@ -115,10 +117,7 @@ def increment_snippet( ... @wp.kernel - def increment( - x: wp.array(dtype=wp.int32), - out: wp.array(dtype=wp.int32) - ): + def increment(x: wp.array(dtype=wp.int32), out: wp.array(dtype=wp.int32)): tid = wp.tid() increment_snippet(x, out, tid) @@ -128,25 +127,17 @@ def increment( wp.launch(kernel=increment, dim=N, inputs=[x], outputs=[out], device=device) - assert_np_equal(out.numpy(), np.arange(1, N+1, 1, dtype=np.int32)) + assert_np_equal(out.numpy(), np.arange(1, N + 1, 1, dtype=np.int32)) -def register(parent): - - class TestSnippets(parent): - pass +class TestSnippets(unittest.TestCase): + pass - if wp.is_cuda_available(): - cuda_device = [wp.get_cuda_device()] - add_function_test(TestSnippets, "test_basic", test_basic, devices=cuda_device) - add_function_test(TestSnippets, "test_shared_memory", test_shared_memory, devices=cuda_device) - - if wp.is_cpu_available(): - add_function_test(TestSnippets, "test_cpu_snippet", test_cpu_snippet, devices=["cpu"]) - return TestSnippets +add_function_test(TestSnippets, "test_basic", test_basic, devices=get_unique_cuda_test_devices()) +add_function_test(TestSnippets, "test_shared_memory", test_shared_memory, devices=get_unique_cuda_test_devices()) +add_function_test(TestSnippets, "test_cpu_snippet", test_cpu_snippet, devices=["cpu"]) if __name__ == "__main__": - c = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_sparse.py b/warp/tests/test_sparse.py index 2b6a325ec..6cbf8f21b 100644 --- a/warp/tests/test_sparse.py +++ b/warp/tests/test_sparse.py @@ -1,13 +1,20 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest import numpy as np -import warp as wp -import unittest +import warp as wp from warp.sparse import bsr_zeros, bsr_set_from_triplets, bsr_get_diag, bsr_diag, bsr_identity, bsr_copy, bsr_scale from warp.sparse import bsr_set_transpose, bsr_transposed from warp.sparse import bsr_axpy, bsr_mm, bsr_axpy_work_arrays, bsr_mm_work_arrays, bsr_mv -from warp.tests.test_base import * +from warp.tests.unittest_utils import * + wp.init() @@ -419,41 +426,35 @@ def test_bsr_mv(test, device): return test_bsr_mv -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestSparse(parent): - pass - add_function_test(TestSparse, "test_csr_from_triplets", test_csr_from_triplets, devices=devices) - add_function_test(TestSparse, "test_bsr_from_triplets", test_bsr_from_triplets, devices=devices) - add_function_test(TestSparse, "test_bsr_get_diag", test_bsr_get_set_diag, devices=devices) - add_function_test(TestSparse, "test_bsr_copy_scale", test_bsr_copy_scale, devices=devices) +class TestSparse(unittest.TestCase): + pass - add_function_test(TestSparse, "test_csr_transpose", make_test_bsr_transpose((1, 1), wp.float32), devices=devices) - add_function_test( - TestSparse, "test_bsr_transpose_1_3", make_test_bsr_transpose((1, 3), wp.float32), devices=devices - ) - add_function_test( - TestSparse, "test_bsr_transpose_3_3", make_test_bsr_transpose((3, 3), wp.float64), devices=devices - ) - add_function_test(TestSparse, "test_csr_axpy", make_test_bsr_axpy((1, 1), wp.float32), devices=devices) - add_function_test(TestSparse, "test_bsr_axpy_1_3", make_test_bsr_axpy((1, 3), wp.float32), devices=devices) - add_function_test(TestSparse, "test_bsr_axpy_3_3", make_test_bsr_axpy((3, 3), wp.float64), devices=devices) +add_function_test(TestSparse, "test_csr_from_triplets", test_csr_from_triplets, devices=devices) +add_function_test(TestSparse, "test_bsr_from_triplets", test_bsr_from_triplets, devices=devices) +add_function_test(TestSparse, "test_bsr_get_diag", test_bsr_get_set_diag, devices=devices) +add_function_test(TestSparse, "test_bsr_copy_scale", test_bsr_copy_scale, devices=devices) + +add_function_test(TestSparse, "test_csr_transpose", make_test_bsr_transpose((1, 1), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_transpose_1_3", make_test_bsr_transpose((1, 3), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_transpose_3_3", make_test_bsr_transpose((3, 3), wp.float64), devices=devices) - add_function_test(TestSparse, "test_csr_mm", make_test_bsr_mm((1, 1), wp.float32), devices=devices) - add_function_test(TestSparse, "test_bsr_mm_1_3", make_test_bsr_mm((1, 3), wp.float32), devices=devices) - add_function_test(TestSparse, "test_bsr_mm_3_3", make_test_bsr_mm((3, 3), wp.float64), devices=devices) +add_function_test(TestSparse, "test_csr_axpy", make_test_bsr_axpy((1, 1), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_axpy_1_3", make_test_bsr_axpy((1, 3), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_axpy_3_3", make_test_bsr_axpy((3, 3), wp.float64), devices=devices) - add_function_test(TestSparse, "test_csr_mv", make_test_bsr_mv((1, 1), wp.float32), devices=devices) - add_function_test(TestSparse, "test_bsr_mv_1_3", make_test_bsr_mv((1, 3), wp.float32), devices=devices) - add_function_test(TestSparse, "test_bsr_mv_3_3", make_test_bsr_mv((3, 3), wp.float64), devices=devices) +add_function_test(TestSparse, "test_csr_mm", make_test_bsr_mm((1, 1), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_mm_1_3", make_test_bsr_mm((1, 3), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_mm_3_3", make_test_bsr_mm((3, 3), wp.float64), devices=devices) - return TestSparse +add_function_test(TestSparse, "test_csr_mv", make_test_bsr_mv((1, 1), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_mv_1_3", make_test_bsr_mv((1, 3), wp.float32), devices=devices) +add_function_test(TestSparse, "test_bsr_mv_3_3", make_test_bsr_mv((3, 3), wp.float64), devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_spatial.py b/warp/tests/test_spatial.py index 9be8a03c1..a557a8d58 100644 --- a/warp/tests/test_spatial.py +++ b/warp/tests/test_spatial.py @@ -1,9 +1,16 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import unittest import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -1956,188 +1963,186 @@ def transform_create_test(input: wp.array(dtype=wptype), output: wp.array(dtype= tape.zero() -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestSpatial(parent): - pass - for dtype in np_float_types: - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_vector_constructors_{dtype.__name__}", - test_spatial_vector_constructors, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_vector_indexing_{dtype.__name__}", - test_spatial_vector_indexing, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_vector_scalar_multiplication_{dtype.__name__}", - test_spatial_vector_scalar_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_vector_add_sub_{dtype.__name__}", - test_spatial_vector_add_sub, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, f"test_spatial_dot_{dtype.__name__}", test_spatial_dot, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestSpatial, f"test_spatial_cross_{dtype.__name__}", test_spatial_cross, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_top_bottom_{dtype.__name__}", - test_spatial_top_bottom, - devices=devices, - dtype=dtype, - ) +class TestSpatial(unittest.TestCase): + pass - add_function_test_register_kernel( - TestSpatial, - f"test_transform_constructors_{dtype.__name__}", - test_transform_constructors, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_anon_type_instance_{dtype.__name__}", - test_transform_anon_type_instance, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_identity_{dtype.__name__}", - test_transform_identity, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_indexing_{dtype.__name__}", - test_transform_indexing, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_get_trans_rot_{dtype.__name__}", - test_transform_get_trans_rot, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_multiply_{dtype.__name__}", - test_transform_multiply, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_inverse_{dtype.__name__}", - test_transform_inverse, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_point_vector_{dtype.__name__}", - test_transform_point_vector, - devices=devices, - dtype=dtype, - ) - # are these two valid? They don't seem to be doing things you'd want to do, - # maybe they should be removed - add_function_test_register_kernel( - TestSpatial, - f"test_transform_scalar_multiplication_{dtype.__name__}", - test_transform_scalar_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_transform_add_sub_{dtype.__name__}", - test_transform_add_sub, - devices=devices, - dtype=dtype, - ) +for dtype in np_float_types: + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_vector_constructors_{dtype.__name__}", + test_spatial_vector_constructors, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_vector_indexing_{dtype.__name__}", + test_spatial_vector_indexing, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_vector_scalar_multiplication_{dtype.__name__}", + test_spatial_vector_scalar_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_vector_add_sub_{dtype.__name__}", + test_spatial_vector_add_sub, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, f"test_spatial_dot_{dtype.__name__}", test_spatial_dot, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestSpatial, f"test_spatial_cross_{dtype.__name__}", test_spatial_cross, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_top_bottom_{dtype.__name__}", + test_spatial_top_bottom, + devices=devices, + dtype=dtype, + ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_matrix_constructors_{dtype.__name__}", - test_spatial_matrix_constructors, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_matrix_indexing_{dtype.__name__}", - test_spatial_matrix_indexing, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_matrix_scalar_multiplication_{dtype.__name__}", - test_spatial_matrix_scalar_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_matrix_add_sub_{dtype.__name__}", - test_spatial_matrix_add_sub, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_matvec_multiplication_{dtype.__name__}", - test_spatial_matvec_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_matmat_multiplication_{dtype.__name__}", - test_spatial_matmat_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, - f"test_spatial_outer_product_{dtype.__name__}", - test_spatial_outer_product, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestSpatial, f"test_spatial_adjoint_{dtype.__name__}", test_spatial_adjoint, devices=devices, dtype=dtype - ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_constructors_{dtype.__name__}", + test_transform_constructors, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_anon_type_instance_{dtype.__name__}", + test_transform_anon_type_instance, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_identity_{dtype.__name__}", + test_transform_identity, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_indexing_{dtype.__name__}", + test_transform_indexing, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_get_trans_rot_{dtype.__name__}", + test_transform_get_trans_rot, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_multiply_{dtype.__name__}", + test_transform_multiply, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_inverse_{dtype.__name__}", + test_transform_inverse, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_point_vector_{dtype.__name__}", + test_transform_point_vector, + devices=devices, + dtype=dtype, + ) - # \TODO: test spatial_mass and spatial_jacobian + # are these two valid? They don't seem to be doing things you'd want to do, + # maybe they should be removed + add_function_test_register_kernel( + TestSpatial, + f"test_transform_scalar_multiplication_{dtype.__name__}", + test_transform_scalar_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_transform_add_sub_{dtype.__name__}", + test_transform_add_sub, + devices=devices, + dtype=dtype, + ) + + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_matrix_constructors_{dtype.__name__}", + test_spatial_matrix_constructors, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_matrix_indexing_{dtype.__name__}", + test_spatial_matrix_indexing, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_matrix_scalar_multiplication_{dtype.__name__}", + test_spatial_matrix_scalar_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_matrix_add_sub_{dtype.__name__}", + test_spatial_matrix_add_sub, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_matvec_multiplication_{dtype.__name__}", + test_spatial_matvec_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_matmat_multiplication_{dtype.__name__}", + test_spatial_matmat_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, + f"test_spatial_outer_product_{dtype.__name__}", + test_spatial_outer_product, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestSpatial, f"test_spatial_adjoint_{dtype.__name__}", test_spatial_adjoint, devices=devices, dtype=dtype + ) - return TestSpatial + # \TODO: test spatial_mass and spatial_jacobian if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_streams.py b/warp/tests/test_streams.py index 2f76861f2..5cb0f5082 100644 --- a/warp/tests/test_streams.py +++ b/warp/tests/test_streams.py @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -284,145 +284,138 @@ def test_stream_scope_wait_stream(test, device): assert_np_equal(d.numpy(), np.full(N, fill_value=4.0)) -def test_stream_exceptions(test, device): - cpu_device = wp.get_device("cpu") +devices = get_unique_cuda_test_devices() - # Can't set the stream on a CPU device - with test.assertRaises(RuntimeError): - stream0 = wp.Stream() - cpu_device.stream = stream0 - # Can't create a stream on the CPU - with test.assertRaises(RuntimeError): - wp.Stream(device="cpu") +class TestStreams(unittest.TestCase): + def test_stream_exceptions(self): + cpu_device = wp.get_device("cpu") - # Can't create an event with CPU device - with test.assertRaises(RuntimeError): - wp.Event(device=cpu_device) + # Can't set the stream on a CPU device + with self.assertRaises(RuntimeError): + stream0 = wp.Stream() + cpu_device.stream = stream0 - # Can't get the stream on a CPU device - with test.assertRaises(RuntimeError): - cpu_stream = cpu_device.stream # noqa: F841 + # Can't create a stream on the CPU + with self.assertRaises(RuntimeError): + wp.Stream(device="cpu") + # Can't create an event with CPU device + with self.assertRaises(RuntimeError): + wp.Event(device=cpu_device) -def test_stream_arg_graph_mgpu(test, device): - # resources on GPU 0 - stream0 = wp.get_stream("cuda:0") - a0 = wp.zeros(N, dtype=float, device="cuda:0") - b0 = wp.empty(N, dtype=float, device="cuda:0") - c0 = wp.empty(N, dtype=float, device="cuda:0") + # Can't get the stream on a CPU device + with self.assertRaises(RuntimeError): + cpu_stream = cpu_device.stream # noqa: F841 - # resources on GPU 1 - stream1 = wp.get_stream("cuda:1") - a1 = wp.zeros(N, dtype=float, device="cuda:1") + @unittest.skipUnless(len(wp.get_cuda_devices()) > 1, "Requires at least two CUDA devices") + def test_stream_arg_graph_mgpu(self): + wp.load_module(device="cuda:0") + wp.load_module(device="cuda:1") - # start recording on stream0 - wp.capture_begin(stream=stream0) + # resources on GPU 0 + stream0 = wp.get_stream("cuda:0") + a0 = wp.zeros(N, dtype=float, device="cuda:0") + b0 = wp.empty(N, dtype=float, device="cuda:0") + c0 = wp.empty(N, dtype=float, device="cuda:0") - # branch into stream1 - stream1.wait_stream(stream0) + # resources on GPU 1 + stream1 = wp.get_stream("cuda:1") + a1 = wp.zeros(N, dtype=float, device="cuda:1") - # launch concurrent kernels on each stream - wp.launch(inc, dim=N, inputs=[a0], stream=stream0) - wp.launch(inc, dim=N, inputs=[a1], stream=stream1) - - # wait for stream1 to finish - stream0.wait_stream(stream1) - - # copy values from stream1 - wp.copy(b0, a1, stream=stream0) + # start recording on stream0 + wp.capture_begin(stream=stream0, force_module_load=False) + try: + # branch into stream1 + stream1.wait_stream(stream0) - # compute sum - wp.launch(sum, dim=N, inputs=[a0, b0, c0], stream=stream0) + # launch concurrent kernels on each stream + wp.launch(inc, dim=N, inputs=[a0], stream=stream0) + wp.launch(inc, dim=N, inputs=[a1], stream=stream1) - # finish recording on stream0 - g = wp.capture_end(stream=stream0) + # wait for stream1 to finish + stream0.wait_stream(stream1) - # replay - num_iters = 10 - for _ in range(num_iters): - wp.capture_launch(g, stream=stream0) + # copy values from stream1 + wp.copy(b0, a1, stream=stream0) - # check results - assert_np_equal(c0.numpy(), np.full(N, fill_value=2 * num_iters)) + # compute sum + wp.launch(sum, dim=N, inputs=[a0, b0, c0], stream=stream0) + finally: + # finish recording on stream0 + g = wp.capture_end(stream=stream0) + # replay + num_iters = 10 + for _ in range(num_iters): + wp.capture_launch(g, stream=stream0) -def test_stream_scope_graph_mgpu(test, device): - # resources on GPU 0 - with wp.ScopedDevice("cuda:0"): - stream0 = wp.get_stream() - a0 = wp.zeros(N, dtype=float) - b0 = wp.empty(N, dtype=float) - c0 = wp.empty(N, dtype=float) + # check results + assert_np_equal(c0.numpy(), np.full(N, fill_value=2 * num_iters)) - # resources on GPU 1 - with wp.ScopedDevice("cuda:1"): - stream1 = wp.get_stream() - a1 = wp.zeros(N, dtype=float) + @unittest.skipUnless(len(wp.get_cuda_devices()) > 1, "Requires at least two CUDA devices") + def test_stream_scope_graph_mgpu(self): + wp.load_module(device="cuda:0") + wp.load_module(device="cuda:1") - # capture graph - with wp.ScopedDevice("cuda:0"): - # start recording - wp.capture_begin() + # resources on GPU 0 + with wp.ScopedDevice("cuda:0"): + stream0 = wp.get_stream() + a0 = wp.zeros(N, dtype=float) + b0 = wp.empty(N, dtype=float) + c0 = wp.empty(N, dtype=float) + # resources on GPU 1 with wp.ScopedDevice("cuda:1"): - # branch into stream1 - wp.wait_stream(stream0) + stream1 = wp.get_stream() + a1 = wp.zeros(N, dtype=float) - wp.launch(inc, dim=N, inputs=[a1]) + # capture graph + with wp.ScopedDevice("cuda:0"): + # start recording + wp.capture_begin(force_module_load=False) + try: + with wp.ScopedDevice("cuda:1"): + # branch into stream1 + wp.wait_stream(stream0) - wp.launch(inc, dim=N, inputs=[a0]) + wp.launch(inc, dim=N, inputs=[a1]) - # wait for stream1 to finish - wp.wait_stream(stream1) + wp.launch(inc, dim=N, inputs=[a0]) - # copy values from stream1 - wp.copy(b0, a1) + # wait for stream1 to finish + wp.wait_stream(stream1) - # compute sum - wp.launch(sum, dim=N, inputs=[a0, b0, c0]) + # copy values from stream1 + wp.copy(b0, a1) - # finish recording - g = wp.capture_end() + # compute sum + wp.launch(sum, dim=N, inputs=[a0, b0, c0]) + finally: + # finish recording + g = wp.capture_end() - # replay - with wp.ScopedDevice("cuda:0"): - num_iters = 10 - for _ in range(num_iters): - wp.capture_launch(g) - - # check results - assert_np_equal(c0.numpy(), np.full(N, fill_value=2 * num_iters)) - - -def register(parent): - devices = wp.get_cuda_devices() + # replay + with wp.ScopedDevice("cuda:0"): + num_iters = 10 + for _ in range(num_iters): + wp.capture_launch(g) - class TestStreams(parent): - pass + # check results + assert_np_equal(c0.numpy(), np.full(N, fill_value=2 * num_iters)) - add_function_test(TestStreams, "test_stream_arg_implicit_sync", test_stream_arg_implicit_sync, devices=devices) - add_function_test(TestStreams, "test_stream_scope_implicit_sync", test_stream_scope_implicit_sync, devices=devices) - add_function_test(TestStreams, "test_stream_arg_synchronize", test_stream_arg_synchronize, devices=devices) - add_function_test(TestStreams, "test_stream_arg_wait_event", test_stream_arg_wait_event, devices=devices) - add_function_test(TestStreams, "test_stream_arg_wait_stream", test_stream_arg_wait_stream, devices=devices) - add_function_test(TestStreams, "test_stream_scope_synchronize", test_stream_scope_synchronize, devices=devices) - add_function_test(TestStreams, "test_stream_scope_wait_event", test_stream_scope_wait_event, devices=devices) - add_function_test(TestStreams, "test_stream_scope_wait_stream", test_stream_scope_wait_stream, devices=devices) - add_function_test(TestStreams, "test_stream_exceptions", test_stream_exceptions, devices=devices) +add_function_test(TestStreams, "test_stream_arg_implicit_sync", test_stream_arg_implicit_sync, devices=devices) +add_function_test(TestStreams, "test_stream_scope_implicit_sync", test_stream_scope_implicit_sync, devices=devices) - if len(devices) > 1: - add_function_test(TestStreams, "test_stream_arg_graph_mgpu", test_stream_arg_graph_mgpu) - add_function_test(TestStreams, "test_stream_scope_graph_mgpu", test_stream_scope_graph_mgpu) - - return TestStreams +add_function_test(TestStreams, "test_stream_arg_synchronize", test_stream_arg_synchronize, devices=devices) +add_function_test(TestStreams, "test_stream_arg_wait_event", test_stream_arg_wait_event, devices=devices) +add_function_test(TestStreams, "test_stream_arg_wait_stream", test_stream_arg_wait_stream, devices=devices) +add_function_test(TestStreams, "test_stream_scope_synchronize", test_stream_scope_synchronize, devices=devices) +add_function_test(TestStreams, "test_stream_scope_wait_event", test_stream_scope_wait_event, devices=devices) +add_function_test(TestStreams, "test_stream_scope_wait_stream", test_stream_scope_wait_stream, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) - - wp.force_load(wp.get_cuda_devices()) - unittest.main(verbosity=2) diff --git a/warp/tests/test_struct.py b/warp/tests/test_struct.py index e41c7a677..9b26b628f 100644 --- a/warp/tests/test_struct.py +++ b/warp/tests/test_struct.py @@ -5,15 +5,16 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. +import unittest from typing import Any + import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * from warp.fem import Sample as StructFromAnotherModule -import unittest - wp.init() @@ -291,7 +292,7 @@ def test_struct_math_conversions(test, device): s.m5 = [10, 20, 30, 40] s.m6 = np.array([100, 200, 300, 400]) - wp.launch(check_math_conversions, dim=1, inputs=[s]) + wp.launch(check_math_conversions, dim=1, inputs=[s], device=device) @wp.struct @@ -416,9 +417,9 @@ def test_nested_array_struct(test, device): var2.i = 2 struct = ArrayStruct() - struct.array = wp.array([var1, var2], dtype=InnerStruct) + struct.array = wp.array([var1, var2], dtype=InnerStruct, device=device) - wp.launch(struct2_reader, dim=2, inputs=[struct]) + wp.launch(struct2_reader, dim=2, inputs=[struct], device=device) @wp.struct @@ -564,81 +565,111 @@ def test_dependent_module_import(c: DependentModuleImport_C): wp.tid() # nop, we're just testing codegen -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestStruct(parent): - pass - add_function_test(TestStruct, "test_step", test_step, devices=devices) - add_function_test(TestStruct, "test_step_grad", test_step_grad, devices=devices) - add_kernel_test(TestStruct, kernel=test_empty, name="test_empty", dim=1, inputs=[Empty()], devices=devices) - add_kernel_test( - TestStruct, - kernel=test_uninitialized, - name="test_uninitialized", - dim=1, - inputs=[Uninitialized()], - devices=devices, - ) - add_kernel_test(TestStruct, kernel=test_return, name="test_return", dim=1, inputs=[], devices=devices) - add_function_test(TestStruct, "test_struct_attribute_error", test_struct_attribute_error, devices=devices) - add_function_test(TestStruct, "test_nested_struct", test_nested_struct, devices=devices) - add_function_test(TestStruct, "test_nested_array_struct", test_nested_array_struct, devices=devices) - add_function_test(TestStruct, "test_nested_empty_struct", test_nested_empty_struct, devices=devices) - add_function_test(TestStruct, "test_struct_math_conversions", test_struct_math_conversions, devices=devices) - add_function_test( - TestStruct, "test_struct_default_attributes_python", test_struct_default_attributes_python, devices=devices - ) - add_kernel_test( - TestStruct, - name="test_struct_default_attributes", - kernel=test_struct_default_attributes_kernel, - dim=1, - inputs=[], - devices=devices, - ) +class TestStruct(unittest.TestCase): + pass + +add_function_test(TestStruct, "test_step", test_step, devices=devices) +add_function_test(TestStruct, "test_step_grad", test_step_grad, devices=devices) +add_kernel_test(TestStruct, kernel=test_empty, name="test_empty", dim=1, inputs=[Empty()], devices=devices) +add_kernel_test( + TestStruct, + kernel=test_uninitialized, + name="test_uninitialized", + dim=1, + inputs=[Uninitialized()], + devices=devices, +) +add_kernel_test(TestStruct, kernel=test_return, name="test_return", dim=1, inputs=[], devices=devices) +add_function_test(TestStruct, "test_nested_struct", test_nested_struct, devices=devices) +add_function_test(TestStruct, "test_nested_array_struct", test_nested_array_struct, devices=devices) +add_function_test(TestStruct, "test_nested_empty_struct", test_nested_empty_struct, devices=devices) +add_function_test(TestStruct, "test_struct_math_conversions", test_struct_math_conversions, devices=devices) +add_function_test( + TestStruct, "test_struct_default_attributes_python", test_struct_default_attributes_python, devices=devices +) +add_kernel_test( + TestStruct, + name="test_struct_default_attributes", + kernel=test_struct_default_attributes_kernel, + dim=1, + inputs=[], + devices=devices, +) + +add_kernel_test( + TestStruct, + name="test_struct_mutate_attributes", + kernel=test_struct_mutate_attributes_kernel, + dim=1, + inputs=[], + devices=devices, +) +add_kernel_test( + TestStruct, + kernel=test_uninitialized, + name="test_uninitialized", + dim=1, + inputs=[Uninitialized()], + devices=devices, +) +add_kernel_test(TestStruct, kernel=test_return, name="test_return", dim=1, inputs=[], devices=devices) +add_function_test(TestStruct, "test_nested_struct", test_nested_struct, devices=devices) +add_function_test(TestStruct, "test_nested_array_struct", test_nested_array_struct, devices=devices) +add_function_test(TestStruct, "test_nested_empty_struct", test_nested_empty_struct, devices=devices) +add_function_test(TestStruct, "test_struct_math_conversions", test_struct_math_conversions, devices=devices) +add_function_test( + TestStruct, "test_struct_default_attributes_python", test_struct_default_attributes_python, devices=devices +) +add_kernel_test( + TestStruct, + name="test_struct_default_attributes", + kernel=test_struct_default_attributes_kernel, + dim=1, + inputs=[], + devices=devices, +) + +add_kernel_test( + TestStruct, + name="test_struct_mutate_attributes", + kernel=test_struct_mutate_attributes_kernel, + dim=1, + inputs=[], + devices=devices, +) + +for device in devices: add_kernel_test( TestStruct, - name="test_struct_mutate_attributes", - kernel=test_struct_mutate_attributes_kernel, + kernel=test_struct_instantiate, + name="test_struct_instantiate", dim=1, - inputs=[], - devices=devices, + inputs=[wp.array([1], dtype=int, device=device)], + devices=[device], ) - - for device in devices: - add_kernel_test( - TestStruct, - kernel=test_struct_instantiate, - name="test_struct_instantiate", - dim=1, - inputs=[wp.array([1], dtype=int, device=device)], - devices=[device], - ) - add_kernel_test( - TestStruct, - kernel=test_return_struct, - name="test_return_struct", - dim=1, - inputs=[wp.zeros(10, dtype=int, device=device)], - devices=[device], - ) - add_kernel_test( TestStruct, - kernel=test_dependent_module_import, - name="test_dependent_module_import", + kernel=test_return_struct, + name="test_return_struct", dim=1, - inputs=[DependentModuleImport_C()], - devices=devices, + inputs=[wp.zeros(10, dtype=int, device=device)], + devices=[device], ) - return TestStruct +add_kernel_test( + TestStruct, + kernel=test_dependent_module_import, + name="test_dependent_module_import", + dim=1, + inputs=[DependentModuleImport_C()], + devices=devices, +) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_tape.py b/warp/tests/test_tape.py index 1f28de38c..598ef2446 100644 --- a/warp/tests/test_tape.py +++ b/warp/tests/test_tape.py @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -127,28 +127,22 @@ def test_tape_dot_product(test, device): assert_np_equal(tape.gradients[y].numpy(), x.numpy()) -def test_tape_no_nested_tapes(test, device): - with test.assertRaises(RuntimeError): - with wp.Tape(): - with wp.Tape(): - pass - +devices = get_test_devices() -def register(parent): - devices = get_test_devices() - class TestTape(parent): - pass +class TestTape(unittest.TestCase): + def test_tape_no_nested_tapes(self): + with self.assertRaises(RuntimeError): + with wp.Tape(): + with wp.Tape(): + pass - add_function_test(TestTape, "test_tape_mul_constant", test_tape_mul_constant, devices=devices) - add_function_test(TestTape, "test_tape_mul_variable", test_tape_mul_variable, devices=devices) - add_function_test(TestTape, "test_tape_dot_product", test_tape_dot_product, devices=devices) - add_function_test(TestTape, "test_tape_no_nested_tapes", test_tape_no_nested_tapes, devices=devices) - return TestTape +add_function_test(TestTape, "test_tape_mul_constant", test_tape_mul_constant, devices=devices) +add_function_test(TestTape, "test_tape_mul_variable", test_tape_mul_variable, devices=devices) +add_function_test(TestTape, "test_tape_dot_product", test_tape_dot_product, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_torch.py b/warp/tests/test_torch.py index 107dc90e3..bc69a3301 100644 --- a/warp/tests/test_torch.py +++ b/warp/tests/test_torch.py @@ -7,11 +7,10 @@ import unittest -# include parent path import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -470,6 +469,8 @@ def backward(ctx, adj_y): def test_torch_graph_torch_stream(test, device): """Capture Torch graph on Torch stream""" + wp.load_module(device=device) + import torch torch_device = wp.device_to_torch(device) @@ -551,12 +552,14 @@ def test_warp_graph_warp_stream(test, device): # capture graph with wp.ScopedDevice(device), torch.cuda.stream(torch_stream): - wp.capture_begin() - t += 1.0 - wp.launch(inc, dim=n, inputs=[a]) - t += 1.0 - wp.launch(inc, dim=n, inputs=[a]) - g = wp.capture_end() + wp.capture_begin(force_module_load=False) + try: + t += 1.0 + wp.launch(inc, dim=n, inputs=[a]) + t += 1.0 + wp.launch(inc, dim=n, inputs=[a]) + finally: + g = wp.capture_end() # replay graph num_iters = 10 @@ -570,6 +573,8 @@ def test_warp_graph_warp_stream(test, device): def test_warp_graph_torch_stream(test, device): """Capture Warp graph on Torch stream""" + wp.load_module(device=device) + import torch torch_device = wp.device_to_torch(device) @@ -587,12 +592,14 @@ def test_warp_graph_torch_stream(test, device): # capture graph with wp.ScopedStream(warp_stream), torch.cuda.stream(torch_stream): - wp.capture_begin() - t += 1.0 - wp.launch(inc, dim=n, inputs=[a]) - t += 1.0 - wp.launch(inc, dim=n, inputs=[a]) - g = wp.capture_end() + wp.capture_begin(force_module_load=False) + try: + t += 1.0 + wp.launch(inc, dim=n, inputs=[a]) + t += 1.0 + wp.launch(inc, dim=n, inputs=[a]) + finally: + g = wp.capture_end() # replay graph num_iters = 10 @@ -603,83 +610,79 @@ def test_warp_graph_torch_stream(test, device): assert passed.item() -def register(parent): - class TestTorch(parent): - pass - - try: - import torch - - # check which Warp devices work with Torch - # CUDA devices may fail if Torch was not compiled with CUDA support - test_devices = get_test_devices() - torch_compatible_devices = [] - torch_compatible_cuda_devices = [] - - for d in test_devices: - try: - t = torch.arange(10, device=wp.device_to_torch(d)) - t += 1 - torch_compatible_devices.append(d) - if d.is_cuda: - torch_compatible_cuda_devices.append(d) - except Exception as e: - print(f"Skipping Torch tests on device '{d}' due to exception: {e}") - - if torch_compatible_devices: - add_function_test(TestTorch, "test_from_torch", test_from_torch, devices=torch_compatible_devices) - add_function_test( - TestTorch, "test_from_torch_slices", test_from_torch_slices, devices=torch_compatible_devices - ) - add_function_test( - TestTorch, - "test_from_torch_zero_strides", - test_from_torch_zero_strides, - devices=torch_compatible_devices, - ) - add_function_test(TestTorch, "test_to_torch", test_to_torch, devices=torch_compatible_devices) - add_function_test(TestTorch, "test_torch_zerocopy", test_torch_zerocopy, devices=torch_compatible_devices) - add_function_test(TestTorch, "test_torch_autograd", test_torch_autograd, devices=torch_compatible_devices) - - if torch_compatible_cuda_devices: - add_function_test( - TestTorch, - "test_torch_graph_torch_stream", - test_torch_graph_torch_stream, - devices=torch_compatible_cuda_devices, - ) - add_function_test( - TestTorch, - "test_torch_graph_warp_stream", - test_torch_graph_warp_stream, - devices=torch_compatible_cuda_devices, - ) - add_function_test( - TestTorch, - "test_warp_graph_warp_stream", - test_warp_graph_warp_stream, - devices=torch_compatible_cuda_devices, - ) - add_function_test( - TestTorch, - "test_warp_graph_torch_stream", - test_warp_graph_torch_stream, - devices=torch_compatible_cuda_devices, - ) +class TestTorch(unittest.TestCase): + pass - # multi-GPU tests - if len(torch_compatible_cuda_devices) > 1: - add_function_test(TestTorch, "test_torch_mgpu_from_torch", test_torch_mgpu_from_torch) - add_function_test(TestTorch, "test_torch_mgpu_to_torch", test_torch_mgpu_to_torch) - add_function_test(TestTorch, "test_torch_mgpu_interop", test_torch_mgpu_interop) - except Exception as e: - print(f"Skipping Torch tests due to exception: {e}") +test_devices = get_test_devices() + +try: + import torch - return TestTorch + # check which Warp devices work with Torch + # CUDA devices may fail if Torch was not compiled with CUDA support + torch_compatible_devices = [] + torch_compatible_cuda_devices = [] + + for d in test_devices: + try: + t = torch.arange(10, device=wp.device_to_torch(d)) + t += 1 + torch_compatible_devices.append(d) + if d.is_cuda: + torch_compatible_cuda_devices.append(d) + except Exception as e: + print(f"Skipping Torch tests on device '{d}' due to exception: {e}") + + if torch_compatible_devices: + add_function_test(TestTorch, "test_from_torch", test_from_torch, devices=torch_compatible_devices) + add_function_test(TestTorch, "test_from_torch_slices", test_from_torch_slices, devices=torch_compatible_devices) + add_function_test( + TestTorch, + "test_from_torch_zero_strides", + test_from_torch_zero_strides, + devices=torch_compatible_devices, + ) + add_function_test(TestTorch, "test_to_torch", test_to_torch, devices=torch_compatible_devices) + add_function_test(TestTorch, "test_torch_zerocopy", test_torch_zerocopy, devices=torch_compatible_devices) + add_function_test(TestTorch, "test_torch_autograd", test_torch_autograd, devices=torch_compatible_devices) + + if torch_compatible_cuda_devices: + add_function_test( + TestTorch, + "test_torch_graph_torch_stream", + test_torch_graph_torch_stream, + devices=torch_compatible_cuda_devices, + ) + add_function_test( + TestTorch, + "test_torch_graph_warp_stream", + test_torch_graph_warp_stream, + devices=torch_compatible_cuda_devices, + ) + add_function_test( + TestTorch, + "test_warp_graph_warp_stream", + test_warp_graph_warp_stream, + devices=torch_compatible_cuda_devices, + ) + add_function_test( + TestTorch, + "test_warp_graph_torch_stream", + test_warp_graph_torch_stream, + devices=torch_compatible_cuda_devices, + ) + + # multi-GPU tests + if len(torch_compatible_cuda_devices) > 1: + add_function_test(TestTorch, "test_torch_mgpu_from_torch", test_torch_mgpu_from_torch) + add_function_test(TestTorch, "test_torch_mgpu_to_torch", test_torch_mgpu_to_torch) + add_function_test(TestTorch, "test_torch_mgpu_interop", test_torch_mgpu_interop) + +except Exception as e: + print(f"Skipping Torch tests due to exception: {e}") if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_transient_module.py b/warp/tests/test_transient_module.py index e35b44ba6..326622c85 100644 --- a/warp/tests/test_transient_module.py +++ b/warp/tests/test_transient_module.py @@ -5,14 +5,13 @@ # distribution of this software and related documentation without an express # license agreement from NVIDIA CORPORATION is strictly prohibited. -import importlib import os import tempfile import unittest +from importlib import util import warp as wp -from warp.tests.test_base import * -from importlib import util +from warp.tests.unittest_utils import * CODE = """# -*- coding: utf-8 -*- @@ -64,27 +63,25 @@ def test_transient_module(test, device): assert len(module.compute.module.functions) == 1 data = module.Data() - data.x = wp.array([123], dtype=int) + data.x = wp.array([123], dtype=int, device=device) wp.set_module_options({"foo": "bar"}, module=module) assert wp.get_module_options(module=module).get("foo") == "bar" assert module.compute.module.options.get("foo") == "bar" - wp.launch(module.compute, dim=1, inputs=[data]) + wp.launch(module.compute, dim=1, inputs=[data], device=device) assert_np_equal(data.x.numpy(), np.array([124])) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() + - class TestTransientModule(parent): - pass +class TestTransientModule(unittest.TestCase): + pass - add_function_test(TestTransientModule, "test_transient_module", test_transient_module, devices=devices) - return TestTransientModule +add_function_test(TestTransientModule, "test_transient_module", test_transient_module, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_types.py b/warp/tests/test_types.py index 450584aa1..bc91c13c2 100644 --- a/warp/tests/test_types.py +++ b/warp/tests/test_types.py @@ -7,397 +7,357 @@ import unittest -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() -def test_constant(test, device): - const = wp.constant(123) - test.assertEqual(const, 123) - - const = wp.constant(1.25) - test.assertEqual(const, 1.25) - - const = wp.constant(True) - test.assertEqual(const, True) - - const = wp.constant(wp.float16(1.25)) - test.assertEqual(const.value, 1.25) - - const = wp.constant(wp.int16(123)) - test.assertEqual(const.value, 123) - - const = wp.constant(wp.vec3i(1, 2, 3)) - test.assertEqual(const, wp.vec3i(1, 2, 3)) - - -def test_constant_error_invalid_type(test, device): - with test.assertRaisesRegex( - RuntimeError, - r"Invalid constant type: $", - ): - wp.constant((1, 2, 3)) - - -def test_vector(test, device, dtype): - def make_scalar(x): - # Cast to the correct integer type to simulate wrapping. - if dtype in wp.types.int_types: - return dtype._type_(x).value - - return x - - def make_vec(*args): - if dtype in wp.types.int_types: - # Cast to the correct integer type to simulate wrapping. - return tuple(dtype._type_(x).value for x in args) - - return args - - vec3_cls = wp.vec(3, dtype) - vec4_cls = wp.vec(4, dtype) - - v = vec4_cls(1, 2, 3, 4) - test.assertEqual(v[0], make_scalar(1)) - test.assertEqual(v.x, make_scalar(1)) - test.assertEqual(v.y, make_scalar(2)) - test.assertEqual(v.z, make_scalar(3)) - test.assertEqual(v.w, make_scalar(4)) - test.assertSequenceEqual(v[0:2], make_vec(1, 2)) - test.assertSequenceEqual(v, make_vec(1, 2, 3, 4)) - - v[0] = -1 - test.assertEqual(v[0], make_scalar(-1)) - test.assertEqual(v.x, make_scalar(-1)) - test.assertEqual(v.y, make_scalar(2)) - test.assertEqual(v.z, make_scalar(3)) - test.assertEqual(v.w, make_scalar(4)) - test.assertSequenceEqual(v[0:2], make_vec(-1, 2)) - test.assertSequenceEqual(v, make_vec(-1, 2, 3, 4)) - - v[1:3] = (-2, -3) - test.assertEqual(v[0], make_scalar(-1)) - test.assertEqual(v.x, make_scalar(-1)) - test.assertEqual(v.y, make_scalar(-2)) - test.assertEqual(v.z, make_scalar(-3)) - test.assertEqual(v.w, make_scalar(4)) - test.assertSequenceEqual(v[0:2], make_vec(-1, -2)) - test.assertSequenceEqual(v, make_vec(-1, -2, -3, 4)) - - v.x = 1 - test.assertEqual(v[0], make_scalar(1)) - test.assertEqual(v.x, make_scalar(1)) - test.assertEqual(v.y, make_scalar(-2)) - test.assertEqual(v.z, make_scalar(-3)) - test.assertEqual(v.w, make_scalar(4)) - test.assertSequenceEqual(v[0:2], make_vec(1, -2)) - test.assertSequenceEqual(v, make_vec(1, -2, -3, 4)) - - v = vec3_cls(2, 4, 6) - test.assertSequenceEqual(+v, make_vec(2, 4, 6)) - test.assertSequenceEqual(-v, make_vec(-2, -4, -6)) - test.assertSequenceEqual(v + vec3_cls(1, 1, 1), make_vec(3, 5, 7)) - test.assertSequenceEqual(v - vec3_cls(1, 1, 1), make_vec(1, 3, 5)) - test.assertSequenceEqual(v * dtype(2), make_vec(4, 8, 12)) - test.assertSequenceEqual(dtype(2) * v, make_vec(4, 8, 12)) - test.assertSequenceEqual(v / dtype(2), make_vec(1, 2, 3)) - test.assertSequenceEqual(dtype(12) / v, make_vec(6, 3, 2)) - - test.assertTrue(v != vec3_cls(1, 2, 3)) - test.assertEqual(str(v), "[{}]".format(", ".join(str(x) for x in v))) - - # Check added purely for coverage reasons but is this really a desired - # behaviour? Not allowing to define new attributes using systems like - # `__slots__` could help improving memory usage. - v.foo = 123 - test.assertEqual(v.foo, 123) - - -def test_vector_error_invalid_arg_count(test, device): - with test.assertRaisesRegex( - ValueError, - r"Invalid number of arguments in vector constructor, expected 3 elements, got 2$", - ): - wp.vec3(1, 2) - - -def test_vector_error_invalid_ptr(test, device): - with test.assertRaisesRegex( - RuntimeError, - r"NULL pointer exception", - ): - wp.vec3.from_ptr(0) - - -def test_vector_error_invalid_get_item_key(test, device): - v = wp.vec3(1, 2, 3) - - with test.assertRaisesRegex( - KeyError, - r"Invalid key None, expected int or slice", - ): - v[None] - - -def test_vector_error_invalid_set_item_key(test, device): - v = wp.vec3(1, 2, 3) - with test.assertRaisesRegex( - KeyError, - r"Invalid key None, expected int or slice", - ): - v[None] = 0 - - -def test_matrix(test, device, dtype): - def make_scalar(x): - # Cast to the correct integer type to simulate wrapping. - if dtype in wp.types.int_types: - return dtype._type_(x).value - - return x - - def make_vec(*args): - if dtype in wp.types.int_types: - # Cast to the correct integer type to simulate wrapping. - return tuple(dtype._type_(x).value for x in args) - - return args - - def make_mat(*args): - if dtype in wp.types.int_types: - # Cast to the correct integer type to simulate wrapping. - return tuple(tuple(dtype._type_(x).value for x in row) for row in args) - - return args - - mat22_cls = wp.mat((2, 2), dtype) - mat33_cls = wp.mat((3, 3), dtype) - vec2_cls = wp.vec(2, dtype) - - m = mat33_cls(((1, 2, 3), (4, 5, 6), (7, 8, 9))) - test.assertEqual(m[0][0], make_scalar(1)) - test.assertEqual(m[0][1], make_scalar(2)) - test.assertEqual(m[0][2], make_scalar(3)) - test.assertEqual(m[1][0], make_scalar(4)) - test.assertEqual(m[1][1], make_scalar(5)) - test.assertEqual(m[1][2], make_scalar(6)) - test.assertEqual(m[2][0], make_scalar(7)) - test.assertEqual(m[2][1], make_scalar(8)) - test.assertEqual(m[2][2], make_scalar(9)) - test.assertEqual(m[0, 0], make_scalar(1)) - test.assertEqual(m[0, 1], make_scalar(2)) - test.assertEqual(m[0, 2], make_scalar(3)) - test.assertEqual(m[1, 0], make_scalar(4)) - test.assertEqual(m[1, 1], make_scalar(5)) - test.assertEqual(m[1, 2], make_scalar(6)) - test.assertEqual(m[2, 0], make_scalar(7)) - test.assertEqual(m[2, 1], make_scalar(8)) - test.assertEqual(m[2, 2], make_scalar(9)) - test.assertSequenceEqual(m[0], make_vec(1, 2, 3)) - test.assertSequenceEqual(m[1], make_vec(4, 5, 6)) - test.assertSequenceEqual(m[2], make_vec(7, 8, 9)) - test.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) - test.assertSequenceEqual(m[1][0:2], make_vec(4, 5)) - test.assertSequenceEqual(m[2][0:3], make_vec(7, 8, 9)) - # test.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) - # test.assertSequenceEqual(m[1, 0:2], make_vec(4, 5)) - # test.assertSequenceEqual(m[2, 0:3], make_vec(7, 8, 9)) - test.assertSequenceEqual(m, make_mat((1, 2, 3), (4, 5, 6), (7, 8, 9))) - - m[1, 0] = -4 - test.assertEqual(m[0][0], make_scalar(1)) - test.assertEqual(m[0][1], make_scalar(2)) - test.assertEqual(m[0][2], make_scalar(3)) - test.assertEqual(m[1][0], make_scalar(-4)) - test.assertEqual(m[1][1], make_scalar(5)) - test.assertEqual(m[1][2], make_scalar(6)) - test.assertEqual(m[2][0], make_scalar(7)) - test.assertEqual(m[2][1], make_scalar(8)) - test.assertEqual(m[2][2], make_scalar(9)) - test.assertEqual(m[0, 0], make_scalar(1)) - test.assertEqual(m[0, 1], make_scalar(2)) - test.assertEqual(m[0, 2], make_scalar(3)) - test.assertEqual(m[1, 0], make_scalar(-4)) - test.assertEqual(m[1, 1], make_scalar(5)) - test.assertEqual(m[1, 2], make_scalar(6)) - test.assertEqual(m[2, 0], make_scalar(7)) - test.assertEqual(m[2, 1], make_scalar(8)) - test.assertEqual(m[2, 2], make_scalar(9)) - test.assertSequenceEqual(m[0], make_vec(1, 2, 3)) - test.assertSequenceEqual(m[1], make_vec(-4, 5, 6)) - test.assertSequenceEqual(m[2], make_vec(7, 8, 9)) - test.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) - test.assertSequenceEqual(m[1][0:2], make_vec(-4, 5)) - test.assertSequenceEqual(m[2][0:3], make_vec(7, 8, 9)) - # test.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) - # test.assertSequenceEqual(m[1, 0:2], make_vec(-4, 5)) - # test.assertSequenceEqual(m[2, 0:3], make_vec(7, 8, 9)) - test.assertSequenceEqual(m, make_mat((1, 2, 3), (-4, 5, 6), (7, 8, 9))) - - m[2] = (-7, 8, -9) - test.assertEqual(m[0][0], make_scalar(1)) - test.assertEqual(m[0][1], make_scalar(2)) - test.assertEqual(m[0][2], make_scalar(3)) - test.assertEqual(m[1][0], make_scalar(-4)) - test.assertEqual(m[1][1], make_scalar(5)) - test.assertEqual(m[1][2], make_scalar(6)) - test.assertEqual(m[2][0], make_scalar(-7)) - test.assertEqual(m[2][1], make_scalar(8)) - test.assertEqual(m[2][2], make_scalar(-9)) - test.assertEqual(m[0, 0], make_scalar(1)) - test.assertEqual(m[0, 1], make_scalar(2)) - test.assertEqual(m[0, 2], make_scalar(3)) - test.assertEqual(m[1, 0], make_scalar(-4)) - test.assertEqual(m[1, 1], make_scalar(5)) - test.assertEqual(m[1, 2], make_scalar(6)) - test.assertEqual(m[2, 0], make_scalar(-7)) - test.assertEqual(m[2, 1], make_scalar(8)) - test.assertEqual(m[2, 2], make_scalar(-9)) - test.assertSequenceEqual(m[0], make_vec(1, 2, 3)) - test.assertSequenceEqual(m[1], make_vec(-4, 5, 6)) - test.assertSequenceEqual(m[2], make_vec(-7, 8, -9)) - test.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) - test.assertSequenceEqual(m[1][0:2], make_vec(-4, 5)) - test.assertSequenceEqual(m[2][0:3], make_vec(-7, 8, -9)) - # test.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) - # test.assertSequenceEqual(m[1, 0:2], make_vec(-4, 5)) - # test.assertSequenceEqual(m[2, 0:3], make_vec(-7, 8, -9)) - test.assertSequenceEqual(m, make_mat((1, 2, 3), (-4, 5, 6), (-7, 8, -9))) - - m = mat22_cls(2, 4, 6, 8) - test.assertSequenceEqual(+m, make_mat((2, 4), (6, 8))) - test.assertSequenceEqual(-m, make_mat((-2, -4), (-6, -8))) - test.assertSequenceEqual(m + mat22_cls(1, 1, 1, 1), make_mat((3, 5), (7, 9))) - test.assertSequenceEqual(m - mat22_cls(1, 1, 1, 1), make_mat((1, 3), (5, 7))) - test.assertSequenceEqual(m * dtype(2), make_mat((4, 8), (12, 16))) - test.assertSequenceEqual(dtype(2) * m, make_mat((4, 8), (12, 16))) - test.assertSequenceEqual(m / dtype(2), make_mat((1, 2), (3, 4))) - test.assertSequenceEqual(dtype(24) / m, make_mat((12, 6), (4, 3))) - - test.assertSequenceEqual(m * vec2_cls(1, 2), make_vec(10, 22)) - test.assertSequenceEqual(m @ vec2_cls(1, 2), make_vec(10, 22)) - test.assertSequenceEqual(vec2_cls(1, 2) * m, make_vec(14, 20)) - test.assertSequenceEqual(vec2_cls(1, 2) @ m, make_vec(14, 20)) - - test.assertTrue(m != mat22_cls(1, 2, 3, 4)) - test.assertEqual( - str(m), "[{}]".format(",\n ".join("[{}]".format(", ".join(str(y) for y in m[x])) for x in range(m._shape_[0]))) - ) - - # Check added purely for coverage reasons but is this really a desired - # behaviour? Not allowing to define new attributes using systems like - # `__slots__` could help improving memory usage. - m.foo = 123 - test.assertEqual(m.foo, 123) - - -def test_matrix_error_invalid_arg_count(test, device): - with test.assertRaisesRegex( - ValueError, - r"Invalid number of arguments in matrix constructor, expected 4 elements, got 3$", - ): - wp.mat22(1, 2, 3) - - -def test_matrix_error_invalid_row_count(test, device): - with test.assertRaisesRegex( - TypeError, - r"Invalid argument in matrix constructor, expected row of length 2, got \(1, 2, 3\)$", - ): - wp.mat22((1, 2, 3), (3, 4, 5)) - - -def test_matrix_error_invalid_ptr(test, device): - with test.assertRaisesRegex( - RuntimeError, - r"NULL pointer exception", - ): - wp.mat22.from_ptr(0) - - -def test_matrix_error_invalid_set_row_index(test, device): - m = wp.mat22(1, 2, 3, 4) - with test.assertRaisesRegex( - IndexError, - r"Invalid row index$", - ): - m.set_row(2, (0, 0)) - - -def test_matrix_error_invalid_get_item_key(test, device): - m = wp.mat22(1, 2, 3, 4) - - with test.assertRaisesRegex( - KeyError, - r"Invalid key None, expected int or pair of ints", - ): - m[None] - - -def test_matrix_error_invalid_get_item_key_length(test, device): - m = wp.mat22(1, 2, 3, 4) - - with test.assertRaisesRegex( - KeyError, - r"Invalid key, expected one or two indices, got 3", - ): - m[0, 1, 2] - - -def test_matrix_error_invalid_set_item_key(test, device): - m = wp.mat22(1, 2, 3, 4) - with test.assertRaisesRegex( - KeyError, - r"Invalid key None, expected int or pair of ints", - ): - m[None] = 0 - - -def test_matrix_error_invalid_set_item_key_length(test, device): - m = wp.mat22(1, 2, 3, 4) - - with test.assertRaisesRegex( - KeyError, - r"Invalid key, expected one or two indices, got 3", - ): - m[0, 1, 2] = (0, 0) - - -def register(parent): - devices = get_test_devices() - - class TestTypes(parent): - pass - - add_function_test(TestTypes, "test_constant", test_constant) - add_function_test(TestTypes, "test_constant_error_invalid_type", test_constant_error_invalid_type) - - for dtype in tuple(wp.types.scalar_types) + (int, float): - add_function_test(TestTypes, f"test_vector_{dtype.__name__}", test_vector, devices=None, dtype=dtype) - - add_function_test(TestTypes, "test_vector_error_invalid_arg_count", test_vector_error_invalid_arg_count) - add_function_test(TestTypes, "test_vector_error_invalid_ptr", test_vector_error_invalid_ptr) - add_function_test(TestTypes, "test_vector_error_invalid_get_item_key", test_vector_error_invalid_get_item_key) - add_function_test(TestTypes, "test_vector_error_invalid_set_item_key", test_vector_error_invalid_set_item_key) - - for dtype in tuple(wp.types.float_types) + (float,): - add_function_test(TestTypes, f"test_matrix_{dtype.__name__}", test_matrix, devices=None, dtype=dtype) - - add_function_test(TestTypes, "test_matrix_error_invalid_arg_count", test_matrix_error_invalid_arg_count) - add_function_test(TestTypes, "test_matrix_error_invalid_row_count", test_matrix_error_invalid_row_count) - add_function_test(TestTypes, "test_matrix_error_invalid_ptr", test_matrix_error_invalid_ptr) - add_function_test(TestTypes, "test_matrix_error_invalid_set_row_index", test_matrix_error_invalid_set_row_index) - add_function_test(TestTypes, "test_matrix_error_invalid_get_item_key", test_matrix_error_invalid_get_item_key) - add_function_test(TestTypes, "test_matrix_error_invalid_get_item_key_length", test_matrix_error_invalid_get_item_key_length) - add_function_test(TestTypes, "test_matrix_error_invalid_set_item_key", test_matrix_error_invalid_set_item_key) - add_function_test(TestTypes, "test_matrix_error_invalid_set_item_key_length", test_matrix_error_invalid_set_item_key_length) - - return TestTypes +devices = get_test_devices() + + +class TestTypes(unittest.TestCase): + def test_constant(self): + const = wp.constant(123) + self.assertEqual(const, 123) + + const = wp.constant(1.25) + self.assertEqual(const, 1.25) + + const = wp.constant(True) + self.assertEqual(const, True) + + const = wp.constant(wp.float16(1.25)) + self.assertEqual(const.value, 1.25) + + const = wp.constant(wp.int16(123)) + self.assertEqual(const.value, 123) + + const = wp.constant(wp.vec3i(1, 2, 3)) + self.assertEqual(const, wp.vec3i(1, 2, 3)) + + def test_constant_error_invalid_type(self): + with self.assertRaisesRegex( + RuntimeError, + r"Invalid constant type: $", + ): + wp.constant((1, 2, 3)) + + def test_vector(self): + for dtype in tuple(wp.types.scalar_types) + (int, float): + + def make_scalar(x): + # Cast to the correct integer type to simulate wrapping. + if dtype in wp.types.int_types: + return dtype._type_(x).value + + return x + + def make_vec(*args): + if dtype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(dtype._type_(x).value for x in args) + + return args + + vec3_cls = wp.vec(3, dtype) + vec4_cls = wp.vec(4, dtype) + + v = vec4_cls(1, 2, 3, 4) + self.assertEqual(v[0], make_scalar(1)) + self.assertEqual(v.x, make_scalar(1)) + self.assertEqual(v.y, make_scalar(2)) + self.assertEqual(v.z, make_scalar(3)) + self.assertEqual(v.w, make_scalar(4)) + self.assertSequenceEqual(v[0:2], make_vec(1, 2)) + self.assertSequenceEqual(v, make_vec(1, 2, 3, 4)) + + v[0] = -1 + self.assertEqual(v[0], make_scalar(-1)) + self.assertEqual(v.x, make_scalar(-1)) + self.assertEqual(v.y, make_scalar(2)) + self.assertEqual(v.z, make_scalar(3)) + self.assertEqual(v.w, make_scalar(4)) + self.assertSequenceEqual(v[0:2], make_vec(-1, 2)) + self.assertSequenceEqual(v, make_vec(-1, 2, 3, 4)) + + v[1:3] = (-2, -3) + self.assertEqual(v[0], make_scalar(-1)) + self.assertEqual(v.x, make_scalar(-1)) + self.assertEqual(v.y, make_scalar(-2)) + self.assertEqual(v.z, make_scalar(-3)) + self.assertEqual(v.w, make_scalar(4)) + self.assertSequenceEqual(v[0:2], make_vec(-1, -2)) + self.assertSequenceEqual(v, make_vec(-1, -2, -3, 4)) + + v.x = 1 + self.assertEqual(v[0], make_scalar(1)) + self.assertEqual(v.x, make_scalar(1)) + self.assertEqual(v.y, make_scalar(-2)) + self.assertEqual(v.z, make_scalar(-3)) + self.assertEqual(v.w, make_scalar(4)) + self.assertSequenceEqual(v[0:2], make_vec(1, -2)) + self.assertSequenceEqual(v, make_vec(1, -2, -3, 4)) + + v = vec3_cls(2, 4, 6) + self.assertSequenceEqual(+v, make_vec(2, 4, 6)) + self.assertSequenceEqual(-v, make_vec(-2, -4, -6)) + self.assertSequenceEqual(v + vec3_cls(1, 1, 1), make_vec(3, 5, 7)) + self.assertSequenceEqual(v - vec3_cls(1, 1, 1), make_vec(1, 3, 5)) + self.assertSequenceEqual(v * dtype(2), make_vec(4, 8, 12)) + self.assertSequenceEqual(dtype(2) * v, make_vec(4, 8, 12)) + self.assertSequenceEqual(v / dtype(2), make_vec(1, 2, 3)) + self.assertSequenceEqual(dtype(12) / v, make_vec(6, 3, 2)) + + self.assertTrue(v != vec3_cls(1, 2, 3)) + self.assertEqual(str(v), "[{}]".format(", ".join(str(x) for x in v))) + + # Check added purely for coverage reasons but is this really a desired + # behaviour? Not allowing to define new attributes using systems like + # `__slots__` could help improving memory usage. + v.foo = 123 + self.assertEqual(v.foo, 123) + + def test_vector_error_invalid_arg_count(self): + with self.assertRaisesRegex( + ValueError, + r"Invalid number of arguments in vector constructor, expected 3 elements, got 2$", + ): + wp.vec3(1, 2) + + def test_vector_error_invalid_ptr(self): + with self.assertRaisesRegex( + RuntimeError, + r"NULL pointer exception", + ): + wp.vec3.from_ptr(0) + + def test_vector_error_invalid_get_item_key(self): + v = wp.vec3(1, 2, 3) + + with self.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or slice", + ): + v[None] + + def test_vector_error_invalid_set_item_key(self): + v = wp.vec3(1, 2, 3) + with self.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or slice", + ): + v[None] = 0 + + def test_matrix(self): + for dtype in tuple(wp.types.float_types) + (float,): + + def make_scalar(x): + # Cast to the correct integer type to simulate wrapping. + if dtype in wp.types.int_types: + return dtype._type_(x).value + + return x + + def make_vec(*args): + if dtype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(dtype._type_(x).value for x in args) + + return args + + def make_mat(*args): + if dtype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(tuple(dtype._type_(x).value for x in row) for row in args) + + return args + + mat22_cls = wp.mat((2, 2), dtype) + mat33_cls = wp.mat((3, 3), dtype) + vec2_cls = wp.vec(2, dtype) + + m = mat33_cls(((1, 2, 3), (4, 5, 6), (7, 8, 9))) + self.assertEqual(m[0][0], make_scalar(1)) + self.assertEqual(m[0][1], make_scalar(2)) + self.assertEqual(m[0][2], make_scalar(3)) + self.assertEqual(m[1][0], make_scalar(4)) + self.assertEqual(m[1][1], make_scalar(5)) + self.assertEqual(m[1][2], make_scalar(6)) + self.assertEqual(m[2][0], make_scalar(7)) + self.assertEqual(m[2][1], make_scalar(8)) + self.assertEqual(m[2][2], make_scalar(9)) + self.assertEqual(m[0, 0], make_scalar(1)) + self.assertEqual(m[0, 1], make_scalar(2)) + self.assertEqual(m[0, 2], make_scalar(3)) + self.assertEqual(m[1, 0], make_scalar(4)) + self.assertEqual(m[1, 1], make_scalar(5)) + self.assertEqual(m[1, 2], make_scalar(6)) + self.assertEqual(m[2, 0], make_scalar(7)) + self.assertEqual(m[2, 1], make_scalar(8)) + self.assertEqual(m[2, 2], make_scalar(9)) + self.assertSequenceEqual(m[0], make_vec(1, 2, 3)) + self.assertSequenceEqual(m[1], make_vec(4, 5, 6)) + self.assertSequenceEqual(m[2], make_vec(7, 8, 9)) + self.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) + self.assertSequenceEqual(m[1][0:2], make_vec(4, 5)) + self.assertSequenceEqual(m[2][0:3], make_vec(7, 8, 9)) + # self.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) + # self.assertSequenceEqual(m[1, 0:2], make_vec(4, 5)) + # self.assertSequenceEqual(m[2, 0:3], make_vec(7, 8, 9)) + self.assertSequenceEqual(m, make_mat((1, 2, 3), (4, 5, 6), (7, 8, 9))) + + m[1, 0] = -4 + self.assertEqual(m[0][0], make_scalar(1)) + self.assertEqual(m[0][1], make_scalar(2)) + self.assertEqual(m[0][2], make_scalar(3)) + self.assertEqual(m[1][0], make_scalar(-4)) + self.assertEqual(m[1][1], make_scalar(5)) + self.assertEqual(m[1][2], make_scalar(6)) + self.assertEqual(m[2][0], make_scalar(7)) + self.assertEqual(m[2][1], make_scalar(8)) + self.assertEqual(m[2][2], make_scalar(9)) + self.assertEqual(m[0, 0], make_scalar(1)) + self.assertEqual(m[0, 1], make_scalar(2)) + self.assertEqual(m[0, 2], make_scalar(3)) + self.assertEqual(m[1, 0], make_scalar(-4)) + self.assertEqual(m[1, 1], make_scalar(5)) + self.assertEqual(m[1, 2], make_scalar(6)) + self.assertEqual(m[2, 0], make_scalar(7)) + self.assertEqual(m[2, 1], make_scalar(8)) + self.assertEqual(m[2, 2], make_scalar(9)) + self.assertSequenceEqual(m[0], make_vec(1, 2, 3)) + self.assertSequenceEqual(m[1], make_vec(-4, 5, 6)) + self.assertSequenceEqual(m[2], make_vec(7, 8, 9)) + self.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) + self.assertSequenceEqual(m[1][0:2], make_vec(-4, 5)) + self.assertSequenceEqual(m[2][0:3], make_vec(7, 8, 9)) + # self.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) + # self.assertSequenceEqual(m[1, 0:2], make_vec(-4, 5)) + # self.assertSequenceEqual(m[2, 0:3], make_vec(7, 8, 9)) + self.assertSequenceEqual(m, make_mat((1, 2, 3), (-4, 5, 6), (7, 8, 9))) + + m[2] = (-7, 8, -9) + self.assertEqual(m[0][0], make_scalar(1)) + self.assertEqual(m[0][1], make_scalar(2)) + self.assertEqual(m[0][2], make_scalar(3)) + self.assertEqual(m[1][0], make_scalar(-4)) + self.assertEqual(m[1][1], make_scalar(5)) + self.assertEqual(m[1][2], make_scalar(6)) + self.assertEqual(m[2][0], make_scalar(-7)) + self.assertEqual(m[2][1], make_scalar(8)) + self.assertEqual(m[2][2], make_scalar(-9)) + self.assertEqual(m[0, 0], make_scalar(1)) + self.assertEqual(m[0, 1], make_scalar(2)) + self.assertEqual(m[0, 2], make_scalar(3)) + self.assertEqual(m[1, 0], make_scalar(-4)) + self.assertEqual(m[1, 1], make_scalar(5)) + self.assertEqual(m[1, 2], make_scalar(6)) + self.assertEqual(m[2, 0], make_scalar(-7)) + self.assertEqual(m[2, 1], make_scalar(8)) + self.assertEqual(m[2, 2], make_scalar(-9)) + self.assertSequenceEqual(m[0], make_vec(1, 2, 3)) + self.assertSequenceEqual(m[1], make_vec(-4, 5, 6)) + self.assertSequenceEqual(m[2], make_vec(-7, 8, -9)) + self.assertSequenceEqual(m[0][1:3], make_vec(2, 3)) + self.assertSequenceEqual(m[1][0:2], make_vec(-4, 5)) + self.assertSequenceEqual(m[2][0:3], make_vec(-7, 8, -9)) + # self.assertSequenceEqual(m[0, 1:3], make_vec(2, 3)) + # self.assertSequenceEqual(m[1, 0:2], make_vec(-4, 5)) + # self.assertSequenceEqual(m[2, 0:3], make_vec(-7, 8, -9)) + self.assertSequenceEqual(m, make_mat((1, 2, 3), (-4, 5, 6), (-7, 8, -9))) + + m = mat22_cls(2, 4, 6, 8) + self.assertSequenceEqual(+m, make_mat((2, 4), (6, 8))) + self.assertSequenceEqual(-m, make_mat((-2, -4), (-6, -8))) + self.assertSequenceEqual(m + mat22_cls(1, 1, 1, 1), make_mat((3, 5), (7, 9))) + self.assertSequenceEqual(m - mat22_cls(1, 1, 1, 1), make_mat((1, 3), (5, 7))) + self.assertSequenceEqual(m * dtype(2), make_mat((4, 8), (12, 16))) + self.assertSequenceEqual(dtype(2) * m, make_mat((4, 8), (12, 16))) + self.assertSequenceEqual(m / dtype(2), make_mat((1, 2), (3, 4))) + self.assertSequenceEqual(dtype(24) / m, make_mat((12, 6), (4, 3))) + + self.assertSequenceEqual(m * vec2_cls(1, 2), make_vec(10, 22)) + self.assertSequenceEqual(m @ vec2_cls(1, 2), make_vec(10, 22)) + self.assertSequenceEqual(vec2_cls(1, 2) * m, make_vec(14, 20)) + self.assertSequenceEqual(vec2_cls(1, 2) @ m, make_vec(14, 20)) + + self.assertTrue(m != mat22_cls(1, 2, 3, 4)) + self.assertEqual( + str(m), + "[{}]".format(",\n ".join("[{}]".format(", ".join(str(y) for y in m[x])) for x in range(m._shape_[0]))), + ) + + # Check added purely for coverage reasons but is this really a desired + # behaviour? Not allowing to define new attributes using systems like + # `__slots__` could help improving memory usage. + m.foo = 123 + self.assertEqual(m.foo, 123) + + def test_matrix_error_invalid_arg_count(self): + with self.assertRaisesRegex( + ValueError, + r"Invalid number of arguments in matrix constructor, expected 4 elements, got 3$", + ): + wp.mat22(1, 2, 3) + + def test_matrix_error_invalid_row_count(self): + with self.assertRaisesRegex( + TypeError, + r"Invalid argument in matrix constructor, expected row of length 2, got \(1, 2, 3\)$", + ): + wp.mat22((1, 2, 3), (3, 4, 5)) + + def test_matrix_error_invalid_ptr(self): + with self.assertRaisesRegex( + RuntimeError, + r"NULL pointer exception", + ): + wp.mat22.from_ptr(0) + + def test_matrix_error_invalid_set_row_index(self): + m = wp.mat22(1, 2, 3, 4) + with self.assertRaisesRegex( + IndexError, + r"Invalid row index$", + ): + m.set_row(2, (0, 0)) + + def test_matrix_error_invalid_get_item_key(self): + m = wp.mat22(1, 2, 3, 4) + + with self.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or pair of ints", + ): + m[None] + + def test_matrix_error_invalid_get_item_key_length(self): + m = wp.mat22(1, 2, 3, 4) + + with self.assertRaisesRegex( + KeyError, + r"Invalid key, expected one or two indices, got 3", + ): + m[0, 1, 2] + + def test_matrix_error_invalid_set_item_key(self): + m = wp.mat22(1, 2, 3, 4) + with self.assertRaisesRegex( + KeyError, + r"Invalid key None, expected int or pair of ints", + ): + m[None] = 0 + + def test_matrix_error_invalid_set_item_key_length(self): + m = wp.mat22(1, 2, 3, 4) + + with self.assertRaisesRegex( + KeyError, + r"Invalid key, expected one or two indices, got 3", + ): + m[0, 1, 2] = (0, 0) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_unresolved_func.py b/warp/tests/test_unresolved_func.py deleted file mode 100644 index 8122be812..000000000 --- a/warp/tests/test_unresolved_func.py +++ /dev/null @@ -1,7 +0,0 @@ -import warp as wp - - -@wp.kernel -def unresolved_func_kernel(): - # this should trigger an exception due to unresolved function - x = wp.missing_func(42) diff --git a/warp/tests/test_unresolved_symbol.py b/warp/tests/test_unresolved_symbol.py deleted file mode 100644 index ce2aa241e..000000000 --- a/warp/tests/test_unresolved_symbol.py +++ /dev/null @@ -1,7 +0,0 @@ -import warp as wp - - -@wp.kernel -def unresolved_symbol_kernel(): - # this should trigger an exception due to unresolved symbol - x = missing_symbol diff --git a/warp/tests/test_utils.py b/warp/tests/test_utils.py index 7bc5ca869..19ea4469e 100644 --- a/warp/tests/test_utils.py +++ b/warp/tests/test_utils.py @@ -6,36 +6,15 @@ # license agreement from NVIDIA CORPORATION is strictly prohibited. import contextlib -import io import inspect +import io import unittest -from warp.tests.test_base import * - +from warp.tests.unittest_utils import * wp.init() -def test_warn(test, device): - with contextlib.redirect_stdout(io.StringIO()) as f: - frame_info = inspect.getframeinfo(inspect.currentframe()) - wp.utils.warn("hello, world!") - - expected = '{}:{}: UserWarning: hello, world!\n wp.utils.warn("hello, world!")\n'.format( - frame_info.filename, - frame_info.lineno + 1, - ) - test.assertEqual(f.getvalue(), expected) - - -def test_transform_expand(test, device): - t = (1.0, 2.0, 3.0, 4.0, 3.0, 2.0, 1.0) - test.assertEqual( - wp.utils.transform_expand(t), - wp.transformf(p=(1.0, 2.0, 3.0), q=(4.0, 3.0, 2.0, 1.0)), - ) - - def test_array_scan(test, device): rng = np.random.default_rng(123) @@ -71,19 +50,9 @@ def test_array_scan_empty(test, device): wp.utils.array_scan(values, result) -def test_array_scan_error_devices_mismatch(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - result = wp.zeros_like(values, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"Array storage devices do not match$", - ): - wp.utils.array_scan(values, result, True) - - def test_array_scan_error_sizes_mismatch(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - result = wp.zeros(234, dtype=int, device="cpu") + values = wp.zeros(123, dtype=int, device=device) + result = wp.zeros(234, dtype=int, device=device) with test.assertRaisesRegex( RuntimeError, r"Array storage sizes do not match$", @@ -92,8 +61,8 @@ def test_array_scan_error_sizes_mismatch(test, device): def test_array_scan_error_dtypes_mismatch(test, device): - values = wp.zeros(123, dtype=int, device="cpu") - result = wp.zeros(123, dtype=float, device="cpu") + values = wp.zeros(123, dtype=int, device=device) + result = wp.zeros(123, dtype=float, device=device) with test.assertRaisesRegex( RuntimeError, r"Array data types do not match$", @@ -125,19 +94,9 @@ def test_radix_sort_pairs_empty(test, device): wp.utils.radix_sort_pairs(keys, values, 0) -def test_radix_sort_pairs_error_devices_mismatch(test, device): - keys = wp.array((1, 2, 3), dtype=int, device="cpu") - values = wp.array((1, 2, 3), dtype=int, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"Array storage devices do not match$", - ): - wp.utils.radix_sort_pairs(keys, values, 1) - - def test_radix_sort_pairs_error_insufficient_storage(test, device): - keys = wp.array((1, 2, 3), dtype=int, device="cpu") - values = wp.array((1, 2, 3), dtype=int, device="cpu") + keys = wp.array((1, 2, 3), dtype=int, device=device) + values = wp.array((1, 2, 3), dtype=int, device=device) with test.assertRaisesRegex( RuntimeError, r"Array storage must be large enough to contain 2\*count elements$", @@ -157,28 +116,19 @@ def test_radix_sort_pairs_error_unsupported_dtype(test, device): def test_array_sum(test, device): for dtype in (wp.float32, wp.float64): - values = wp.array((1.0, 2.0, 3.0), dtype=dtype, device=device) - test.assertEqual(wp.utils.array_sum(values), 6.0) - - values = wp.array((1.0, 2.0, 3.0), dtype=dtype, device=device) - result = wp.empty(shape=(1,), dtype=dtype, device=device) - wp.utils.array_sum(values, out=result) - test.assertEqual(result.numpy()[0], 6.0) - + with test.subTest(dtype=dtype): + values = wp.array((1.0, 2.0, 3.0), dtype=dtype, device=device) + test.assertEqual(wp.utils.array_sum(values), 6.0) -def test_array_sum_error_out_device_mismatch(test, device): - values = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - result = wp.empty(shape=(1,), dtype=wp.float32, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"out storage device should match values array$", - ): - wp.utils.array_sum(values, out=result) + values = wp.array((1.0, 2.0, 3.0), dtype=dtype, device=device) + result = wp.empty(shape=(1,), dtype=dtype, device=device) + wp.utils.array_sum(values, out=result) + test.assertEqual(result.numpy()[0], 6.0) def test_array_sum_error_out_dtype_mismatch(test, device): - values = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - result = wp.empty(shape=(1,), dtype=wp.float64, device="cpu") + values = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) + result = wp.empty(shape=(1,), dtype=wp.float64, device=device) with test.assertRaisesRegex( RuntimeError, r"out array should have type float32$", @@ -187,8 +137,8 @@ def test_array_sum_error_out_dtype_mismatch(test, device): def test_array_sum_error_out_shape_mismatch(test, device): - values = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - result = wp.empty(shape=(2,), dtype=wp.float32, device="cpu") + values = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) + result = wp.empty(shape=(2,), dtype=wp.float32, device=device) with test.assertRaisesRegex( RuntimeError, r"out array should have shape \(1,\)$", @@ -219,8 +169,8 @@ def test_array_inner(test, device): def test_array_inner_error_sizes_mismatch(test, device): - a = wp.array((1.0, 2.0), dtype=wp.float32, device="cpu") - b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") + a = wp.array((1.0, 2.0), dtype=wp.float32, device=device) + b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) with test.assertRaisesRegex( RuntimeError, r"Array storage sizes do not match$", @@ -228,19 +178,9 @@ def test_array_inner_error_sizes_mismatch(test, device): wp.utils.array_inner(a, b) -def test_array_inner_error_devices_mismatch(test, device): - a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"Array storage devices do not match$", - ): - wp.utils.array_inner(a, b) - - def test_array_inner_error_dtypes_mismatch(test, device): - a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - b = wp.array((1.0, 2.0, 3.0), dtype=wp.float64, device="cpu") + a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) + b = wp.array((1.0, 2.0, 3.0), dtype=wp.float64, device=device) with test.assertRaisesRegex( RuntimeError, r"Array data types do not match$", @@ -248,21 +188,10 @@ def test_array_inner_error_dtypes_mismatch(test, device): wp.utils.array_inner(a, b) -def test_array_inner_error_out_device_mismatch(test, device): - a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - result = wp.empty(shape=(1,), dtype=wp.float32, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"out storage device should match values array$", - ): - wp.utils.array_inner(a, b, result) - - def test_array_inner_error_out_dtype_mismatch(test, device): - a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - result = wp.empty(shape=(1,), dtype=wp.float64, device="cpu") + a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) + b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) + result = wp.empty(shape=(1,), dtype=wp.float64, device=device) with test.assertRaisesRegex( RuntimeError, r"out array should have type float32$", @@ -271,9 +200,9 @@ def test_array_inner_error_out_dtype_mismatch(test, device): def test_array_inner_error_out_shape_mismatch(test, device): - a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") - result = wp.empty(shape=(2,), dtype=wp.float32, device="cpu") + a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) + b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device=device) + result = wp.empty(shape=(2,), dtype=wp.float32, device=device) with test.assertRaisesRegex( RuntimeError, r"out array should have shape \(1,\)$", @@ -313,27 +242,17 @@ def test_array_cast(test, device): test.assertEqual(result.shape, (2,)) assert_np_equal(result.numpy(), np.array((1.0, 2.0), dtype=float)) - values = wp.array(((1, 2), (3, 4)), dtype=int, device="cpu") - result = wp.zeros((2, 2), dtype=int, device="cpu") + values = wp.array(((1, 2), (3, 4)), dtype=int, device=device) + result = wp.zeros((2, 2), dtype=int, device=device) wp.utils.array_cast(values, result) test.assertEqual(result.dtype, wp.int32) test.assertEqual(result.shape, (2, 2)) assert_np_equal(result.numpy(), np.array(((1, 2), (3, 4)), dtype=int)) -def test_array_cast_error_devices_mismatch(test, device): - values = wp.array((1, 2, 3), dtype=int, device="cpu") - result = wp.empty(3, dtype=float, device="cuda:0") - with test.assertRaisesRegex( - RuntimeError, - r"Array storage devices do not match$", - ): - wp.utils.array_cast(values, result) - - def test_array_cast_error_unsupported_partial_cast(test, device): - values = wp.array(((1, 2), (3, 4)), dtype=int, device="cpu") - result = wp.zeros((2, 2), dtype=float, device="cpu") + values = wp.array(((1, 2), (3, 4)), dtype=int, device=device) + result = wp.zeros((2, 2), dtype=float, device=device) with test.assertRaisesRegex( RuntimeError, r"Partial cast is not supported for arrays with more than one dimension$", @@ -341,112 +260,192 @@ def test_array_cast_error_unsupported_partial_cast(test, device): wp.utils.array_cast(values, result, count=1) -def test_mesh_adjacency(test, device): - triangles = ( - (0, 3, 1), - (0, 2, 3), - ) - adj = wp.utils.MeshAdjacency(triangles, len(triangles)) - expected_edges = { - (0, 3): (0, 3, 1, 2, 0, 1), - (1, 3): (3, 1, 0, -1, 0, -1), - (0, 1): (1, 0, 3, -1, 0, -1), - (0, 2): (0, 2, 3, -1, 1, -1), - (2, 3): (2, 3, 0, -1, 1, -1), - } - edges = {k: (e.v0, e.v1, e.o0, e.o1, e.f0, e.f1) for k, e in adj.edges.items()} - test.assertDictEqual(edges, expected_edges) - - -def test_mesh_adjacency_error_manifold(test, device): - triangles = ( - (0, 3, 1), - (0, 2, 3), - (3, 0, 1), - ) - - with contextlib.redirect_stdout(io.StringIO()) as f: - wp.utils.MeshAdjacency(triangles, len(triangles)) - - test.assertEqual(f.getvalue(), "Detected non-manifold edge\n") - - -def test_scoped_timer(test, device): - with contextlib.redirect_stdout(io.StringIO()) as f: - with wp.ScopedTimer("hello"): - pass - - test.assertRegex(f.getvalue(), r"^hello took \d+\.\d+ ms$") - - with contextlib.redirect_stdout(io.StringIO()) as f: - with wp.ScopedTimer("hello", detailed=True): - pass - - test.assertRegex(f.getvalue(), r"^ 2 function calls in \d+\.\d+ seconds") - test.assertRegex(f.getvalue(), r"hello took \d+\.\d+ ms$") - - -def register(parent): - devices = get_test_devices() - - class TestUtils(parent): - pass - - add_function_test(TestUtils, "test_warn", test_warn) - add_function_test(TestUtils, "test_transform_expand", test_transform_expand) - add_function_test(TestUtils, "test_array_scan", test_array_scan, devices=devices) - add_function_test(TestUtils, "test_array_scan_empty", test_array_scan_empty, devices=devices) - add_function_test(TestUtils, "test_array_scan_error_devices_mismatch", test_array_scan_error_devices_mismatch) - add_function_test(TestUtils, "test_array_scan_error_sizes_mismatch", test_array_scan_error_sizes_mismatch) - add_function_test(TestUtils, "test_array_scan_error_dtypes_mismatch", test_array_scan_error_dtypes_mismatch) - add_function_test( - TestUtils, "test_array_scan_error_unsupported_dtype", test_array_scan_error_unsupported_dtype, devices=devices - ) - add_function_test(TestUtils, "test_radix_sort_pairs", test_radix_sort_pairs, devices=devices) - add_function_test(TestUtils, "test_radix_sort_pairs_empty", test_radix_sort_pairs_empty, devices=devices) - add_function_test( - TestUtils, "test_radix_sort_pairs_error_devices_mismatch", test_radix_sort_pairs_error_devices_mismatch - ) - add_function_test( - TestUtils, "test_radix_sort_pairs_error_insufficient_storage", test_radix_sort_pairs_error_insufficient_storage - ) - add_function_test( - TestUtils, - "test_radix_sort_pairs_error_unsupported_dtype", - test_radix_sort_pairs_error_unsupported_dtype, - devices=devices, - ) - add_function_test(TestUtils, "test_array_sum", test_array_sum, devices=devices) - add_function_test(TestUtils, "test_array_sum_error_out_device_mismatch", test_array_sum_error_out_device_mismatch) - add_function_test(TestUtils, "test_array_sum_error_out_dtype_mismatch", test_array_sum_error_out_dtype_mismatch) - add_function_test(TestUtils, "test_array_sum_error_out_shape_mismatch", test_array_sum_error_out_shape_mismatch) - add_function_test( - TestUtils, "test_array_sum_error_unsupported_dtype", test_array_sum_error_unsupported_dtype, devices=devices - ) - add_function_test(TestUtils, "test_array_inner", test_array_inner, devices=devices) - add_function_test(TestUtils, "test_array_inner_error_sizes_mismatch", test_array_inner_error_sizes_mismatch) - add_function_test(TestUtils, "test_array_inner_error_devices_mismatch", test_array_inner_error_devices_mismatch) - add_function_test(TestUtils, "test_array_inner_error_dtypes_mismatch", test_array_inner_error_dtypes_mismatch) - add_function_test( - TestUtils, "test_array_inner_error_out_device_mismatch", test_array_inner_error_out_device_mismatch - ) - add_function_test(TestUtils, "test_array_inner_error_out_dtype_mismatch", test_array_inner_error_out_dtype_mismatch) - add_function_test(TestUtils, "test_array_inner_error_out_shape_mismatch", test_array_inner_error_out_shape_mismatch) - add_function_test( - TestUtils, "test_array_inner_error_unsupported_dtype", test_array_inner_error_unsupported_dtype, devices=devices - ) - add_function_test(TestUtils, "test_array_cast", test_array_cast, devices=devices) - add_function_test(TestUtils, "test_array_cast_error_devices_mismatch", test_array_cast_error_devices_mismatch) - add_function_test( - TestUtils, "test_array_cast_error_unsupported_partial_cast", test_array_cast_error_unsupported_partial_cast - ) - add_function_test(TestUtils, "test_mesh_adjacency", test_mesh_adjacency) - add_function_test(TestUtils, "test_mesh_adjacency_error_manifold", test_mesh_adjacency_error_manifold) - add_function_test(TestUtils, "test_scoped_timer", test_scoped_timer) - return TestUtils +devices = get_test_devices() + + +class TestUtils(unittest.TestCase): + def test_warn(self): + with contextlib.redirect_stdout(io.StringIO()) as f: + frame_info = inspect.getframeinfo(inspect.currentframe()) + wp.utils.warn("hello, world!") + + expected = '{}:{}: UserWarning: hello, world!\n wp.utils.warn("hello, world!")\n'.format( + frame_info.filename, + frame_info.lineno + 1, + ) + self.assertEqual(f.getvalue(), expected) + + def test_transform_expand(self): + t = (1.0, 2.0, 3.0, 4.0, 3.0, 2.0, 1.0) + self.assertEqual( + wp.utils.transform_expand(t), + wp.transformf(p=(1.0, 2.0, 3.0), q=(4.0, 3.0, 2.0, 1.0)), + ) + + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_array_scan_error_devices_mismatch(self): + values = wp.zeros(123, dtype=int, device="cpu") + result = wp.zeros_like(values, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"Array storage devices do not match$", + ): + wp.utils.array_scan(values, result, True) + + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_radix_sort_pairs_error_devices_mismatch(self): + keys = wp.array((1, 2, 3), dtype=int, device="cpu") + values = wp.array((1, 2, 3), dtype=int, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"Array storage devices do not match$", + ): + wp.utils.radix_sort_pairs(keys, values, 1) + + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_array_inner_error_out_device_mismatch(self): + a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") + b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") + result = wp.empty(shape=(1,), dtype=wp.float32, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"out storage device should match values array$", + ): + wp.utils.array_inner(a, b, result) + + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_array_sum_error_out_device_mismatch(self): + values = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") + result = wp.empty(shape=(1,), dtype=wp.float32, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"out storage device should match values array$", + ): + wp.utils.array_sum(values, out=result) + + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_array_inner_error_devices_mismatch(self): + a = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cpu") + b = wp.array((1.0, 2.0, 3.0), dtype=wp.float32, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"Array storage devices do not match$", + ): + wp.utils.array_inner(a, b) + + @unittest.skipUnless(wp.is_cuda_available(), "Requires CUDA") + def test_array_cast_error_devices_mismatch(self): + values = wp.array((1, 2, 3), dtype=int, device="cpu") + result = wp.empty(3, dtype=float, device="cuda:0") + with self.assertRaisesRegex( + RuntimeError, + r"Array storage devices do not match$", + ): + wp.utils.array_cast(values, result) + + def test_mesh_adjacency(self): + triangles = ( + (0, 3, 1), + (0, 2, 3), + ) + adj = wp.utils.MeshAdjacency(triangles, len(triangles)) + expected_edges = { + (0, 3): (0, 3, 1, 2, 0, 1), + (1, 3): (3, 1, 0, -1, 0, -1), + (0, 1): (1, 0, 3, -1, 0, -1), + (0, 2): (0, 2, 3, -1, 1, -1), + (2, 3): (2, 3, 0, -1, 1, -1), + } + edges = {k: (e.v0, e.v1, e.o0, e.o1, e.f0, e.f1) for k, e in adj.edges.items()} + self.assertDictEqual(edges, expected_edges) + + def test_mesh_adjacency_error_manifold(self): + triangles = ( + (0, 3, 1), + (0, 2, 3), + (3, 0, 1), + ) + + with contextlib.redirect_stdout(io.StringIO()) as f: + wp.utils.MeshAdjacency(triangles, len(triangles)) + + self.assertEqual(f.getvalue(), "Detected non-manifold edge\n") + + def test_scoped_timer(self): + with contextlib.redirect_stdout(io.StringIO()) as f: + with wp.ScopedTimer("hello"): + pass + + self.assertRegex(f.getvalue(), r"^hello took \d+\.\d+ ms$") + + with contextlib.redirect_stdout(io.StringIO()) as f: + with wp.ScopedTimer("hello", detailed=True): + pass + + self.assertRegex(f.getvalue(), r"^ 2 function calls in \d+\.\d+ seconds") + self.assertRegex(f.getvalue(), r"hello took \d+\.\d+ ms$") + + +add_function_test(TestUtils, "test_array_scan", test_array_scan, devices=devices) +add_function_test(TestUtils, "test_array_scan_empty", test_array_scan_empty, devices=devices) +add_function_test( + TestUtils, "test_array_scan_error_sizes_mismatch", test_array_scan_error_sizes_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_scan_error_dtypes_mismatch", test_array_scan_error_dtypes_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_scan_error_unsupported_dtype", test_array_scan_error_unsupported_dtype, devices=devices +) +add_function_test(TestUtils, "test_radix_sort_pairs", test_radix_sort_pairs, devices=devices) +add_function_test(TestUtils, "test_radix_sort_pairs_empty", test_radix_sort_pairs, devices=devices) +add_function_test( + TestUtils, + "test_radix_sort_pairs_error_insufficient_storage", + test_radix_sort_pairs_error_insufficient_storage, + devices=devices, +) +add_function_test( + TestUtils, + "test_radix_sort_pairs_error_unsupported_dtype", + test_radix_sort_pairs_error_unsupported_dtype, + devices=devices, +) +add_function_test(TestUtils, "test_array_sum", test_array_sum, devices=devices) +add_function_test( + TestUtils, "test_array_sum_error_out_dtype_mismatch", test_array_sum_error_out_dtype_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_sum_error_out_shape_mismatch", test_array_sum_error_out_shape_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_sum_error_unsupported_dtype", test_array_sum_error_unsupported_dtype, devices=devices +) +add_function_test(TestUtils, "test_array_inner", test_array_inner, devices=devices) +add_function_test( + TestUtils, "test_array_inner_error_sizes_mismatch", test_array_inner_error_sizes_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_inner_error_dtypes_mismatch", test_array_inner_error_dtypes_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_inner_error_out_dtype_mismatch", test_array_inner_error_out_dtype_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_inner_error_out_shape_mismatch", test_array_inner_error_out_shape_mismatch, devices=devices +) +add_function_test( + TestUtils, "test_array_inner_error_unsupported_dtype", test_array_inner_error_unsupported_dtype, devices=devices +) +add_function_test(TestUtils, "test_array_cast", test_array_cast, devices=devices) +add_function_test( + TestUtils, + "test_array_cast_error_unsupported_partial_cast", + test_array_cast_error_unsupported_partial_cast, + devices=devices, +) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_vec.py b/warp/tests/test_vec.py index 88f5d9d2d..dd6ba4e2b 100644 --- a/warp/tests/test_vec.py +++ b/warp/tests/test_vec.py @@ -8,8 +8,9 @@ import unittest import numpy as np + import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -29,12 +30,8 @@ np.ubyte, ] -np_int_types = np_signed_int_types + np_unsigned_int_types - np_float_types = [np.float16, np.float32, np.float64] -np_scalar_types = np_int_types + np_float_types - def randvals(rng, shape, dtype): if dtype in np_float_types: @@ -54,546 +51,6 @@ def getkernel(func, suffix=""): return kernel_cache[key] -def get_select_kernel(dtype): - def output_select_kernel_fn( - input: wp.array(dtype=dtype), - index: int, - out: wp.array(dtype=dtype), - ): - out[0] = input[index] - - return getkernel(output_select_kernel_fn, suffix=dtype.__name__) - - -def get_select_kernel2(dtype): - def output_select_kernel2_fn( - input: wp.array(dtype=dtype, ndim=2), - index0: int, - index1: int, - out: wp.array(dtype=dtype), - ): - out[0] = input[index0, index1] - - return getkernel(output_select_kernel2_fn, suffix=dtype.__name__) - - -def test_arrays(test, device, dtype): - rng = np.random.default_rng(123) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - v2_np = randvals(rng, (10, 2), dtype) - v3_np = randvals(rng, (10, 3), dtype) - v4_np = randvals(rng, (10, 4), dtype) - v5_np = randvals(rng, (10, 5), dtype) - - v2 = wp.array(v2_np, dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(v3_np, dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(v4_np, dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(v5_np, dtype=vec5, requires_grad=True, device=device) - - assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) - assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) - assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) - assert_np_equal(v5.numpy(), v5_np, tol=1.0e-6) - - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - - v2 = wp.array(v2_np, dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(v3_np, dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(v4_np, dtype=vec4, requires_grad=True, device=device) - - assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) - assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) - assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) - - -def test_components(test, device, dtype): - # test accessing vector components from Python - this is especially important - # for float16, which requires special handling internally - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec3 = wp.types.vector(length=3, dtype=wptype) - - v = vec3(1, 2, 3) - - # test __getitem__ for individual components - test.assertEqual(v[0], 1) - test.assertEqual(v[1], 2) - test.assertEqual(v[2], 3) - - # test __getitem__ for slices - s = v[:] - test.assertEqual(s[0], 1) - test.assertEqual(s[1], 2) - test.assertEqual(s[2], 3) - - s = v[1:] - test.assertEqual(s[0], 2) - test.assertEqual(s[1], 3) - - s = v[:2] - test.assertEqual(s[0], 1) - test.assertEqual(s[1], 2) - - s = v[::2] - test.assertEqual(s[0], 1) - test.assertEqual(s[1], 3) - - # test __setitem__ for individual components - v[0] = 4 - v[1] = 5 - v[2] = 6 - test.assertEqual(v[0], 4) - test.assertEqual(v[1], 5) - test.assertEqual(v[2], 6) - - # test __setitem__ for slices - v[:] = [7, 8, 9] - test.assertEqual(v[0], 7) - test.assertEqual(v[1], 8) - test.assertEqual(v[2], 9) - - v[1:] = [10, 11] - test.assertEqual(v[0], 7) - test.assertEqual(v[1], 10) - test.assertEqual(v[2], 11) - - v[:2] = [12, 13] - test.assertEqual(v[0], 12) - test.assertEqual(v[1], 13) - test.assertEqual(v[2], 11) - - v[::2] = [14, 15] - test.assertEqual(v[0], 14) - test.assertEqual(v[1], 13) - test.assertEqual(v[2], 15) - - -def test_py_arithmetic_ops(test, device, dtype): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - def make_vec(*args): - if wptype in wp.types.int_types: - # Cast to the correct integer type to simulate wrapping. - return tuple(wptype._type_(x).value for x in args) - - return args - - vec_cls = wp.vec(3, wptype) - - v = vec_cls(1, -2, 3) - test.assertSequenceEqual(+v, make_vec(1, -2, 3)) - test.assertSequenceEqual(-v, make_vec(-1, 2, -3)) - test.assertSequenceEqual(v + vec_cls(5, 5, 5), make_vec(6, 3, 8)) - test.assertSequenceEqual(v - vec_cls(5, 5, 5), make_vec(-4, -7, -2)) - - v = vec_cls(2, 4, 6) - test.assertSequenceEqual(v * wptype(2), make_vec(4, 8, 12)) - test.assertSequenceEqual(wptype(2) * v, make_vec(4, 8, 12)) - test.assertSequenceEqual(v / wptype(2), make_vec(1, 2, 3)) - test.assertSequenceEqual(wptype(24) / v, make_vec(12, 6, 4)) - - -def test_anon_type_instance(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - def check_scalar_init( - input: wp.array(dtype=wptype), - output: wp.array(dtype=wptype), - ): - v2result = wp.vector(input[0], length=2) - v3result = wp.vector(input[1], length=3) - v4result = wp.vector(input[2], length=4) - v5result = wp.vector(input[3], length=5) - - idx = 0 - for i in range(2): - output[idx] = wptype(2) * v2result[i] - idx = idx + 1 - for i in range(3): - output[idx] = wptype(2) * v3result[i] - idx = idx + 1 - for i in range(4): - output[idx] = wptype(2) * v4result[i] - idx = idx + 1 - for i in range(5): - output[idx] = wptype(2) * v5result[i] - idx = idx + 1 - - def check_component_init( - input: wp.array(dtype=wptype), - output: wp.array(dtype=wptype), - ): - v2result = wp.vector(input[0], input[1]) - v3result = wp.vector(input[2], input[3], input[4]) - v4result = wp.vector(input[5], input[6], input[7], input[8]) - v5result = wp.vector(input[9], input[10], input[11], input[12], input[13]) - - idx = 0 - for i in range(2): - output[idx] = wptype(2) * v2result[i] - idx = idx + 1 - for i in range(3): - output[idx] = wptype(2) * v3result[i] - idx = idx + 1 - for i in range(4): - output[idx] = wptype(2) * v4result[i] - idx = idx + 1 - for i in range(5): - output[idx] = wptype(2) * v5result[i] - idx = idx + 1 - - scalar_kernel = getkernel(check_scalar_init, suffix=dtype.__name__) - component_kernel = getkernel(check_component_init, suffix=dtype.__name__) - output_select_kernel = get_select_kernel(wptype) - - if register_kernels: - return - - input = wp.array(randvals(rng, [4], dtype), requires_grad=True, device=device) - output = wp.zeros(2 + 3 + 4 + 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) - - assert_np_equal(output.numpy()[:2], 2 * np.array([input.numpy()[0]] * 2), tol=1.0e-6) - assert_np_equal(output.numpy()[2:5], 2 * np.array([input.numpy()[1]] * 3), tol=1.0e-6) - assert_np_equal(output.numpy()[5:9], 2 * np.array([input.numpy()[2]] * 4), tol=1.0e-6) - assert_np_equal(output.numpy()[9:], 2 * np.array([input.numpy()[3]] * 5), tol=1.0e-6) - - if dtype in np_float_types: - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for i in range(len(output)): - tape = wp.Tape() - with tape: - wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) - - tape.backward(loss=out) - expected = np.zeros_like(input.numpy()) - if i < 2: - expected[0] = 2 - elif i < 5: - expected[1] = 2 - elif i < 9: - expected[2] = 2 - else: - expected[3] = 2 - - assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) - - tape.reset() - tape.zero() - - input = wp.array(randvals(rng, [2 + 3 + 4 + 5], dtype), requires_grad=True, device=device) - output = wp.zeros(2 + 3 + 4 + 5, dtype=wptype, requires_grad=True, device=device) - - wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) - - assert_np_equal(output.numpy(), 2 * input.numpy(), tol=1.0e-6) - - if dtype in np_float_types: - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - for i in range(len(output)): - tape = wp.Tape() - with tape: - wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) - - tape.backward(loss=out) - expected = np.zeros_like(input.numpy()) - expected[i] = 2 - - assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) - - tape.reset() - tape.zero() - - -def test_constants(test, device, dtype, register_kernels=False): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - cv2 = wp.constant(vec2(1, 2)) - cv3 = wp.constant(vec3(1, 2, 3)) - cv4 = wp.constant(vec4(1, 2, 3, 4)) - cv5 = wp.constant(vec5(1, 2, 3, 4, 5)) - - def check_vector_constants(): - wp.expect_eq(cv2, vec2(wptype(1), wptype(2))) - wp.expect_eq(cv3, vec3(wptype(1), wptype(2), wptype(3))) - wp.expect_eq(cv4, vec4(wptype(1), wptype(2), wptype(3), wptype(4))) - wp.expect_eq(cv5, vec5(wptype(1), wptype(2), wptype(3), wptype(4), wptype(5))) - - kernel = getkernel(check_vector_constants, suffix=dtype.__name__) - - if register_kernels: - return - - wp.launch(kernel, dim=1, inputs=[]) - - -def test_constructors(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_scalar_constructor( - input: wp.array(dtype=wptype), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = vec2(input[0]) - v3result = vec3(input[0]) - v4result = vec4(input[0]) - v5result = vec5(input[0]) - - v2[0] = v2result - v3[0] = v3result - v4[0] = v4result - v5[0] = v5result - - # multiply outputs by 2 so we've got something to backpropagate - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - def check_vector_constructors( - input: wp.array(dtype=wptype), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = vec2(input[0], input[1]) - v3result = vec3(input[2], input[3], input[4]) - v4result = vec4(input[5], input[6], input[7], input[8]) - v5result = vec5(input[9], input[10], input[11], input[12], input[13]) - - v2[0] = v2result - v3[0] = v3result - v4[0] = v4result - v5[0] = v5result - - # multiply the output by 2 so we've got something to backpropagate: - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - vec_kernel = getkernel(check_vector_constructors, suffix=dtype.__name__) - kernel = getkernel(check_scalar_constructor, suffix=dtype.__name__) - - if register_kernels: - return - - input = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) - v2 = wp.zeros(1, dtype=vec2, device=device) - v3 = wp.zeros(1, dtype=vec3, device=device) - v4 = wp.zeros(1, dtype=vec4, device=device) - v5 = wp.zeros(1, dtype=vec5, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[input], - outputs=[v2, v3, v4, v5, v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - if dtype in np_float_types: - for l in [v20, v21]: - tape.backward(loss=l) - test.assertEqual(tape.gradients[input].numpy()[0], 2.0) - tape.zero() - - for l in [v30, v31, v32]: - tape.backward(loss=l) - test.assertEqual(tape.gradients[input].numpy()[0], 2.0) - tape.zero() - - for l in [v40, v41, v42, v43]: - tape.backward(loss=l) - test.assertEqual(tape.gradients[input].numpy()[0], 2.0) - tape.zero() - - for l in [v50, v51, v52, v53, v54]: - tape.backward(loss=l) - test.assertEqual(tape.gradients[input].numpy()[0], 2.0) - tape.zero() - - val = input.numpy()[0] - assert_np_equal(v2.numpy()[0], np.array([val, val]), tol=1.0e-6) - assert_np_equal(v3.numpy()[0], np.array([val, val, val]), tol=1.0e-6) - assert_np_equal(v4.numpy()[0], np.array([val, val, val, val]), tol=1.0e-6) - assert_np_equal(v5.numpy()[0], np.array([val, val, val, val, val]), tol=1.0e-6) - - assert_np_equal(v20.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v21.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v30.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v31.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v32.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v40.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v41.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v42.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v43.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v50.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v51.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v52.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v53.numpy()[0], 2 * val, tol=1.0e-6) - assert_np_equal(v54.numpy()[0], 2 * val, tol=1.0e-6) - - input = wp.array(randvals(rng, [14], dtype), requires_grad=True, device=device) - tape = wp.Tape() - with tape: - wp.launch( - vec_kernel, - dim=1, - inputs=[input], - outputs=[v2, v3, v4, v5, v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - if dtype in np_float_types: - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): - tape.backward(loss=l) - grad = tape.gradients[input].numpy() - expected_grad = np.zeros_like(grad) - expected_grad[i] = 2 - assert_np_equal(grad, expected_grad, tol=tol) - tape.zero() - - assert_np_equal(v2.numpy()[0, 0], input.numpy()[0], tol=tol) - assert_np_equal(v2.numpy()[0, 1], input.numpy()[1], tol=tol) - assert_np_equal(v3.numpy()[0, 0], input.numpy()[2], tol=tol) - assert_np_equal(v3.numpy()[0, 1], input.numpy()[3], tol=tol) - assert_np_equal(v3.numpy()[0, 2], input.numpy()[4], tol=tol) - assert_np_equal(v4.numpy()[0, 0], input.numpy()[5], tol=tol) - assert_np_equal(v4.numpy()[0, 1], input.numpy()[6], tol=tol) - assert_np_equal(v4.numpy()[0, 2], input.numpy()[7], tol=tol) - assert_np_equal(v4.numpy()[0, 3], input.numpy()[8], tol=tol) - assert_np_equal(v5.numpy()[0, 0], input.numpy()[9], tol=tol) - assert_np_equal(v5.numpy()[0, 1], input.numpy()[10], tol=tol) - assert_np_equal(v5.numpy()[0, 2], input.numpy()[11], tol=tol) - assert_np_equal(v5.numpy()[0, 3], input.numpy()[12], tol=tol) - assert_np_equal(v5.numpy()[0, 4], input.numpy()[13], tol=tol) - - assert_np_equal(v20.numpy()[0], 2 * input.numpy()[0], tol=tol) - assert_np_equal(v21.numpy()[0], 2 * input.numpy()[1], tol=tol) - assert_np_equal(v30.numpy()[0], 2 * input.numpy()[2], tol=tol) - assert_np_equal(v31.numpy()[0], 2 * input.numpy()[3], tol=tol) - assert_np_equal(v32.numpy()[0], 2 * input.numpy()[4], tol=tol) - assert_np_equal(v40.numpy()[0], 2 * input.numpy()[5], tol=tol) - assert_np_equal(v41.numpy()[0], 2 * input.numpy()[6], tol=tol) - assert_np_equal(v42.numpy()[0], 2 * input.numpy()[7], tol=tol) - assert_np_equal(v43.numpy()[0], 2 * input.numpy()[8], tol=tol) - assert_np_equal(v50.numpy()[0], 2 * input.numpy()[9], tol=tol) - assert_np_equal(v51.numpy()[0], 2 * input.numpy()[10], tol=tol) - assert_np_equal(v52.numpy()[0], 2 * input.numpy()[11], tol=tol) - assert_np_equal(v53.numpy()[0], 2 * input.numpy()[12], tol=tol) - assert_np_equal(v54.numpy()[0], 2 * input.numpy()[13], tol=tol) - - def test_anon_constructor_error_dtype_keyword_missing(test, device): @wp.kernel def kernel(): @@ -726,1102 +183,30 @@ def kernel(): r"All numeric arguments to vec\(\) constructor should have the same " r"type, expected 2 arg_types of type , " r"received ,$", - ): - wp.launch( - kernel, - dim=1, - inputs=[], - device=device, - ) - - -def test_tpl_ops_with_anon(test, device): - vec3i = wp.vec(3, dtype=int) - - v = wp.vec3i(1, 2, 3) - v += vec3i(2, 3, 4) - v -= vec3i(3, 4, 5) - test.assertSequenceEqual(v, (0, 1, 2)) - - v = vec3i(1, 2, 3) - v += wp.vec3i(2, 3, 4) - v -= wp.vec3i(3, 4, 5) - test.assertSequenceEqual(v, (0, 1, 2)) - - -def test_indexing(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_indexing( - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - # multiply outputs by 2 so we've got something to backpropagate: - v20[0] = wptype(2) * v2[0][0] - v21[0] = wptype(2) * v2[0][1] - - v30[0] = wptype(2) * v3[0][0] - v31[0] = wptype(2) * v3[0][1] - v32[0] = wptype(2) * v3[0][2] - - v40[0] = wptype(2) * v4[0][0] - v41[0] = wptype(2) * v4[0][1] - v42[0] = wptype(2) * v4[0][2] - v43[0] = wptype(2) * v4[0][3] - - v50[0] = wptype(2) * v5[0][0] - v51[0] = wptype(2) * v5[0][1] - v52[0] = wptype(2) * v5[0][2] - v53[0] = wptype(2) * v5[0][3] - v54[0] = wptype(2) * v5[0][4] - - kernel = getkernel(check_indexing, suffix=dtype.__name__) - - if register_kernels: - return - - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[v2, v3, v4, v5], - outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - if dtype in np_float_types: - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): - tape.backward(loss=l) - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) - expected_grads = np.zeros_like(allgrads) - expected_grads[i] = 2 - assert_np_equal(allgrads, expected_grads, tol=tol) - tape.zero() - - assert_np_equal(v20.numpy()[0], 2.0 * v2.numpy()[0, 0], tol=tol) - assert_np_equal(v21.numpy()[0], 2.0 * v2.numpy()[0, 1], tol=tol) - assert_np_equal(v30.numpy()[0], 2.0 * v3.numpy()[0, 0], tol=tol) - assert_np_equal(v31.numpy()[0], 2.0 * v3.numpy()[0, 1], tol=tol) - assert_np_equal(v32.numpy()[0], 2.0 * v3.numpy()[0, 2], tol=tol) - assert_np_equal(v40.numpy()[0], 2.0 * v4.numpy()[0, 0], tol=tol) - assert_np_equal(v41.numpy()[0], 2.0 * v4.numpy()[0, 1], tol=tol) - assert_np_equal(v42.numpy()[0], 2.0 * v4.numpy()[0, 2], tol=tol) - assert_np_equal(v43.numpy()[0], 2.0 * v4.numpy()[0, 3], tol=tol) - assert_np_equal(v50.numpy()[0], 2.0 * v5.numpy()[0, 0], tol=tol) - assert_np_equal(v51.numpy()[0], 2.0 * v5.numpy()[0, 1], tol=tol) - assert_np_equal(v52.numpy()[0], 2.0 * v5.numpy()[0, 2], tol=tol) - assert_np_equal(v53.numpy()[0], 2.0 * v5.numpy()[0, 3], tol=tol) - assert_np_equal(v54.numpy()[0], 2.0 * v5.numpy()[0, 4], tol=tol) - - -def test_equality(test, device, dtype, register_kernels=False): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_equality( - v20: wp.array(dtype=vec2), - v21: wp.array(dtype=vec2), - v22: wp.array(dtype=vec2), - v30: wp.array(dtype=vec3), - v31: wp.array(dtype=vec3), - v32: wp.array(dtype=vec3), - v33: wp.array(dtype=vec3), - v40: wp.array(dtype=vec4), - v41: wp.array(dtype=vec4), - v42: wp.array(dtype=vec4), - v43: wp.array(dtype=vec4), - v44: wp.array(dtype=vec4), - v50: wp.array(dtype=vec5), - v51: wp.array(dtype=vec5), - v52: wp.array(dtype=vec5), - v53: wp.array(dtype=vec5), - v54: wp.array(dtype=vec5), - v55: wp.array(dtype=vec5), - ): - wp.expect_eq(v20[0], v20[0]) - wp.expect_neq(v21[0], v20[0]) - wp.expect_neq(v22[0], v20[0]) - - wp.expect_eq(v30[0], v30[0]) - wp.expect_neq(v31[0], v30[0]) - wp.expect_neq(v32[0], v30[0]) - wp.expect_neq(v33[0], v30[0]) - - wp.expect_eq(v40[0], v40[0]) - wp.expect_neq(v41[0], v40[0]) - wp.expect_neq(v42[0], v40[0]) - wp.expect_neq(v43[0], v40[0]) - wp.expect_neq(v44[0], v40[0]) - - wp.expect_eq(v50[0], v50[0]) - wp.expect_neq(v51[0], v50[0]) - wp.expect_neq(v52[0], v50[0]) - wp.expect_neq(v53[0], v50[0]) - wp.expect_neq(v54[0], v50[0]) - wp.expect_neq(v55[0], v50[0]) - - kernel = getkernel(check_equality, suffix=dtype.__name__) - - if register_kernels: - return - - v20 = wp.array([1.0, 2.0], dtype=vec2, requires_grad=True, device=device) - v21 = wp.array([1.0, 3.0], dtype=vec2, requires_grad=True, device=device) - v22 = wp.array([3.0, 2.0], dtype=vec2, requires_grad=True, device=device) - - v30 = wp.array([1.0, 2.0, 3.0], dtype=vec3, requires_grad=True, device=device) - v31 = wp.array([-1.0, 2.0, 3.0], dtype=vec3, requires_grad=True, device=device) - v32 = wp.array([1.0, -2.0, 3.0], dtype=vec3, requires_grad=True, device=device) - v33 = wp.array([1.0, 2.0, -3.0], dtype=vec3, requires_grad=True, device=device) - - v40 = wp.array([1.0, 2.0, 3.0, 4.0], dtype=vec4, requires_grad=True, device=device) - v41 = wp.array([-1.0, 2.0, 3.0, 4.0], dtype=vec4, requires_grad=True, device=device) - v42 = wp.array([1.0, -2.0, 3.0, 4.0], dtype=vec4, requires_grad=True, device=device) - v43 = wp.array([1.0, 2.0, -3.0, 4.0], dtype=vec4, requires_grad=True, device=device) - v44 = wp.array([1.0, 2.0, 3.0, -4.0], dtype=vec4, requires_grad=True, device=device) - - v50 = wp.array([1.0, 2.0, 3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) - v51 = wp.array([-1.0, 2.0, 3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) - v52 = wp.array([1.0, -2.0, 3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) - v53 = wp.array([1.0, 2.0, -3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) - v54 = wp.array([1.0, 2.0, 3.0, -4.0, 5.0], dtype=vec5, requires_grad=True, device=device) - v55 = wp.array([1.0, 2.0, 3.0, 4.0, -5.0], dtype=vec5, requires_grad=True, device=device) - wp.launch( - kernel, - dim=1, - inputs=[ - v20, - v21, - v22, - v30, - v31, - v32, - v33, - v40, - v41, - v42, - v43, - v44, - v50, - v51, - v52, - v53, - v54, - v55, - ], - outputs=[], - device=device, - ) - - -def test_negation(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_negation( - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v2out: wp.array(dtype=vec2), - v3out: wp.array(dtype=vec3), - v4out: wp.array(dtype=vec4), - v5out: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = -v2[0] - v3result = -v3[0] - v4result = -v4[0] - v5result = -v5[0] - - v2out[0] = v2result - v3out[0] = v3result - v4out[0] = v4result - v5out[0] = v5result - - # multiply these outputs by 2 so we've got something to backpropagate: - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - kernel = getkernel(check_negation, suffix=dtype.__name__) - - if register_kernels: - return - - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5_np = randvals(rng, (1, 5), dtype) - v5 = wp.array(v5_np, dtype=vec5, requires_grad=True, device=device) - - v2out = wp.zeros(1, dtype=vec2, device=device) - v3out = wp.zeros(1, dtype=vec3, device=device) - v4out = wp.zeros(1, dtype=vec4, device=device) - v5out = wp.zeros(1, dtype=vec5, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[v2, v3, v4, v5], - outputs=[v2out, v3out, v4out, v5out, v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - if dtype in np_float_types: - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): - tape.backward(loss=l) - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) - expected_grads = np.zeros_like(allgrads) - expected_grads[i] = -2 - assert_np_equal(allgrads, expected_grads, tol=tol) - tape.zero() - - assert_np_equal(v2out.numpy()[0], -v2.numpy()[0], tol=tol) - assert_np_equal(v3out.numpy()[0], -v3.numpy()[0], tol=tol) - assert_np_equal(v4out.numpy()[0], -v4.numpy()[0], tol=tol) - assert_np_equal(v5out.numpy()[0], -v5.numpy()[0], tol=tol) - - -def test_scalar_multiplication(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_mul( - s: wp.array(dtype=wptype), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = s[0] * v2[0] - v3result = s[0] * v3[0] - v4result = s[0] * v4[0] - v5result = s[0] * v5[0] - - # multiply outputs by 2 so we've got something to backpropagate: - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - kernel = getkernel(check_mul, suffix=dtype.__name__) - - if register_kernels: - return - - s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s, - v2, - v3, - v4, - v5, - ], - outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - assert_np_equal(v20.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 0], tol=tol) - assert_np_equal(v21.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 1], tol=tol) - - assert_np_equal(v30.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v31.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v32.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 2], tol=10 * tol) - - assert_np_equal(v40.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v41.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v42.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 2], tol=10 * tol) - assert_np_equal(v43.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 3], tol=10 * tol) - - assert_np_equal(v50.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v51.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v52.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 2], tol=10 * tol) - assert_np_equal(v53.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 3], tol=10 * tol) - assert_np_equal(v54.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 4], tol=10 * tol) - - incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) - - if dtype in np_float_types: - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43]): - tape.backward(loss=l) - sgrad = tape.gradients[s].numpy()[0] - assert_np_equal(sgrad, 2 * incmps[i], tol=10 * tol) - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4]]) - expected_grads = np.zeros_like(allgrads) - expected_grads[i] = s.numpy()[0] * 2 - assert_np_equal(allgrads, expected_grads, tol=10 * tol) - tape.zero() - - -def test_scalar_multiplication_rightmul(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_rightmul( - s: wp.array(dtype=wptype), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = v2[0] * s[0] - v3result = v3[0] * s[0] - v4result = v4[0] * s[0] - v5result = v5[0] * s[0] - - # multiply outputs by 2 so we've got something to backpropagate: - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - kernel = getkernel(check_rightmul, suffix=dtype.__name__) - - if register_kernels: - return - - s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s, - v2, - v3, - v4, - v5, - ], - outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - assert_np_equal(v20.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 0], tol=tol) - assert_np_equal(v21.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 1], tol=tol) - - assert_np_equal(v30.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v31.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v32.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 2], tol=10 * tol) - - assert_np_equal(v40.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v41.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v42.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 2], tol=10 * tol) - assert_np_equal(v43.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 3], tol=10 * tol) - - assert_np_equal(v50.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v51.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v52.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 2], tol=10 * tol) - assert_np_equal(v53.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 3], tol=10 * tol) - assert_np_equal(v54.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 4], tol=10 * tol) - - incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) - - if dtype in np_float_types: - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43]): - tape.backward(loss=l) - sgrad = tape.gradients[s].numpy()[0] - assert_np_equal(sgrad, 2 * incmps[i], tol=10 * tol) - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4]]) - expected_grads = np.zeros_like(allgrads) - expected_grads[i] = s.numpy()[0] * 2 - assert_np_equal(allgrads, expected_grads, tol=10 * tol) - tape.zero() - - -def test_cw_multiplication(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_cw_mul( - s2: wp.array(dtype=vec2), - s3: wp.array(dtype=vec3), - s4: wp.array(dtype=vec4), - s5: wp.array(dtype=vec5), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = wp.cw_mul(s2[0], v2[0]) - v3result = wp.cw_mul(s3[0], v3[0]) - v4result = wp.cw_mul(s4[0], v4[0]) - v5result = wp.cw_mul(s5[0], v5[0]) - - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - kernel = getkernel(check_cw_mul, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - assert_np_equal(v20.numpy()[0], 2 * s2.numpy()[0, 0] * v2.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v21.numpy()[0], 2 * s2.numpy()[0, 1] * v2.numpy()[0, 1], tol=10 * tol) - - assert_np_equal(v30.numpy()[0], 2 * s3.numpy()[0, 0] * v3.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v31.numpy()[0], 2 * s3.numpy()[0, 1] * v3.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v32.numpy()[0], 2 * s3.numpy()[0, 2] * v3.numpy()[0, 2], tol=10 * tol) - - assert_np_equal(v40.numpy()[0], 2 * s4.numpy()[0, 0] * v4.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v41.numpy()[0], 2 * s4.numpy()[0, 1] * v4.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v42.numpy()[0], 2 * s4.numpy()[0, 2] * v4.numpy()[0, 2], tol=10 * tol) - assert_np_equal(v43.numpy()[0], 2 * s4.numpy()[0, 3] * v4.numpy()[0, 3], tol=10 * tol) - - assert_np_equal(v50.numpy()[0], 2 * s5.numpy()[0, 0] * v5.numpy()[0, 0], tol=10 * tol) - assert_np_equal(v51.numpy()[0], 2 * s5.numpy()[0, 1] * v5.numpy()[0, 1], tol=10 * tol) - assert_np_equal(v52.numpy()[0], 2 * s5.numpy()[0, 2] * v5.numpy()[0, 2], tol=10 * tol) - assert_np_equal(v53.numpy()[0], 2 * s5.numpy()[0, 3] * v5.numpy()[0, 3], tol=10 * tol) - assert_np_equal(v54.numpy()[0], 2 * s5.numpy()[0, 4] * v5.numpy()[0, 4], tol=10 * tol) - - incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) - scmps = np.concatenate([v.numpy()[0] for v in [s2, s3, s4, s5]]) - - if dtype in np_float_types: - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): - tape.backward(loss=l) - sgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [s2, s3, s4, s5]]) - expected_grads = np.zeros_like(sgrads) - expected_grads[i] = incmps[i] * 2 - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) - expected_grads = np.zeros_like(allgrads) - expected_grads[i] = scmps[i] * 2 - assert_np_equal(allgrads, expected_grads, tol=10 * tol) - - tape.zero() - - -def test_scalar_division(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 5.0e-3, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_div( - s: wp.array(dtype=wptype), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = v2[0] / s[0] - v3result = v3[0] / s[0] - v4result = v4[0] / s[0] - v5result = v5[0] / s[0] - - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - kernel = getkernel(check_div, suffix=dtype.__name__) - - if register_kernels: - return - - s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s, - v2, - v3, - v4, - v5, - ], - outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - if dtype in np_int_types: - assert_np_equal(v20.numpy()[0], 2 * (v2.numpy()[0, 0] // (s.numpy()[0])), tol=tol) - assert_np_equal(v21.numpy()[0], 2 * (v2.numpy()[0, 1] // (s.numpy()[0])), tol=tol) - - assert_np_equal(v30.numpy()[0], 2 * (v3.numpy()[0, 0] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v31.numpy()[0], 2 * (v3.numpy()[0, 1] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v32.numpy()[0], 2 * (v3.numpy()[0, 2] // (s.numpy()[0])), tol=10 * tol) - - assert_np_equal(v40.numpy()[0], 2 * (v4.numpy()[0, 0] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v41.numpy()[0], 2 * (v4.numpy()[0, 1] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v42.numpy()[0], 2 * (v4.numpy()[0, 2] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v43.numpy()[0], 2 * (v4.numpy()[0, 3] // (s.numpy()[0])), tol=10 * tol) - - assert_np_equal(v50.numpy()[0], 2 * (v5.numpy()[0, 0] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v51.numpy()[0], 2 * (v5.numpy()[0, 1] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v52.numpy()[0], 2 * (v5.numpy()[0, 2] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v53.numpy()[0], 2 * (v5.numpy()[0, 3] // (s.numpy()[0])), tol=10 * tol) - assert_np_equal(v54.numpy()[0], 2 * (v5.numpy()[0, 4] // (s.numpy()[0])), tol=10 * tol) - - else: - assert_np_equal(v20.numpy()[0], 2 * v2.numpy()[0, 0] / (s.numpy()[0]), tol=tol) - assert_np_equal(v21.numpy()[0], 2 * v2.numpy()[0, 1] / (s.numpy()[0]), tol=tol) - - assert_np_equal(v30.numpy()[0], 2 * v3.numpy()[0, 0] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v31.numpy()[0], 2 * v3.numpy()[0, 1] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v32.numpy()[0], 2 * v3.numpy()[0, 2] / (s.numpy()[0]), tol=10 * tol) - - assert_np_equal(v40.numpy()[0], 2 * v4.numpy()[0, 0] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v41.numpy()[0], 2 * v4.numpy()[0, 1] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v42.numpy()[0], 2 * v4.numpy()[0, 2] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v43.numpy()[0], 2 * v4.numpy()[0, 3] / (s.numpy()[0]), tol=10 * tol) - - assert_np_equal(v50.numpy()[0], 2 * v5.numpy()[0, 0] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v51.numpy()[0], 2 * v5.numpy()[0, 1] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v52.numpy()[0], 2 * v5.numpy()[0, 2] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v53.numpy()[0], 2 * v5.numpy()[0, 3] / (s.numpy()[0]), tol=10 * tol) - assert_np_equal(v54.numpy()[0], 2 * v5.numpy()[0, 4] / (s.numpy()[0]), tol=10 * tol) - - incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) - - if dtype in np_float_types: - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): - tape.backward(loss=l) - sgrad = tape.gradients[s].numpy()[0] - - # d/ds v/s = -v/s^2 - assert_np_equal(sgrad, -2 * incmps[i] / (s.numpy()[0] * s.numpy()[0]), tol=10 * tol) - - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) - expected_grads = np.zeros_like(allgrads) - expected_grads[i] = 2 / s.numpy()[0] - - # d/dv v/s = 1/s - assert_np_equal(allgrads, expected_grads, tol=tol) - tape.zero() - - -def test_cw_division(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_cw_div( - s2: wp.array(dtype=vec2), - s3: wp.array(dtype=vec3), - s4: wp.array(dtype=vec4), - s5: wp.array(dtype=vec5), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - v20: wp.array(dtype=wptype), - v21: wp.array(dtype=wptype), - v30: wp.array(dtype=wptype), - v31: wp.array(dtype=wptype), - v32: wp.array(dtype=wptype), - v40: wp.array(dtype=wptype), - v41: wp.array(dtype=wptype), - v42: wp.array(dtype=wptype), - v43: wp.array(dtype=wptype), - v50: wp.array(dtype=wptype), - v51: wp.array(dtype=wptype), - v52: wp.array(dtype=wptype), - v53: wp.array(dtype=wptype), - v54: wp.array(dtype=wptype), - ): - v2result = wp.cw_div(v2[0], s2[0]) - v3result = wp.cw_div(v3[0], s3[0]) - v4result = wp.cw_div(v4[0], s4[0]) - v5result = wp.cw_div(v5[0], s5[0]) - - v20[0] = wptype(2) * v2result[0] - v21[0] = wptype(2) * v2result[1] - - v30[0] = wptype(2) * v3result[0] - v31[0] = wptype(2) * v3result[1] - v32[0] = wptype(2) * v3result[2] - - v40[0] = wptype(2) * v4result[0] - v41[0] = wptype(2) * v4result[1] - v42[0] = wptype(2) * v4result[2] - v43[0] = wptype(2) * v4result[3] - - v50[0] = wptype(2) * v5result[0] - v51[0] = wptype(2) * v5result[1] - v52[0] = wptype(2) * v5result[2] - v53[0] = wptype(2) * v5result[3] - v54[0] = wptype(2) * v5result[4] - - kernel = getkernel(check_cw_div, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], - device=device, - ) - - if dtype in np_int_types: - assert_np_equal(v20.numpy()[0], 2 * (v2.numpy()[0, 0] // s2.numpy()[0, 0]), tol=tol) - assert_np_equal(v21.numpy()[0], 2 * (v2.numpy()[0, 1] // s2.numpy()[0, 1]), tol=tol) - - assert_np_equal(v30.numpy()[0], 2 * (v3.numpy()[0, 0] // s3.numpy()[0, 0]), tol=tol) - assert_np_equal(v31.numpy()[0], 2 * (v3.numpy()[0, 1] // s3.numpy()[0, 1]), tol=tol) - assert_np_equal(v32.numpy()[0], 2 * (v3.numpy()[0, 2] // s3.numpy()[0, 2]), tol=tol) - - assert_np_equal(v40.numpy()[0], 2 * (v4.numpy()[0, 0] // s4.numpy()[0, 0]), tol=tol) - assert_np_equal(v41.numpy()[0], 2 * (v4.numpy()[0, 1] // s4.numpy()[0, 1]), tol=tol) - assert_np_equal(v42.numpy()[0], 2 * (v4.numpy()[0, 2] // s4.numpy()[0, 2]), tol=tol) - assert_np_equal(v43.numpy()[0], 2 * (v4.numpy()[0, 3] // s4.numpy()[0, 3]), tol=tol) - - assert_np_equal(v50.numpy()[0], 2 * (v5.numpy()[0, 0] // s5.numpy()[0, 0]), tol=tol) - assert_np_equal(v51.numpy()[0], 2 * (v5.numpy()[0, 1] // s5.numpy()[0, 1]), tol=tol) - assert_np_equal(v52.numpy()[0], 2 * (v5.numpy()[0, 2] // s5.numpy()[0, 2]), tol=tol) - assert_np_equal(v53.numpy()[0], 2 * (v5.numpy()[0, 3] // s5.numpy()[0, 3]), tol=tol) - assert_np_equal(v54.numpy()[0], 2 * (v5.numpy()[0, 4] // s5.numpy()[0, 4]), tol=tol) - else: - assert_np_equal(v20.numpy()[0], 2 * v2.numpy()[0, 0] / s2.numpy()[0, 0], tol=tol) - assert_np_equal(v21.numpy()[0], 2 * v2.numpy()[0, 1] / s2.numpy()[0, 1], tol=tol) - - assert_np_equal(v30.numpy()[0], 2 * v3.numpy()[0, 0] / s3.numpy()[0, 0], tol=tol) - assert_np_equal(v31.numpy()[0], 2 * v3.numpy()[0, 1] / s3.numpy()[0, 1], tol=tol) - assert_np_equal(v32.numpy()[0], 2 * v3.numpy()[0, 2] / s3.numpy()[0, 2], tol=tol) - - assert_np_equal(v40.numpy()[0], 2 * v4.numpy()[0, 0] / s4.numpy()[0, 0], tol=tol) - assert_np_equal(v41.numpy()[0], 2 * v4.numpy()[0, 1] / s4.numpy()[0, 1], tol=tol) - assert_np_equal(v42.numpy()[0], 2 * v4.numpy()[0, 2] / s4.numpy()[0, 2], tol=tol) - assert_np_equal(v43.numpy()[0], 2 * v4.numpy()[0, 3] / s4.numpy()[0, 3], tol=tol) - - assert_np_equal(v50.numpy()[0], 2 * v5.numpy()[0, 0] / s5.numpy()[0, 0], tol=tol) - assert_np_equal(v51.numpy()[0], 2 * v5.numpy()[0, 1] / s5.numpy()[0, 1], tol=tol) - assert_np_equal(v52.numpy()[0], 2 * v5.numpy()[0, 2] / s5.numpy()[0, 2], tol=tol) - assert_np_equal(v53.numpy()[0], 2 * v5.numpy()[0, 3] / s5.numpy()[0, 3], tol=tol) - assert_np_equal(v54.numpy()[0], 2 * v5.numpy()[0, 4] / s5.numpy()[0, 4], tol=tol) - - if dtype in np_float_types: - incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) - scmps = np.concatenate([v.numpy()[0] for v in [s2, s3, s4, s5]]) - - for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): - tape.backward(loss=l) - sgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [s2, s3, s4, s5]]) - expected_grads = np.zeros_like(sgrads) + ): + wp.launch( + kernel, + dim=1, + inputs=[], + device=device, + ) - # d/ds v/s = -v/s^2 - expected_grads[i] = -incmps[i] * 2 / (scmps[i] * scmps[i]) - assert_np_equal(sgrads, expected_grads, tol=20 * tol) - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) - expected_grads = np.zeros_like(allgrads) +def test_tpl_ops_with_anon(test, device): + vec3i = wp.vec(3, dtype=int) - # d/dv v/s = 1/s - expected_grads[i] = 2 / scmps[i] - assert_np_equal(allgrads, expected_grads, tol=tol) + v = wp.vec3i(1, 2, 3) + v += vec3i(2, 3, 4) + v -= vec3i(3, 4, 5) + test.assertSequenceEqual(v, (0, 1, 2)) - tape.zero() + v = vec3i(1, 2, 3) + v += wp.vec3i(2, 3, 4) + v -= wp.vec3i(3, 4, 5) + test.assertSequenceEqual(v, (0, 1, 2)) -def test_addition(test, device, dtype, register_kernels=False): +def test_negation(test, device, dtype, register_kernels=False): rng = np.random.default_rng(123) tol = { @@ -1836,15 +221,15 @@ def test_addition(test, device, dtype, register_kernels=False): vec4 = wp.types.vector(length=4, dtype=wptype) vec5 = wp.types.vector(length=5, dtype=wptype) - def check_add( - s2: wp.array(dtype=vec2), - s3: wp.array(dtype=vec3), - s4: wp.array(dtype=vec4), - s5: wp.array(dtype=vec5), + def check_negation( v2: wp.array(dtype=vec2), v3: wp.array(dtype=vec3), v4: wp.array(dtype=vec4), v5: wp.array(dtype=vec5), + v2out: wp.array(dtype=vec2), + v3out: wp.array(dtype=vec3), + v4out: wp.array(dtype=vec4), + v5out: wp.array(dtype=vec5), v20: wp.array(dtype=wptype), v21: wp.array(dtype=wptype), v30: wp.array(dtype=wptype), @@ -1860,11 +245,17 @@ def check_add( v53: wp.array(dtype=wptype), v54: wp.array(dtype=wptype), ): - v2result = v2[0] + s2[0] - v3result = v3[0] + s3[0] - v4result = v4[0] + s4[0] - v5result = v5[0] + s5[0] + v2result = -v2[0] + v3result = -v3[0] + v4result = -v4[0] + v5result = -v5[0] + + v2out[0] = v2result + v3out[0] = v3result + v4out[0] = v4result + v5out[0] = v5result + # multiply these outputs by 2 so we've got something to backpropagate: v20[0] = wptype(2) * v2result[0] v21[0] = wptype(2) * v2result[1] @@ -1883,19 +274,21 @@ def check_add( v53[0] = wptype(2) * v5result[3] v54[0] = wptype(2) * v5result[4] - kernel = getkernel(check_add, suffix=dtype.__name__) + kernel = getkernel(check_negation, suffix=dtype.__name__) if register_kernels: return - s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v5_np = randvals(rng, (1, 5), dtype) + v5 = wp.array(v5_np, dtype=vec5, requires_grad=True, device=device) + + v2out = wp.zeros(1, dtype=vec2, device=device) + v3out = wp.zeros(1, dtype=vec3, device=device) + v4out = wp.zeros(1, dtype=vec4, device=device) + v5out = wp.zeros(1, dtype=vec5, device=device) v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) @@ -1910,57 +303,31 @@ def check_add( v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() with tape: wp.launch( kernel, dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + inputs=[v2, v3, v4, v5], + outputs=[v2out, v3out, v4out, v5out, v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], device=device, ) - assert_np_equal(v20.numpy()[0], 2 * (v2.numpy()[0, 0] + s2.numpy()[0, 0]), tol=tol) - assert_np_equal(v21.numpy()[0], 2 * (v2.numpy()[0, 1] + s2.numpy()[0, 1]), tol=tol) - - assert_np_equal(v30.numpy()[0], 2 * (v3.numpy()[0, 0] + s3.numpy()[0, 0]), tol=tol) - assert_np_equal(v31.numpy()[0], 2 * (v3.numpy()[0, 1] + s3.numpy()[0, 1]), tol=tol) - assert_np_equal(v32.numpy()[0], 2 * (v3.numpy()[0, 2] + s3.numpy()[0, 2]), tol=tol) - - assert_np_equal(v40.numpy()[0], 2 * (v4.numpy()[0, 0] + s4.numpy()[0, 0]), tol=tol) - assert_np_equal(v41.numpy()[0], 2 * (v4.numpy()[0, 1] + s4.numpy()[0, 1]), tol=tol) - assert_np_equal(v42.numpy()[0], 2 * (v4.numpy()[0, 2] + s4.numpy()[0, 2]), tol=tol) - assert_np_equal(v43.numpy()[0], 2 * (v4.numpy()[0, 3] + s4.numpy()[0, 3]), tol=tol) - - assert_np_equal(v50.numpy()[0], 2 * (v5.numpy()[0, 0] + s5.numpy()[0, 0]), tol=tol) - assert_np_equal(v51.numpy()[0], 2 * (v5.numpy()[0, 1] + s5.numpy()[0, 1]), tol=tol) - assert_np_equal(v52.numpy()[0], 2 * (v5.numpy()[0, 2] + s5.numpy()[0, 2]), tol=tol) - assert_np_equal(v53.numpy()[0], 2 * (v5.numpy()[0, 3] + s5.numpy()[0, 3]), tol=tol) - assert_np_equal(v54.numpy()[0], 2 * (v5.numpy()[0, 4] + s5.numpy()[0, 4]), tol=2 * tol) - if dtype in np_float_types: for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): tape.backward(loss=l) - sgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [s2, s3, s4, s5]]) - expected_grads = np.zeros_like(sgrads) - - expected_grads[i] = 2 - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) + expected_grads = np.zeros_like(allgrads) + expected_grads[i] = -2 assert_np_equal(allgrads, expected_grads, tol=tol) - tape.zero() + assert_np_equal(v2out.numpy()[0], -v2.numpy()[0], tol=tol) + assert_np_equal(v3out.numpy()[0], -v3.numpy()[0], tol=tol) + assert_np_equal(v4out.numpy()[0], -v4.numpy()[0], tol=tol) + assert_np_equal(v5out.numpy()[0], -v5.numpy()[0], tol=tol) + def test_subtraction_unsigned(test, device, dtype, register_kernels=False): wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] @@ -2156,127 +523,6 @@ def check_subtraction( tape.zero() -def test_dotproduct(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - tol = { - np.float16: 1.0e-2, - np.float32: 1.0e-6, - np.float64: 1.0e-8, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - def check_dot( - s2: wp.array(dtype=vec2), - s3: wp.array(dtype=vec3), - s4: wp.array(dtype=vec4), - s5: wp.array(dtype=vec5), - v2: wp.array(dtype=vec2), - v3: wp.array(dtype=vec3), - v4: wp.array(dtype=vec4), - v5: wp.array(dtype=vec5), - dot2: wp.array(dtype=wptype), - dot3: wp.array(dtype=wptype), - dot4: wp.array(dtype=wptype), - dot5: wp.array(dtype=wptype), - ): - dot2[0] = wptype(2) * wp.dot(v2[0], s2[0]) - dot3[0] = wptype(2) * wp.dot(v3[0], s3[0]) - dot4[0] = wptype(2) * wp.dot(v4[0], s4[0]) - dot5[0] = wptype(2) * wp.dot(v5[0], s5[0]) - - kernel = getkernel(check_dot, suffix=dtype.__name__) - - if register_kernels: - return - - s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) - v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) - v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) - v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) - dot2 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - dot3 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - dot4 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - dot5 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - tape = wp.Tape() - with tape: - wp.launch( - kernel, - dim=1, - inputs=[ - s2, - s3, - s4, - s5, - v2, - v3, - v4, - v5, - ], - outputs=[dot2, dot3, dot4, dot5], - device=device, - ) - - assert_np_equal(dot2.numpy()[0], 2.0 * (v2.numpy() * s2.numpy()).sum(), tol=10 * tol) - assert_np_equal(dot3.numpy()[0], 2.0 * (v3.numpy() * s3.numpy()).sum(), tol=10 * tol) - assert_np_equal(dot4.numpy()[0], 2.0 * (v4.numpy() * s4.numpy()).sum(), tol=10 * tol) - assert_np_equal(dot5.numpy()[0], 2.0 * (v5.numpy() * s5.numpy()).sum(), tol=10 * tol) - - if dtype in np_float_types: - tape.backward(loss=dot2) - sgrads = tape.gradients[s2].numpy()[0] - expected_grads = 2.0 * v2.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v2].numpy()[0] - expected_grads = 2.0 * s2.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=tol) - - tape.zero() - - tape.backward(loss=dot3) - sgrads = tape.gradients[s3].numpy()[0] - expected_grads = 2.0 * v3.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v3].numpy()[0] - expected_grads = 2.0 * s3.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=tol) - - tape.zero() - - tape.backward(loss=dot4) - sgrads = tape.gradients[s4].numpy()[0] - expected_grads = 2.0 * v4.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v4].numpy()[0] - expected_grads = 2.0 * s4.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=tol) - - tape.zero() - - tape.backward(loss=dot5) - sgrads = tape.gradients[s5].numpy()[0] - expected_grads = 2.0 * v5.numpy()[0] - assert_np_equal(sgrads, expected_grads, tol=10 * tol) - - vgrads = tape.gradients[v5].numpy()[0] - expected_grads = 2.0 * s5.numpy()[0] - assert_np_equal(vgrads, expected_grads, tol=10 * tol) - - tape.zero() - - def test_length(test, device, dtype, register_kernels=False): rng = np.random.default_rng(123) @@ -2738,139 +984,6 @@ def check_cross( tape.zero() -def test_minmax(test, device, dtype, register_kernels=False): - rng = np.random.default_rng(123) - - # \TODO: not quite sure why, but the numbers are off for 16 bit float - # on the cpu (but not cuda). This is probably just the sketchy float16 - # arithmetic I implemented to get all this stuff working, so - # hopefully that can be fixed when we do that correctly. - tol = { - np.float16: 1.0e-2, - }.get(dtype, 0) - - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - # \TODO: Also not quite sure why: this kernel compiles incredibly - # slowly though... - def check_vec_min_max( - a: wp.array(dtype=wptype, ndim=2), - b: wp.array(dtype=wptype, ndim=2), - mins: wp.array(dtype=wptype, ndim=2), - maxs: wp.array(dtype=wptype, ndim=2), - ): - for i in range(10): - # multiplying by 2 so we've got something to backpropagate: - a2read = vec2(a[i, 0], a[i, 1]) - b2read = vec2(b[i, 0], b[i, 1]) - c2 = wptype(2) * wp.min(a2read, b2read) - d2 = wptype(2) * wp.max(a2read, b2read) - - a3read = vec3(a[i, 2], a[i, 3], a[i, 4]) - b3read = vec3(b[i, 2], b[i, 3], b[i, 4]) - c3 = wptype(2) * wp.min(a3read, b3read) - d3 = wptype(2) * wp.max(a3read, b3read) - - a4read = vec4(a[i, 5], a[i, 6], a[i, 7], a[i, 8]) - b4read = vec4(b[i, 5], b[i, 6], b[i, 7], b[i, 8]) - c4 = wptype(2) * wp.min(a4read, b4read) - d4 = wptype(2) * wp.max(a4read, b4read) - - a5read = vec5(a[i, 9], a[i, 10], a[i, 11], a[i, 12], a[i, 13]) - b5read = vec5(b[i, 9], b[i, 10], b[i, 11], b[i, 12], b[i, 13]) - c5 = wptype(2) * wp.min(a5read, b5read) - d5 = wptype(2) * wp.max(a5read, b5read) - - mins[i, 0] = c2[0] - mins[i, 1] = c2[1] - - mins[i, 2] = c3[0] - mins[i, 3] = c3[1] - mins[i, 4] = c3[2] - - mins[i, 5] = c4[0] - mins[i, 6] = c4[1] - mins[i, 7] = c4[2] - mins[i, 8] = c4[3] - - mins[i, 9] = c5[0] - mins[i, 10] = c5[1] - mins[i, 11] = c5[2] - mins[i, 12] = c5[3] - mins[i, 13] = c5[4] - - maxs[i, 0] = d2[0] - maxs[i, 1] = d2[1] - - maxs[i, 2] = d3[0] - maxs[i, 3] = d3[1] - maxs[i, 4] = d3[2] - - maxs[i, 5] = d4[0] - maxs[i, 6] = d4[1] - maxs[i, 7] = d4[2] - maxs[i, 8] = d4[3] - - maxs[i, 9] = d5[0] - maxs[i, 10] = d5[1] - maxs[i, 11] = d5[2] - maxs[i, 12] = d5[3] - maxs[i, 13] = d5[4] - - kernel = getkernel(check_vec_min_max, suffix=dtype.__name__) - output_select_kernel = get_select_kernel2(wptype) - - if register_kernels: - return - - a = wp.array(randvals(rng, (10, 14), dtype), dtype=wptype, requires_grad=True, device=device) - b = wp.array(randvals(rng, (10, 14), dtype), dtype=wptype, requires_grad=True, device=device) - - mins = wp.zeros((10, 14), dtype=wptype, requires_grad=True, device=device) - maxs = wp.zeros((10, 14), dtype=wptype, requires_grad=True, device=device) - - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[a, b], outputs=[mins, maxs], device=device) - - assert_np_equal(mins.numpy(), 2 * np.minimum(a.numpy(), b.numpy()), tol=tol) - assert_np_equal(maxs.numpy(), 2 * np.maximum(a.numpy(), b.numpy()), tol=tol) - - out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) - if dtype in np_float_types: - for i in range(10): - for j in range(14): - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[a, b], outputs=[mins, maxs], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[mins, i, j], outputs=[out], device=device) - - tape.backward(loss=out) - expected = np.zeros_like(a.numpy()) - expected[i, j] = 2 if (a.numpy()[i, j] < b.numpy()[i, j]) else 0 - assert_np_equal(tape.gradients[a].numpy(), expected, tol=tol) - expected[i, j] = 2 if (b.numpy()[i, j] < a.numpy()[i, j]) else 0 - assert_np_equal(tape.gradients[b].numpy(), expected, tol=tol) - tape.zero() - - tape = wp.Tape() - with tape: - wp.launch(kernel, dim=1, inputs=[a, b], outputs=[mins, maxs], device=device) - wp.launch(output_select_kernel, dim=1, inputs=[maxs, i, j], outputs=[out], device=device) - - tape.backward(loss=out) - expected = np.zeros_like(a.numpy()) - expected[i, j] = 2 if (a.numpy()[i, j] > b.numpy()[i, j]) else 0 - assert_np_equal(tape.gradients[a].numpy(), expected, tol=tol) - expected[i, j] = 2 if (b.numpy()[i, j] > a.numpy()[i, j]) else 0 - assert_np_equal(tape.gradients[b].numpy(), expected, tol=tol) - tape.zero() - - def test_casting_constructors(test, device, dtype, register_kernels=False): np_type = np.dtype(dtype) wp_type = wp.types.np_dtype_to_warp_type[np_type] @@ -2974,85 +1087,6 @@ def cast_float64(a: wp.array(dtype=wp_type, ndim=2), b: wp.array(dtype=wp64, ndi assert_np_equal(out, a_grad.numpy()) -def test_equivalent_types(test, device, dtype, register_kernels=False): - wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] - - # vector types - vec2 = wp.types.vector(length=2, dtype=wptype) - vec3 = wp.types.vector(length=3, dtype=wptype) - vec4 = wp.types.vector(length=4, dtype=wptype) - vec5 = wp.types.vector(length=5, dtype=wptype) - - # vector types equivalent to the above - vec2_equiv = wp.types.vector(length=2, dtype=wptype) - vec3_equiv = wp.types.vector(length=3, dtype=wptype) - vec4_equiv = wp.types.vector(length=4, dtype=wptype) - vec5_equiv = wp.types.vector(length=5, dtype=wptype) - - # declare kernel with original types - def check_equivalence( - v2: vec2, - v3: vec3, - v4: vec4, - v5: vec5, - ): - wp.expect_eq(v2, vec2(wptype(1), wptype(2))) - wp.expect_eq(v3, vec3(wptype(1), wptype(2), wptype(3))) - wp.expect_eq(v4, vec4(wptype(1), wptype(2), wptype(3), wptype(4))) - wp.expect_eq(v5, vec5(wptype(1), wptype(2), wptype(3), wptype(4), wptype(5))) - - wp.expect_eq(v2, vec2_equiv(wptype(1), wptype(2))) - wp.expect_eq(v3, vec3_equiv(wptype(1), wptype(2), wptype(3))) - wp.expect_eq(v4, vec4_equiv(wptype(1), wptype(2), wptype(3), wptype(4))) - wp.expect_eq(v5, vec5_equiv(wptype(1), wptype(2), wptype(3), wptype(4), wptype(5))) - - kernel = getkernel(check_equivalence, suffix=dtype.__name__) - - if register_kernels: - return - - # call kernel with equivalent types - v2 = vec2_equiv(1, 2) - v3 = vec3_equiv(1, 2, 3) - v4 = vec4_equiv(1, 2, 3, 4) - v5 = vec5_equiv(1, 2, 3, 4, 5) - - wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5], device=device) - - -def test_conversions(test, device, dtype, register_kernels=False): - def check_vectors_equal( - v0: wp.vec3, - v1: wp.vec3, - v2: wp.vec3, - v3: wp.vec3, - ): - wp.expect_eq(v1, v0) - wp.expect_eq(v2, v0) - wp.expect_eq(v3, v0) - - kernel = getkernel(check_vectors_equal, suffix=dtype.__name__) - - if register_kernels: - return - - v0 = wp.vec3(1, 2, 3) - - # test explicit conversions - constructing vectors from different containers - v1 = wp.vec3((1, 2, 3)) - v2 = wp.vec3([1, 2, 3]) - v3 = wp.vec3(np.array([1, 2, 3], dtype=dtype)) - - wp.launch(kernel, dim=1, inputs=[v0, v1, v2, v3], device=device) - - # test implicit conversions - passing different containers as vectors to wp.launch() - v1 = (1, 2, 3) - v2 = [1, 2, 3] - v3 = np.array([1, 2, 3], dtype=dtype) - - wp.launch(kernel, dim=1, inputs=[v0, v1, v2, v3], device=device) - - @wp.kernel def test_vector_constructor_value_func(): a = wp.vec2() @@ -3122,175 +1156,113 @@ def test_constructors_constant_length(): v[i] = float(i) -def register(parent): - devices = get_test_devices() - - class TestVec(parent): - pass +devices = get_test_devices() - add_kernel_test(TestVec, test_vector_constructor_value_func, dim=1, devices=devices) - add_kernel_test(TestVec, test_constructors_explicit_precision, dim=1, devices=devices) - add_kernel_test(TestVec, test_constructors_default_precision, dim=1, devices=devices) - add_kernel_test(TestVec, test_constructors_constant_length, dim=1, devices=devices) - vec10 = wp.types.vector(length=10, dtype=float) - add_kernel_test( - TestVec, - test_vector_mutation, - dim=1, - inputs=[vec10(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0)], - devices=devices, - ) +class TestVec(unittest.TestCase): + pass - for dtype in np_unsigned_int_types: - add_function_test_register_kernel( - TestVec, - f"test_subtraction_unsigned_{dtype.__name__}", - test_subtraction_unsigned, - devices=devices, - dtype=dtype, - ) - for dtype in np_signed_int_types + np_float_types: - add_function_test_register_kernel( - TestVec, f"test_negation_{dtype.__name__}", test_negation, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_subtraction_{dtype.__name__}", test_subtraction, devices=devices, dtype=dtype - ) +add_kernel_test(TestVec, test_vector_constructor_value_func, dim=1, devices=devices) +add_kernel_test(TestVec, test_constructors_explicit_precision, dim=1, devices=devices) +add_kernel_test(TestVec, test_constructors_default_precision, dim=1, devices=devices) +add_kernel_test(TestVec, test_constructors_constant_length, dim=1, devices=devices) - for dtype in np_float_types: - add_function_test_register_kernel( - TestVec, f"test_crossproduct_{dtype.__name__}", test_crossproduct, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_length_{dtype.__name__}", test_length, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_normalize_{dtype.__name__}", test_normalize, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, - f"test_casting_constructors_{dtype.__name__}", - test_casting_constructors, - devices=devices, - dtype=dtype, - ) +vec10 = wp.types.vector(length=10, dtype=float) +add_kernel_test( + TestVec, + test_vector_mutation, + dim=1, + inputs=[vec10(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0, 10.0)], + devices=devices, +) - add_function_test( +for dtype in np_unsigned_int_types: + add_function_test_register_kernel( TestVec, - "test_anon_constructor_error_dtype_keyword_missing", - test_anon_constructor_error_dtype_keyword_missing, + f"test_subtraction_unsigned_{dtype.__name__}", + test_subtraction_unsigned, devices=devices, + dtype=dtype, ) - add_function_test( - TestVec, - "test_anon_constructor_error_length_mismatch", - test_anon_constructor_error_length_mismatch, - devices=devices, - ) - add_function_test( - TestVec, - "test_anon_constructor_error_numeric_arg_missing_1", - test_anon_constructor_error_numeric_arg_missing_1, - devices=devices, + +for dtype in np_signed_int_types + np_float_types: + add_function_test_register_kernel( + TestVec, f"test_negation_{dtype.__name__}", test_negation, devices=devices, dtype=dtype ) - add_function_test( - TestVec, - "test_anon_constructor_error_numeric_arg_missing_2", - test_anon_constructor_error_numeric_arg_missing_2, - devices=devices, + add_function_test_register_kernel( + TestVec, f"test_subtraction_{dtype.__name__}", test_subtraction, devices=devices, dtype=dtype ) - add_function_test( - TestVec, - "test_anon_constructor_error_dtype_keyword_extraneous", - test_anon_constructor_error_dtype_keyword_extraneous, - devices=devices, + +for dtype in np_float_types: + add_function_test_register_kernel( + TestVec, f"test_crossproduct_{dtype.__name__}", test_crossproduct, devices=devices, dtype=dtype ) - add_function_test( - TestVec, - "test_anon_constructor_error_numeric_args_mismatch", - test_anon_constructor_error_numeric_args_mismatch, - devices=devices, + add_function_test_register_kernel( + TestVec, f"test_length_{dtype.__name__}", test_length, devices=devices, dtype=dtype ) - add_function_test( - TestVec, - "test_tpl_constructor_error_incompatible_sizes", - test_tpl_constructor_error_incompatible_sizes, - devices=devices, + add_function_test_register_kernel( + TestVec, f"test_normalize_{dtype.__name__}", test_normalize, devices=devices, dtype=dtype ) - add_function_test( + add_function_test_register_kernel( TestVec, - "test_tpl_constructor_error_numeric_args_mismatch", - test_tpl_constructor_error_numeric_args_mismatch, + f"test_casting_constructors_{dtype.__name__}", + test_casting_constructors, devices=devices, + dtype=dtype, ) - add_function_test(TestVec, "test_tpl_ops_with_anon", test_tpl_ops_with_anon) - - for dtype in np_scalar_types: - add_function_test(TestVec, f"test_arrays_{dtype.__name__}", test_arrays, devices=devices, dtype=dtype) - add_function_test(TestVec, f"test_components_{dtype.__name__}", test_components, devices=None, dtype=dtype) - add_function_test( - TestVec, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_constructors_{dtype.__name__}", test_constructors, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_anon_type_instance_{dtype.__name__}", test_anon_type_instance, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_indexing_{dtype.__name__}", test_indexing, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_equality_{dtype.__name__}", test_equality, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, - f"test_scalar_multiplication_{dtype.__name__}", - test_scalar_multiplication, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestVec, - f"test_scalar_multiplication_rightmul_{dtype.__name__}", - test_scalar_multiplication_rightmul, - devices=devices, - dtype=dtype, - ) - add_function_test_register_kernel( - TestVec, f"test_cw_multiplication_{dtype.__name__}", test_cw_multiplication, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_scalar_division_{dtype.__name__}", test_scalar_division, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_cw_division_{dtype.__name__}", test_cw_division, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_addition_{dtype.__name__}", test_addition, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_dotproduct_{dtype.__name__}", test_dotproduct, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_equivalent_types_{dtype.__name__}", test_equivalent_types, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_conversions_{dtype.__name__}", test_conversions, devices=devices, dtype=dtype - ) - add_function_test_register_kernel( - TestVec, f"test_constants_{dtype.__name__}", test_constants, devices=devices, dtype=dtype - ) - - # the kernels in this test compile incredibly slowly... - # add_function_test_register_kernel(TestVec, f"test_minmax_{dtype.__name__}", test_minmax, devices=devices, dtype=dtype) - return TestVec +add_function_test( + TestVec, + "test_anon_constructor_error_dtype_keyword_missing", + test_anon_constructor_error_dtype_keyword_missing, + devices=devices, +) +add_function_test( + TestVec, + "test_anon_constructor_error_length_mismatch", + test_anon_constructor_error_length_mismatch, + devices=devices, +) +add_function_test( + TestVec, + "test_anon_constructor_error_numeric_arg_missing_1", + test_anon_constructor_error_numeric_arg_missing_1, + devices=devices, +) +add_function_test( + TestVec, + "test_anon_constructor_error_numeric_arg_missing_2", + test_anon_constructor_error_numeric_arg_missing_2, + devices=devices, +) +add_function_test( + TestVec, + "test_anon_constructor_error_dtype_keyword_extraneous", + test_anon_constructor_error_dtype_keyword_extraneous, + devices=devices, +) +add_function_test( + TestVec, + "test_anon_constructor_error_numeric_args_mismatch", + test_anon_constructor_error_numeric_args_mismatch, + devices=devices, +) +add_function_test( + TestVec, + "test_tpl_constructor_error_incompatible_sizes", + test_tpl_constructor_error_incompatible_sizes, + devices=devices, +) +add_function_test( + TestVec, + "test_tpl_constructor_error_numeric_args_mismatch", + test_tpl_constructor_error_numeric_args_mismatch, + devices=devices, +) +add_function_test(TestVec, "test_tpl_ops_with_anon", test_tpl_ops_with_anon) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_vec_lite.py b/warp/tests/test_vec_lite.py index 71e706eda..4eda8a5af 100644 --- a/warp/tests/test_vec_lite.py +++ b/warp/tests/test_vec_lite.py @@ -7,9 +7,8 @@ import unittest -import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -57,20 +56,18 @@ def test_constructors_default_precision(): wp.expect_eq(custom[i], float(i)) -def register(parent): - devices = get_test_devices() +devices = get_test_devices() - class TestVec(parent): - pass - add_kernel_test(TestVec, test_vector_constructor_value_func, dim=1, devices=devices) - add_kernel_test(TestVec, test_constructors_explicit_precision, dim=1, devices=devices) - add_kernel_test(TestVec, test_constructors_default_precision, dim=1, devices=devices) +class TestVecLite(unittest.TestCase): + pass - return TestVec + +add_kernel_test(TestVecLite, test_vector_constructor_value_func, dim=1, devices=devices) +add_kernel_test(TestVecLite, test_constructors_explicit_precision, dim=1, devices=devices) +add_kernel_test(TestVecLite, test_constructors_default_precision, dim=1, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_vec_scalar_ops.py b/warp/tests/test_vec_scalar_ops.py new file mode 100644 index 000000000..c3b9fdfc9 --- /dev/null +++ b/warp/tests/test_vec_scalar_ops.py @@ -0,0 +1,2099 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +import unittest + +import numpy as np + +import warp as wp +from warp.tests.unittest_utils import * + +wp.init() + +np_signed_int_types = [ + np.int8, + np.int16, + np.int32, + np.int64, + np.byte, +] + +np_unsigned_int_types = [ + np.uint8, + np.uint16, + np.uint32, + np.uint64, + np.ubyte, +] + +np_int_types = np_signed_int_types + np_unsigned_int_types + +np_float_types = [np.float16, np.float32, np.float64] + +np_scalar_types = np_int_types + np_float_types + + +def randvals(rng, shape, dtype): + if dtype in np_float_types: + return rng.standard_normal(size=shape).astype(dtype) + elif dtype in [np.int8, np.uint8, np.byte, np.ubyte]: + return rng.integers(1, high=3, size=shape, dtype=dtype) + return rng.integers(1, high=5, size=shape, dtype=dtype) + + +kernel_cache = dict() + + +def getkernel(func, suffix=""): + key = func.__name__ + "_" + suffix + if key not in kernel_cache: + kernel_cache[key] = wp.Kernel(func=func, key=key) + return kernel_cache[key] + + +def get_select_kernel(dtype): + def output_select_kernel_fn( + input: wp.array(dtype=dtype), + index: int, + out: wp.array(dtype=dtype), + ): + out[0] = input[index] + + return getkernel(output_select_kernel_fn, suffix=dtype.__name__) + + +def get_select_kernel2(dtype): + def output_select_kernel2_fn( + input: wp.array(dtype=dtype, ndim=2), + index0: int, + index1: int, + out: wp.array(dtype=dtype), + ): + out[0] = input[index0, index1] + + return getkernel(output_select_kernel2_fn, suffix=dtype.__name__) + + +def test_arrays(test, device, dtype): + rng = np.random.default_rng(123) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + v2_np = randvals(rng, (10, 2), dtype) + v3_np = randvals(rng, (10, 3), dtype) + v4_np = randvals(rng, (10, 4), dtype) + v5_np = randvals(rng, (10, 5), dtype) + + v2 = wp.array(v2_np, dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(v3_np, dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(v4_np, dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(v5_np, dtype=vec5, requires_grad=True, device=device) + + assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) + assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) + assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) + assert_np_equal(v5.numpy(), v5_np, tol=1.0e-6) + + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + + v2 = wp.array(v2_np, dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(v3_np, dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(v4_np, dtype=vec4, requires_grad=True, device=device) + + assert_np_equal(v2.numpy(), v2_np, tol=1.0e-6) + assert_np_equal(v3.numpy(), v3_np, tol=1.0e-6) + assert_np_equal(v4.numpy(), v4_np, tol=1.0e-6) + + +def test_components(test, device, dtype): + # test accessing vector components from Python - this is especially important + # for float16, which requires special handling internally + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec3 = wp.types.vector(length=3, dtype=wptype) + + v = vec3(1, 2, 3) + + # test __getitem__ for individual components + test.assertEqual(v[0], 1) + test.assertEqual(v[1], 2) + test.assertEqual(v[2], 3) + + # test __getitem__ for slices + s = v[:] + test.assertEqual(s[0], 1) + test.assertEqual(s[1], 2) + test.assertEqual(s[2], 3) + + s = v[1:] + test.assertEqual(s[0], 2) + test.assertEqual(s[1], 3) + + s = v[:2] + test.assertEqual(s[0], 1) + test.assertEqual(s[1], 2) + + s = v[::2] + test.assertEqual(s[0], 1) + test.assertEqual(s[1], 3) + + # test __setitem__ for individual components + v[0] = 4 + v[1] = 5 + v[2] = 6 + test.assertEqual(v[0], 4) + test.assertEqual(v[1], 5) + test.assertEqual(v[2], 6) + + # test __setitem__ for slices + v[:] = [7, 8, 9] + test.assertEqual(v[0], 7) + test.assertEqual(v[1], 8) + test.assertEqual(v[2], 9) + + v[1:] = [10, 11] + test.assertEqual(v[0], 7) + test.assertEqual(v[1], 10) + test.assertEqual(v[2], 11) + + v[:2] = [12, 13] + test.assertEqual(v[0], 12) + test.assertEqual(v[1], 13) + test.assertEqual(v[2], 11) + + v[::2] = [14, 15] + test.assertEqual(v[0], 14) + test.assertEqual(v[1], 13) + test.assertEqual(v[2], 15) + + +def test_py_arithmetic_ops(test, device, dtype): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def make_vec(*args): + if wptype in wp.types.int_types: + # Cast to the correct integer type to simulate wrapping. + return tuple(wptype._type_(x).value for x in args) + + return args + + vec_cls = wp.vec(3, wptype) + + v = vec_cls(1, -2, 3) + test.assertSequenceEqual(+v, make_vec(1, -2, 3)) + test.assertSequenceEqual(-v, make_vec(-1, 2, -3)) + test.assertSequenceEqual(v + vec_cls(5, 5, 5), make_vec(6, 3, 8)) + test.assertSequenceEqual(v - vec_cls(5, 5, 5), make_vec(-4, -7, -2)) + + v = vec_cls(2, 4, 6) + test.assertSequenceEqual(v * wptype(2), make_vec(4, 8, 12)) + test.assertSequenceEqual(wptype(2) * v, make_vec(4, 8, 12)) + test.assertSequenceEqual(v / wptype(2), make_vec(1, 2, 3)) + test.assertSequenceEqual(wptype(24) / v, make_vec(12, 6, 4)) + + +def test_constructors(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_scalar_constructor( + input: wp.array(dtype=wptype), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = vec2(input[0]) + v3result = vec3(input[0]) + v4result = vec4(input[0]) + v5result = vec5(input[0]) + + v2[0] = v2result + v3[0] = v3result + v4[0] = v4result + v5[0] = v5result + + # multiply outputs by 2 so we've got something to backpropagate + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + def check_vector_constructors( + input: wp.array(dtype=wptype), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = vec2(input[0], input[1]) + v3result = vec3(input[2], input[3], input[4]) + v4result = vec4(input[5], input[6], input[7], input[8]) + v5result = vec5(input[9], input[10], input[11], input[12], input[13]) + + v2[0] = v2result + v3[0] = v3result + v4[0] = v4result + v5[0] = v5result + + # multiply the output by 2 so we've got something to backpropagate: + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + vec_kernel = getkernel(check_vector_constructors, suffix=dtype.__name__) + kernel = getkernel(check_scalar_constructor, suffix=dtype.__name__) + + if register_kernels: + return + + input = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) + v2 = wp.zeros(1, dtype=vec2, device=device) + v3 = wp.zeros(1, dtype=vec3, device=device) + v4 = wp.zeros(1, dtype=vec4, device=device) + v5 = wp.zeros(1, dtype=vec5, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[input], + outputs=[v2, v3, v4, v5, v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + if dtype in np_float_types: + for l in [v20, v21]: + tape.backward(loss=l) + test.assertEqual(tape.gradients[input].numpy()[0], 2.0) + tape.zero() + + for l in [v30, v31, v32]: + tape.backward(loss=l) + test.assertEqual(tape.gradients[input].numpy()[0], 2.0) + tape.zero() + + for l in [v40, v41, v42, v43]: + tape.backward(loss=l) + test.assertEqual(tape.gradients[input].numpy()[0], 2.0) + tape.zero() + + for l in [v50, v51, v52, v53, v54]: + tape.backward(loss=l) + test.assertEqual(tape.gradients[input].numpy()[0], 2.0) + tape.zero() + + val = input.numpy()[0] + assert_np_equal(v2.numpy()[0], np.array([val, val]), tol=1.0e-6) + assert_np_equal(v3.numpy()[0], np.array([val, val, val]), tol=1.0e-6) + assert_np_equal(v4.numpy()[0], np.array([val, val, val, val]), tol=1.0e-6) + assert_np_equal(v5.numpy()[0], np.array([val, val, val, val, val]), tol=1.0e-6) + + assert_np_equal(v20.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v21.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v30.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v31.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v32.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v40.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v41.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v42.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v43.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v50.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v51.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v52.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v53.numpy()[0], 2 * val, tol=1.0e-6) + assert_np_equal(v54.numpy()[0], 2 * val, tol=1.0e-6) + + input = wp.array(randvals(rng, [14], dtype), requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + vec_kernel, + dim=1, + inputs=[input], + outputs=[v2, v3, v4, v5, v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + if dtype in np_float_types: + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): + tape.backward(loss=l) + grad = tape.gradients[input].numpy() + expected_grad = np.zeros_like(grad) + expected_grad[i] = 2 + assert_np_equal(grad, expected_grad, tol=tol) + tape.zero() + + assert_np_equal(v2.numpy()[0, 0], input.numpy()[0], tol=tol) + assert_np_equal(v2.numpy()[0, 1], input.numpy()[1], tol=tol) + assert_np_equal(v3.numpy()[0, 0], input.numpy()[2], tol=tol) + assert_np_equal(v3.numpy()[0, 1], input.numpy()[3], tol=tol) + assert_np_equal(v3.numpy()[0, 2], input.numpy()[4], tol=tol) + assert_np_equal(v4.numpy()[0, 0], input.numpy()[5], tol=tol) + assert_np_equal(v4.numpy()[0, 1], input.numpy()[6], tol=tol) + assert_np_equal(v4.numpy()[0, 2], input.numpy()[7], tol=tol) + assert_np_equal(v4.numpy()[0, 3], input.numpy()[8], tol=tol) + assert_np_equal(v5.numpy()[0, 0], input.numpy()[9], tol=tol) + assert_np_equal(v5.numpy()[0, 1], input.numpy()[10], tol=tol) + assert_np_equal(v5.numpy()[0, 2], input.numpy()[11], tol=tol) + assert_np_equal(v5.numpy()[0, 3], input.numpy()[12], tol=tol) + assert_np_equal(v5.numpy()[0, 4], input.numpy()[13], tol=tol) + + assert_np_equal(v20.numpy()[0], 2 * input.numpy()[0], tol=tol) + assert_np_equal(v21.numpy()[0], 2 * input.numpy()[1], tol=tol) + assert_np_equal(v30.numpy()[0], 2 * input.numpy()[2], tol=tol) + assert_np_equal(v31.numpy()[0], 2 * input.numpy()[3], tol=tol) + assert_np_equal(v32.numpy()[0], 2 * input.numpy()[4], tol=tol) + assert_np_equal(v40.numpy()[0], 2 * input.numpy()[5], tol=tol) + assert_np_equal(v41.numpy()[0], 2 * input.numpy()[6], tol=tol) + assert_np_equal(v42.numpy()[0], 2 * input.numpy()[7], tol=tol) + assert_np_equal(v43.numpy()[0], 2 * input.numpy()[8], tol=tol) + assert_np_equal(v50.numpy()[0], 2 * input.numpy()[9], tol=tol) + assert_np_equal(v51.numpy()[0], 2 * input.numpy()[10], tol=tol) + assert_np_equal(v52.numpy()[0], 2 * input.numpy()[11], tol=tol) + assert_np_equal(v53.numpy()[0], 2 * input.numpy()[12], tol=tol) + assert_np_equal(v54.numpy()[0], 2 * input.numpy()[13], tol=tol) + + +def test_anon_type_instance(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + def check_scalar_init( + input: wp.array(dtype=wptype), + output: wp.array(dtype=wptype), + ): + v2result = wp.vector(input[0], length=2) + v3result = wp.vector(input[1], length=3) + v4result = wp.vector(input[2], length=4) + v5result = wp.vector(input[3], length=5) + + idx = 0 + for i in range(2): + output[idx] = wptype(2) * v2result[i] + idx = idx + 1 + for i in range(3): + output[idx] = wptype(2) * v3result[i] + idx = idx + 1 + for i in range(4): + output[idx] = wptype(2) * v4result[i] + idx = idx + 1 + for i in range(5): + output[idx] = wptype(2) * v5result[i] + idx = idx + 1 + + def check_component_init( + input: wp.array(dtype=wptype), + output: wp.array(dtype=wptype), + ): + v2result = wp.vector(input[0], input[1]) + v3result = wp.vector(input[2], input[3], input[4]) + v4result = wp.vector(input[5], input[6], input[7], input[8]) + v5result = wp.vector(input[9], input[10], input[11], input[12], input[13]) + + idx = 0 + for i in range(2): + output[idx] = wptype(2) * v2result[i] + idx = idx + 1 + for i in range(3): + output[idx] = wptype(2) * v3result[i] + idx = idx + 1 + for i in range(4): + output[idx] = wptype(2) * v4result[i] + idx = idx + 1 + for i in range(5): + output[idx] = wptype(2) * v5result[i] + idx = idx + 1 + + scalar_kernel = getkernel(check_scalar_init, suffix=dtype.__name__) + component_kernel = getkernel(check_component_init, suffix=dtype.__name__) + output_select_kernel = get_select_kernel(wptype) + + if register_kernels: + return + + input = wp.array(randvals(rng, [4], dtype), requires_grad=True, device=device) + output = wp.zeros(2 + 3 + 4 + 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) + + assert_np_equal(output.numpy()[:2], 2 * np.array([input.numpy()[0]] * 2), tol=1.0e-6) + assert_np_equal(output.numpy()[2:5], 2 * np.array([input.numpy()[1]] * 3), tol=1.0e-6) + assert_np_equal(output.numpy()[5:9], 2 * np.array([input.numpy()[2]] * 4), tol=1.0e-6) + assert_np_equal(output.numpy()[9:], 2 * np.array([input.numpy()[3]] * 5), tol=1.0e-6) + + if dtype in np_float_types: + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for i in range(len(output)): + tape = wp.Tape() + with tape: + wp.launch(scalar_kernel, dim=1, inputs=[input], outputs=[output], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) + + tape.backward(loss=out) + expected = np.zeros_like(input.numpy()) + if i < 2: + expected[0] = 2 + elif i < 5: + expected[1] = 2 + elif i < 9: + expected[2] = 2 + else: + expected[3] = 2 + + assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) + + tape.reset() + tape.zero() + + input = wp.array(randvals(rng, [2 + 3 + 4 + 5], dtype), requires_grad=True, device=device) + output = wp.zeros(2 + 3 + 4 + 5, dtype=wptype, requires_grad=True, device=device) + + wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) + + assert_np_equal(output.numpy(), 2 * input.numpy(), tol=1.0e-6) + + if dtype in np_float_types: + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + for i in range(len(output)): + tape = wp.Tape() + with tape: + wp.launch(component_kernel, dim=1, inputs=[input], outputs=[output], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[output, i], outputs=[out], device=device) + + tape.backward(loss=out) + expected = np.zeros_like(input.numpy()) + expected[i] = 2 + + assert_np_equal(tape.gradients[input].numpy(), expected, tol=tol) + + tape.reset() + tape.zero() + + +def test_indexing(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_indexing( + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + # multiply outputs by 2 so we've got something to backpropagate: + v20[0] = wptype(2) * v2[0][0] + v21[0] = wptype(2) * v2[0][1] + + v30[0] = wptype(2) * v3[0][0] + v31[0] = wptype(2) * v3[0][1] + v32[0] = wptype(2) * v3[0][2] + + v40[0] = wptype(2) * v4[0][0] + v41[0] = wptype(2) * v4[0][1] + v42[0] = wptype(2) * v4[0][2] + v43[0] = wptype(2) * v4[0][3] + + v50[0] = wptype(2) * v5[0][0] + v51[0] = wptype(2) * v5[0][1] + v52[0] = wptype(2) * v5[0][2] + v53[0] = wptype(2) * v5[0][3] + v54[0] = wptype(2) * v5[0][4] + + kernel = getkernel(check_indexing, suffix=dtype.__name__) + + if register_kernels: + return + + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[v2, v3, v4, v5], + outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + if dtype in np_float_types: + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): + tape.backward(loss=l) + allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) + expected_grads = np.zeros_like(allgrads) + expected_grads[i] = 2 + assert_np_equal(allgrads, expected_grads, tol=tol) + tape.zero() + + assert_np_equal(v20.numpy()[0], 2.0 * v2.numpy()[0, 0], tol=tol) + assert_np_equal(v21.numpy()[0], 2.0 * v2.numpy()[0, 1], tol=tol) + assert_np_equal(v30.numpy()[0], 2.0 * v3.numpy()[0, 0], tol=tol) + assert_np_equal(v31.numpy()[0], 2.0 * v3.numpy()[0, 1], tol=tol) + assert_np_equal(v32.numpy()[0], 2.0 * v3.numpy()[0, 2], tol=tol) + assert_np_equal(v40.numpy()[0], 2.0 * v4.numpy()[0, 0], tol=tol) + assert_np_equal(v41.numpy()[0], 2.0 * v4.numpy()[0, 1], tol=tol) + assert_np_equal(v42.numpy()[0], 2.0 * v4.numpy()[0, 2], tol=tol) + assert_np_equal(v43.numpy()[0], 2.0 * v4.numpy()[0, 3], tol=tol) + assert_np_equal(v50.numpy()[0], 2.0 * v5.numpy()[0, 0], tol=tol) + assert_np_equal(v51.numpy()[0], 2.0 * v5.numpy()[0, 1], tol=tol) + assert_np_equal(v52.numpy()[0], 2.0 * v5.numpy()[0, 2], tol=tol) + assert_np_equal(v53.numpy()[0], 2.0 * v5.numpy()[0, 3], tol=tol) + assert_np_equal(v54.numpy()[0], 2.0 * v5.numpy()[0, 4], tol=tol) + + +def test_equality(test, device, dtype, register_kernels=False): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_equality( + v20: wp.array(dtype=vec2), + v21: wp.array(dtype=vec2), + v22: wp.array(dtype=vec2), + v30: wp.array(dtype=vec3), + v31: wp.array(dtype=vec3), + v32: wp.array(dtype=vec3), + v33: wp.array(dtype=vec3), + v40: wp.array(dtype=vec4), + v41: wp.array(dtype=vec4), + v42: wp.array(dtype=vec4), + v43: wp.array(dtype=vec4), + v44: wp.array(dtype=vec4), + v50: wp.array(dtype=vec5), + v51: wp.array(dtype=vec5), + v52: wp.array(dtype=vec5), + v53: wp.array(dtype=vec5), + v54: wp.array(dtype=vec5), + v55: wp.array(dtype=vec5), + ): + wp.expect_eq(v20[0], v20[0]) + wp.expect_neq(v21[0], v20[0]) + wp.expect_neq(v22[0], v20[0]) + + wp.expect_eq(v30[0], v30[0]) + wp.expect_neq(v31[0], v30[0]) + wp.expect_neq(v32[0], v30[0]) + wp.expect_neq(v33[0], v30[0]) + + wp.expect_eq(v40[0], v40[0]) + wp.expect_neq(v41[0], v40[0]) + wp.expect_neq(v42[0], v40[0]) + wp.expect_neq(v43[0], v40[0]) + wp.expect_neq(v44[0], v40[0]) + + wp.expect_eq(v50[0], v50[0]) + wp.expect_neq(v51[0], v50[0]) + wp.expect_neq(v52[0], v50[0]) + wp.expect_neq(v53[0], v50[0]) + wp.expect_neq(v54[0], v50[0]) + wp.expect_neq(v55[0], v50[0]) + + kernel = getkernel(check_equality, suffix=dtype.__name__) + + if register_kernels: + return + + v20 = wp.array([1.0, 2.0], dtype=vec2, requires_grad=True, device=device) + v21 = wp.array([1.0, 3.0], dtype=vec2, requires_grad=True, device=device) + v22 = wp.array([3.0, 2.0], dtype=vec2, requires_grad=True, device=device) + + v30 = wp.array([1.0, 2.0, 3.0], dtype=vec3, requires_grad=True, device=device) + v31 = wp.array([-1.0, 2.0, 3.0], dtype=vec3, requires_grad=True, device=device) + v32 = wp.array([1.0, -2.0, 3.0], dtype=vec3, requires_grad=True, device=device) + v33 = wp.array([1.0, 2.0, -3.0], dtype=vec3, requires_grad=True, device=device) + + v40 = wp.array([1.0, 2.0, 3.0, 4.0], dtype=vec4, requires_grad=True, device=device) + v41 = wp.array([-1.0, 2.0, 3.0, 4.0], dtype=vec4, requires_grad=True, device=device) + v42 = wp.array([1.0, -2.0, 3.0, 4.0], dtype=vec4, requires_grad=True, device=device) + v43 = wp.array([1.0, 2.0, -3.0, 4.0], dtype=vec4, requires_grad=True, device=device) + v44 = wp.array([1.0, 2.0, 3.0, -4.0], dtype=vec4, requires_grad=True, device=device) + + v50 = wp.array([1.0, 2.0, 3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) + v51 = wp.array([-1.0, 2.0, 3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) + v52 = wp.array([1.0, -2.0, 3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) + v53 = wp.array([1.0, 2.0, -3.0, 4.0, 5.0], dtype=vec5, requires_grad=True, device=device) + v54 = wp.array([1.0, 2.0, 3.0, -4.0, 5.0], dtype=vec5, requires_grad=True, device=device) + v55 = wp.array([1.0, 2.0, 3.0, 4.0, -5.0], dtype=vec5, requires_grad=True, device=device) + wp.launch( + kernel, + dim=1, + inputs=[ + v20, + v21, + v22, + v30, + v31, + v32, + v33, + v40, + v41, + v42, + v43, + v44, + v50, + v51, + v52, + v53, + v54, + v55, + ], + outputs=[], + device=device, + ) + + +def test_scalar_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_mul( + s: wp.array(dtype=wptype), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = s[0] * v2[0] + v3result = s[0] * v3[0] + v4result = s[0] * v4[0] + v5result = s[0] * v5[0] + + # multiply outputs by 2 so we've got something to backpropagate: + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + kernel = getkernel(check_mul, suffix=dtype.__name__) + + if register_kernels: + return + + s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s, + v2, + v3, + v4, + v5, + ], + outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + assert_np_equal(v20.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 0], tol=tol) + assert_np_equal(v21.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 1], tol=tol) + + assert_np_equal(v30.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v31.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v32.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 2], tol=10 * tol) + + assert_np_equal(v40.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v41.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v42.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 2], tol=10 * tol) + assert_np_equal(v43.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 3], tol=10 * tol) + + assert_np_equal(v50.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v51.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v52.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 2], tol=10 * tol) + assert_np_equal(v53.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 3], tol=10 * tol) + assert_np_equal(v54.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 4], tol=10 * tol) + + incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) + + if dtype in np_float_types: + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43]): + tape.backward(loss=l) + sgrad = tape.gradients[s].numpy()[0] + assert_np_equal(sgrad, 2 * incmps[i], tol=10 * tol) + allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4]]) + expected_grads = np.zeros_like(allgrads) + expected_grads[i] = s.numpy()[0] * 2 + assert_np_equal(allgrads, expected_grads, tol=10 * tol) + tape.zero() + + +def test_scalar_multiplication_rightmul(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_rightmul( + s: wp.array(dtype=wptype), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = v2[0] * s[0] + v3result = v3[0] * s[0] + v4result = v4[0] * s[0] + v5result = v5[0] * s[0] + + # multiply outputs by 2 so we've got something to backpropagate: + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + kernel = getkernel(check_rightmul, suffix=dtype.__name__) + + if register_kernels: + return + + s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s, + v2, + v3, + v4, + v5, + ], + outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + assert_np_equal(v20.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 0], tol=tol) + assert_np_equal(v21.numpy()[0], 2 * s.numpy()[0] * v2.numpy()[0, 1], tol=tol) + + assert_np_equal(v30.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v31.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v32.numpy()[0], 2 * s.numpy()[0] * v3.numpy()[0, 2], tol=10 * tol) + + assert_np_equal(v40.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v41.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v42.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 2], tol=10 * tol) + assert_np_equal(v43.numpy()[0], 2 * s.numpy()[0] * v4.numpy()[0, 3], tol=10 * tol) + + assert_np_equal(v50.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v51.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v52.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 2], tol=10 * tol) + assert_np_equal(v53.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 3], tol=10 * tol) + assert_np_equal(v54.numpy()[0], 2 * s.numpy()[0] * v5.numpy()[0, 4], tol=10 * tol) + + incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) + + if dtype in np_float_types: + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43]): + tape.backward(loss=l) + sgrad = tape.gradients[s].numpy()[0] + assert_np_equal(sgrad, 2 * incmps[i], tol=10 * tol) + allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4]]) + expected_grads = np.zeros_like(allgrads) + expected_grads[i] = s.numpy()[0] * 2 + assert_np_equal(allgrads, expected_grads, tol=10 * tol) + tape.zero() + + +def test_cw_multiplication(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_cw_mul( + s2: wp.array(dtype=vec2), + s3: wp.array(dtype=vec3), + s4: wp.array(dtype=vec4), + s5: wp.array(dtype=vec5), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = wp.cw_mul(s2[0], v2[0]) + v3result = wp.cw_mul(s3[0], v3[0]) + v4result = wp.cw_mul(s4[0], v4[0]) + v5result = wp.cw_mul(s5[0], v5[0]) + + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + kernel = getkernel(check_cw_mul, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + assert_np_equal(v20.numpy()[0], 2 * s2.numpy()[0, 0] * v2.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v21.numpy()[0], 2 * s2.numpy()[0, 1] * v2.numpy()[0, 1], tol=10 * tol) + + assert_np_equal(v30.numpy()[0], 2 * s3.numpy()[0, 0] * v3.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v31.numpy()[0], 2 * s3.numpy()[0, 1] * v3.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v32.numpy()[0], 2 * s3.numpy()[0, 2] * v3.numpy()[0, 2], tol=10 * tol) + + assert_np_equal(v40.numpy()[0], 2 * s4.numpy()[0, 0] * v4.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v41.numpy()[0], 2 * s4.numpy()[0, 1] * v4.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v42.numpy()[0], 2 * s4.numpy()[0, 2] * v4.numpy()[0, 2], tol=10 * tol) + assert_np_equal(v43.numpy()[0], 2 * s4.numpy()[0, 3] * v4.numpy()[0, 3], tol=10 * tol) + + assert_np_equal(v50.numpy()[0], 2 * s5.numpy()[0, 0] * v5.numpy()[0, 0], tol=10 * tol) + assert_np_equal(v51.numpy()[0], 2 * s5.numpy()[0, 1] * v5.numpy()[0, 1], tol=10 * tol) + assert_np_equal(v52.numpy()[0], 2 * s5.numpy()[0, 2] * v5.numpy()[0, 2], tol=10 * tol) + assert_np_equal(v53.numpy()[0], 2 * s5.numpy()[0, 3] * v5.numpy()[0, 3], tol=10 * tol) + assert_np_equal(v54.numpy()[0], 2 * s5.numpy()[0, 4] * v5.numpy()[0, 4], tol=10 * tol) + + incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) + scmps = np.concatenate([v.numpy()[0] for v in [s2, s3, s4, s5]]) + + if dtype in np_float_types: + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): + tape.backward(loss=l) + sgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [s2, s3, s4, s5]]) + expected_grads = np.zeros_like(sgrads) + expected_grads[i] = incmps[i] * 2 + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) + expected_grads = np.zeros_like(allgrads) + expected_grads[i] = scmps[i] * 2 + assert_np_equal(allgrads, expected_grads, tol=10 * tol) + + tape.zero() + + +def test_scalar_division(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_div( + s: wp.array(dtype=wptype), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = v2[0] / s[0] + v3result = v3[0] / s[0] + v4result = v4[0] / s[0] + v5result = v5[0] / s[0] + + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + kernel = getkernel(check_div, suffix=dtype.__name__) + + if register_kernels: + return + + s = wp.array(randvals(rng, [1], dtype), requires_grad=True, device=device) + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s, + v2, + v3, + v4, + v5, + ], + outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + if dtype in np_int_types: + assert_np_equal(v20.numpy()[0], 2 * (v2.numpy()[0, 0] // (s.numpy()[0])), tol=tol) + assert_np_equal(v21.numpy()[0], 2 * (v2.numpy()[0, 1] // (s.numpy()[0])), tol=tol) + + assert_np_equal(v30.numpy()[0], 2 * (v3.numpy()[0, 0] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v31.numpy()[0], 2 * (v3.numpy()[0, 1] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v32.numpy()[0], 2 * (v3.numpy()[0, 2] // (s.numpy()[0])), tol=10 * tol) + + assert_np_equal(v40.numpy()[0], 2 * (v4.numpy()[0, 0] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v41.numpy()[0], 2 * (v4.numpy()[0, 1] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v42.numpy()[0], 2 * (v4.numpy()[0, 2] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v43.numpy()[0], 2 * (v4.numpy()[0, 3] // (s.numpy()[0])), tol=10 * tol) + + assert_np_equal(v50.numpy()[0], 2 * (v5.numpy()[0, 0] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v51.numpy()[0], 2 * (v5.numpy()[0, 1] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v52.numpy()[0], 2 * (v5.numpy()[0, 2] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v53.numpy()[0], 2 * (v5.numpy()[0, 3] // (s.numpy()[0])), tol=10 * tol) + assert_np_equal(v54.numpy()[0], 2 * (v5.numpy()[0, 4] // (s.numpy()[0])), tol=10 * tol) + + else: + assert_np_equal(v20.numpy()[0], 2 * v2.numpy()[0, 0] / (s.numpy()[0]), tol=tol) + assert_np_equal(v21.numpy()[0], 2 * v2.numpy()[0, 1] / (s.numpy()[0]), tol=tol) + + assert_np_equal(v30.numpy()[0], 2 * v3.numpy()[0, 0] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v31.numpy()[0], 2 * v3.numpy()[0, 1] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v32.numpy()[0], 2 * v3.numpy()[0, 2] / (s.numpy()[0]), tol=10 * tol) + + assert_np_equal(v40.numpy()[0], 2 * v4.numpy()[0, 0] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v41.numpy()[0], 2 * v4.numpy()[0, 1] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v42.numpy()[0], 2 * v4.numpy()[0, 2] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v43.numpy()[0], 2 * v4.numpy()[0, 3] / (s.numpy()[0]), tol=10 * tol) + + assert_np_equal(v50.numpy()[0], 2 * v5.numpy()[0, 0] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v51.numpy()[0], 2 * v5.numpy()[0, 1] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v52.numpy()[0], 2 * v5.numpy()[0, 2] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v53.numpy()[0], 2 * v5.numpy()[0, 3] / (s.numpy()[0]), tol=10 * tol) + assert_np_equal(v54.numpy()[0], 2 * v5.numpy()[0, 4] / (s.numpy()[0]), tol=10 * tol) + + incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) + + if dtype in np_float_types: + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): + tape.backward(loss=l) + sgrad = tape.gradients[s].numpy()[0] + + # d/ds v/s = -v/s^2 + assert_np_equal(sgrad, -2 * incmps[i] / (s.numpy()[0] * s.numpy()[0]), tol=10 * tol) + + allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) + expected_grads = np.zeros_like(allgrads) + expected_grads[i] = 2 / s.numpy()[0] + + # d/dv v/s = 1/s + assert_np_equal(allgrads, expected_grads, tol=tol) + tape.zero() + + +def test_cw_division(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-2, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_cw_div( + s2: wp.array(dtype=vec2), + s3: wp.array(dtype=vec3), + s4: wp.array(dtype=vec4), + s5: wp.array(dtype=vec5), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = wp.cw_div(v2[0], s2[0]) + v3result = wp.cw_div(v3[0], s3[0]) + v4result = wp.cw_div(v4[0], s4[0]) + v5result = wp.cw_div(v5[0], s5[0]) + + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + kernel = getkernel(check_cw_div, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + if dtype in np_int_types: + assert_np_equal(v20.numpy()[0], 2 * (v2.numpy()[0, 0] // s2.numpy()[0, 0]), tol=tol) + assert_np_equal(v21.numpy()[0], 2 * (v2.numpy()[0, 1] // s2.numpy()[0, 1]), tol=tol) + + assert_np_equal(v30.numpy()[0], 2 * (v3.numpy()[0, 0] // s3.numpy()[0, 0]), tol=tol) + assert_np_equal(v31.numpy()[0], 2 * (v3.numpy()[0, 1] // s3.numpy()[0, 1]), tol=tol) + assert_np_equal(v32.numpy()[0], 2 * (v3.numpy()[0, 2] // s3.numpy()[0, 2]), tol=tol) + + assert_np_equal(v40.numpy()[0], 2 * (v4.numpy()[0, 0] // s4.numpy()[0, 0]), tol=tol) + assert_np_equal(v41.numpy()[0], 2 * (v4.numpy()[0, 1] // s4.numpy()[0, 1]), tol=tol) + assert_np_equal(v42.numpy()[0], 2 * (v4.numpy()[0, 2] // s4.numpy()[0, 2]), tol=tol) + assert_np_equal(v43.numpy()[0], 2 * (v4.numpy()[0, 3] // s4.numpy()[0, 3]), tol=tol) + + assert_np_equal(v50.numpy()[0], 2 * (v5.numpy()[0, 0] // s5.numpy()[0, 0]), tol=tol) + assert_np_equal(v51.numpy()[0], 2 * (v5.numpy()[0, 1] // s5.numpy()[0, 1]), tol=tol) + assert_np_equal(v52.numpy()[0], 2 * (v5.numpy()[0, 2] // s5.numpy()[0, 2]), tol=tol) + assert_np_equal(v53.numpy()[0], 2 * (v5.numpy()[0, 3] // s5.numpy()[0, 3]), tol=tol) + assert_np_equal(v54.numpy()[0], 2 * (v5.numpy()[0, 4] // s5.numpy()[0, 4]), tol=tol) + else: + assert_np_equal(v20.numpy()[0], 2 * v2.numpy()[0, 0] / s2.numpy()[0, 0], tol=tol) + assert_np_equal(v21.numpy()[0], 2 * v2.numpy()[0, 1] / s2.numpy()[0, 1], tol=tol) + + assert_np_equal(v30.numpy()[0], 2 * v3.numpy()[0, 0] / s3.numpy()[0, 0], tol=tol) + assert_np_equal(v31.numpy()[0], 2 * v3.numpy()[0, 1] / s3.numpy()[0, 1], tol=tol) + assert_np_equal(v32.numpy()[0], 2 * v3.numpy()[0, 2] / s3.numpy()[0, 2], tol=tol) + + assert_np_equal(v40.numpy()[0], 2 * v4.numpy()[0, 0] / s4.numpy()[0, 0], tol=tol) + assert_np_equal(v41.numpy()[0], 2 * v4.numpy()[0, 1] / s4.numpy()[0, 1], tol=tol) + assert_np_equal(v42.numpy()[0], 2 * v4.numpy()[0, 2] / s4.numpy()[0, 2], tol=tol) + assert_np_equal(v43.numpy()[0], 2 * v4.numpy()[0, 3] / s4.numpy()[0, 3], tol=tol) + + assert_np_equal(v50.numpy()[0], 2 * v5.numpy()[0, 0] / s5.numpy()[0, 0], tol=tol) + assert_np_equal(v51.numpy()[0], 2 * v5.numpy()[0, 1] / s5.numpy()[0, 1], tol=tol) + assert_np_equal(v52.numpy()[0], 2 * v5.numpy()[0, 2] / s5.numpy()[0, 2], tol=tol) + assert_np_equal(v53.numpy()[0], 2 * v5.numpy()[0, 3] / s5.numpy()[0, 3], tol=tol) + assert_np_equal(v54.numpy()[0], 2 * v5.numpy()[0, 4] / s5.numpy()[0, 4], tol=tol) + + if dtype in np_float_types: + incmps = np.concatenate([v.numpy()[0] for v in [v2, v3, v4, v5]]) + scmps = np.concatenate([v.numpy()[0] for v in [s2, s3, s4, s5]]) + + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): + tape.backward(loss=l) + sgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [s2, s3, s4, s5]]) + expected_grads = np.zeros_like(sgrads) + + # d/ds v/s = -v/s^2 + expected_grads[i] = -incmps[i] * 2 / (scmps[i] * scmps[i]) + assert_np_equal(sgrads, expected_grads, tol=20 * tol) + + allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) + expected_grads = np.zeros_like(allgrads) + + # d/dv v/s = 1/s + expected_grads[i] = 2 / scmps[i] + assert_np_equal(allgrads, expected_grads, tol=tol) + + tape.zero() + + +def test_addition(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 5.0e-3, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_add( + s2: wp.array(dtype=vec2), + s3: wp.array(dtype=vec3), + s4: wp.array(dtype=vec4), + s5: wp.array(dtype=vec5), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + v20: wp.array(dtype=wptype), + v21: wp.array(dtype=wptype), + v30: wp.array(dtype=wptype), + v31: wp.array(dtype=wptype), + v32: wp.array(dtype=wptype), + v40: wp.array(dtype=wptype), + v41: wp.array(dtype=wptype), + v42: wp.array(dtype=wptype), + v43: wp.array(dtype=wptype), + v50: wp.array(dtype=wptype), + v51: wp.array(dtype=wptype), + v52: wp.array(dtype=wptype), + v53: wp.array(dtype=wptype), + v54: wp.array(dtype=wptype), + ): + v2result = v2[0] + s2[0] + v3result = v3[0] + s3[0] + v4result = v4[0] + s4[0] + v5result = v5[0] + s5[0] + + v20[0] = wptype(2) * v2result[0] + v21[0] = wptype(2) * v2result[1] + + v30[0] = wptype(2) * v3result[0] + v31[0] = wptype(2) * v3result[1] + v32[0] = wptype(2) * v3result[2] + + v40[0] = wptype(2) * v4result[0] + v41[0] = wptype(2) * v4result[1] + v42[0] = wptype(2) * v4result[2] + v43[0] = wptype(2) * v4result[3] + + v50[0] = wptype(2) * v5result[0] + v51[0] = wptype(2) * v5result[1] + v52[0] = wptype(2) * v5result[2] + v53[0] = wptype(2) * v5result[3] + v54[0] = wptype(2) * v5result[4] + + kernel = getkernel(check_add, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v20 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v21 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v30 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v31 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v32 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v40 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v41 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v42 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v43 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v50 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v51 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v52 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v53 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + v54 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54], + device=device, + ) + + assert_np_equal(v20.numpy()[0], 2 * (v2.numpy()[0, 0] + s2.numpy()[0, 0]), tol=tol) + assert_np_equal(v21.numpy()[0], 2 * (v2.numpy()[0, 1] + s2.numpy()[0, 1]), tol=tol) + + assert_np_equal(v30.numpy()[0], 2 * (v3.numpy()[0, 0] + s3.numpy()[0, 0]), tol=tol) + assert_np_equal(v31.numpy()[0], 2 * (v3.numpy()[0, 1] + s3.numpy()[0, 1]), tol=tol) + assert_np_equal(v32.numpy()[0], 2 * (v3.numpy()[0, 2] + s3.numpy()[0, 2]), tol=tol) + + assert_np_equal(v40.numpy()[0], 2 * (v4.numpy()[0, 0] + s4.numpy()[0, 0]), tol=tol) + assert_np_equal(v41.numpy()[0], 2 * (v4.numpy()[0, 1] + s4.numpy()[0, 1]), tol=tol) + assert_np_equal(v42.numpy()[0], 2 * (v4.numpy()[0, 2] + s4.numpy()[0, 2]), tol=tol) + assert_np_equal(v43.numpy()[0], 2 * (v4.numpy()[0, 3] + s4.numpy()[0, 3]), tol=tol) + + assert_np_equal(v50.numpy()[0], 2 * (v5.numpy()[0, 0] + s5.numpy()[0, 0]), tol=tol) + assert_np_equal(v51.numpy()[0], 2 * (v5.numpy()[0, 1] + s5.numpy()[0, 1]), tol=tol) + assert_np_equal(v52.numpy()[0], 2 * (v5.numpy()[0, 2] + s5.numpy()[0, 2]), tol=tol) + assert_np_equal(v53.numpy()[0], 2 * (v5.numpy()[0, 3] + s5.numpy()[0, 3]), tol=tol) + assert_np_equal(v54.numpy()[0], 2 * (v5.numpy()[0, 4] + s5.numpy()[0, 4]), tol=2 * tol) + + if dtype in np_float_types: + for i, l in enumerate([v20, v21, v30, v31, v32, v40, v41, v42, v43, v50, v51, v52, v53, v54]): + tape.backward(loss=l) + sgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [s2, s3, s4, s5]]) + expected_grads = np.zeros_like(sgrads) + + expected_grads[i] = 2 + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + allgrads = np.concatenate([tape.gradients[v].numpy()[0] for v in [v2, v3, v4, v5]]) + assert_np_equal(allgrads, expected_grads, tol=tol) + + tape.zero() + + +def test_dotproduct(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + tol = { + np.float16: 1.0e-2, + np.float32: 1.0e-6, + np.float64: 1.0e-8, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + def check_dot( + s2: wp.array(dtype=vec2), + s3: wp.array(dtype=vec3), + s4: wp.array(dtype=vec4), + s5: wp.array(dtype=vec5), + v2: wp.array(dtype=vec2), + v3: wp.array(dtype=vec3), + v4: wp.array(dtype=vec4), + v5: wp.array(dtype=vec5), + dot2: wp.array(dtype=wptype), + dot3: wp.array(dtype=wptype), + dot4: wp.array(dtype=wptype), + dot5: wp.array(dtype=wptype), + ): + dot2[0] = wptype(2) * wp.dot(v2[0], s2[0]) + dot3[0] = wptype(2) * wp.dot(v3[0], s3[0]) + dot4[0] = wptype(2) * wp.dot(v4[0], s4[0]) + dot5[0] = wptype(2) * wp.dot(v5[0], s5[0]) + + kernel = getkernel(check_dot, suffix=dtype.__name__) + + if register_kernels: + return + + s2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + s3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + s4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + s5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + v2 = wp.array(randvals(rng, (1, 2), dtype), dtype=vec2, requires_grad=True, device=device) + v3 = wp.array(randvals(rng, (1, 3), dtype), dtype=vec3, requires_grad=True, device=device) + v4 = wp.array(randvals(rng, (1, 4), dtype), dtype=vec4, requires_grad=True, device=device) + v5 = wp.array(randvals(rng, (1, 5), dtype), dtype=vec5, requires_grad=True, device=device) + dot2 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + dot3 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + dot4 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + dot5 = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + tape = wp.Tape() + with tape: + wp.launch( + kernel, + dim=1, + inputs=[ + s2, + s3, + s4, + s5, + v2, + v3, + v4, + v5, + ], + outputs=[dot2, dot3, dot4, dot5], + device=device, + ) + + assert_np_equal(dot2.numpy()[0], 2.0 * (v2.numpy() * s2.numpy()).sum(), tol=10 * tol) + assert_np_equal(dot3.numpy()[0], 2.0 * (v3.numpy() * s3.numpy()).sum(), tol=10 * tol) + assert_np_equal(dot4.numpy()[0], 2.0 * (v4.numpy() * s4.numpy()).sum(), tol=10 * tol) + assert_np_equal(dot5.numpy()[0], 2.0 * (v5.numpy() * s5.numpy()).sum(), tol=10 * tol) + + if dtype in np_float_types: + tape.backward(loss=dot2) + sgrads = tape.gradients[s2].numpy()[0] + expected_grads = 2.0 * v2.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v2].numpy()[0] + expected_grads = 2.0 * s2.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=tol) + + tape.zero() + + tape.backward(loss=dot3) + sgrads = tape.gradients[s3].numpy()[0] + expected_grads = 2.0 * v3.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v3].numpy()[0] + expected_grads = 2.0 * s3.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=tol) + + tape.zero() + + tape.backward(loss=dot4) + sgrads = tape.gradients[s4].numpy()[0] + expected_grads = 2.0 * v4.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v4].numpy()[0] + expected_grads = 2.0 * s4.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=tol) + + tape.zero() + + tape.backward(loss=dot5) + sgrads = tape.gradients[s5].numpy()[0] + expected_grads = 2.0 * v5.numpy()[0] + assert_np_equal(sgrads, expected_grads, tol=10 * tol) + + vgrads = tape.gradients[v5].numpy()[0] + expected_grads = 2.0 * s5.numpy()[0] + assert_np_equal(vgrads, expected_grads, tol=10 * tol) + + tape.zero() + + +def test_equivalent_types(test, device, dtype, register_kernels=False): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + + # vector types + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + # vector types equivalent to the above + vec2_equiv = wp.types.vector(length=2, dtype=wptype) + vec3_equiv = wp.types.vector(length=3, dtype=wptype) + vec4_equiv = wp.types.vector(length=4, dtype=wptype) + vec5_equiv = wp.types.vector(length=5, dtype=wptype) + + # declare kernel with original types + def check_equivalence( + v2: vec2, + v3: vec3, + v4: vec4, + v5: vec5, + ): + wp.expect_eq(v2, vec2(wptype(1), wptype(2))) + wp.expect_eq(v3, vec3(wptype(1), wptype(2), wptype(3))) + wp.expect_eq(v4, vec4(wptype(1), wptype(2), wptype(3), wptype(4))) + wp.expect_eq(v5, vec5(wptype(1), wptype(2), wptype(3), wptype(4), wptype(5))) + + wp.expect_eq(v2, vec2_equiv(wptype(1), wptype(2))) + wp.expect_eq(v3, vec3_equiv(wptype(1), wptype(2), wptype(3))) + wp.expect_eq(v4, vec4_equiv(wptype(1), wptype(2), wptype(3), wptype(4))) + wp.expect_eq(v5, vec5_equiv(wptype(1), wptype(2), wptype(3), wptype(4), wptype(5))) + + kernel = getkernel(check_equivalence, suffix=dtype.__name__) + + if register_kernels: + return + + # call kernel with equivalent types + v2 = vec2_equiv(1, 2) + v3 = vec3_equiv(1, 2, 3) + v4 = vec4_equiv(1, 2, 3, 4) + v5 = vec5_equiv(1, 2, 3, 4, 5) + + wp.launch(kernel, dim=1, inputs=[v2, v3, v4, v5], device=device) + + +def test_conversions(test, device, dtype, register_kernels=False): + def check_vectors_equal( + v0: wp.vec3, + v1: wp.vec3, + v2: wp.vec3, + v3: wp.vec3, + ): + wp.expect_eq(v1, v0) + wp.expect_eq(v2, v0) + wp.expect_eq(v3, v0) + + kernel = getkernel(check_vectors_equal, suffix=dtype.__name__) + + if register_kernels: + return + + v0 = wp.vec3(1, 2, 3) + + # test explicit conversions - constructing vectors from different containers + v1 = wp.vec3((1, 2, 3)) + v2 = wp.vec3([1, 2, 3]) + v3 = wp.vec3(np.array([1, 2, 3], dtype=dtype)) + + wp.launch(kernel, dim=1, inputs=[v0, v1, v2, v3], device=device) + + # test implicit conversions - passing different containers as vectors to wp.launch() + v1 = (1, 2, 3) + v2 = [1, 2, 3] + v3 = np.array([1, 2, 3], dtype=dtype) + + wp.launch(kernel, dim=1, inputs=[v0, v1, v2, v3], device=device) + + +def test_constants(test, device, dtype, register_kernels=False): + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + cv2 = wp.constant(vec2(1, 2)) + cv3 = wp.constant(vec3(1, 2, 3)) + cv4 = wp.constant(vec4(1, 2, 3, 4)) + cv5 = wp.constant(vec5(1, 2, 3, 4, 5)) + + def check_vector_constants(): + wp.expect_eq(cv2, vec2(wptype(1), wptype(2))) + wp.expect_eq(cv3, vec3(wptype(1), wptype(2), wptype(3))) + wp.expect_eq(cv4, vec4(wptype(1), wptype(2), wptype(3), wptype(4))) + wp.expect_eq(cv5, vec5(wptype(1), wptype(2), wptype(3), wptype(4), wptype(5))) + + kernel = getkernel(check_vector_constants, suffix=dtype.__name__) + + if register_kernels: + return + + wp.launch(kernel, dim=1, inputs=[]) + + +def test_minmax(test, device, dtype, register_kernels=False): + rng = np.random.default_rng(123) + + # \TODO: not quite sure why, but the numbers are off for 16 bit float + # on the cpu (but not cuda). This is probably just the sketchy float16 + # arithmetic I implemented to get all this stuff working, so + # hopefully that can be fixed when we do that correctly. + tol = { + np.float16: 1.0e-2, + }.get(dtype, 0) + + wptype = wp.types.np_dtype_to_warp_type[np.dtype(dtype)] + vec2 = wp.types.vector(length=2, dtype=wptype) + vec3 = wp.types.vector(length=3, dtype=wptype) + vec4 = wp.types.vector(length=4, dtype=wptype) + vec5 = wp.types.vector(length=5, dtype=wptype) + + # \TODO: Also not quite sure why: this kernel compiles incredibly + # slowly though... + def check_vec_min_max( + a: wp.array(dtype=wptype, ndim=2), + b: wp.array(dtype=wptype, ndim=2), + mins: wp.array(dtype=wptype, ndim=2), + maxs: wp.array(dtype=wptype, ndim=2), + ): + for i in range(10): + # multiplying by 2 so we've got something to backpropagate: + a2read = vec2(a[i, 0], a[i, 1]) + b2read = vec2(b[i, 0], b[i, 1]) + c2 = wptype(2) * wp.min(a2read, b2read) + d2 = wptype(2) * wp.max(a2read, b2read) + + a3read = vec3(a[i, 2], a[i, 3], a[i, 4]) + b3read = vec3(b[i, 2], b[i, 3], b[i, 4]) + c3 = wptype(2) * wp.min(a3read, b3read) + d3 = wptype(2) * wp.max(a3read, b3read) + + a4read = vec4(a[i, 5], a[i, 6], a[i, 7], a[i, 8]) + b4read = vec4(b[i, 5], b[i, 6], b[i, 7], b[i, 8]) + c4 = wptype(2) * wp.min(a4read, b4read) + d4 = wptype(2) * wp.max(a4read, b4read) + + a5read = vec5(a[i, 9], a[i, 10], a[i, 11], a[i, 12], a[i, 13]) + b5read = vec5(b[i, 9], b[i, 10], b[i, 11], b[i, 12], b[i, 13]) + c5 = wptype(2) * wp.min(a5read, b5read) + d5 = wptype(2) * wp.max(a5read, b5read) + + mins[i, 0] = c2[0] + mins[i, 1] = c2[1] + + mins[i, 2] = c3[0] + mins[i, 3] = c3[1] + mins[i, 4] = c3[2] + + mins[i, 5] = c4[0] + mins[i, 6] = c4[1] + mins[i, 7] = c4[2] + mins[i, 8] = c4[3] + + mins[i, 9] = c5[0] + mins[i, 10] = c5[1] + mins[i, 11] = c5[2] + mins[i, 12] = c5[3] + mins[i, 13] = c5[4] + + maxs[i, 0] = d2[0] + maxs[i, 1] = d2[1] + + maxs[i, 2] = d3[0] + maxs[i, 3] = d3[1] + maxs[i, 4] = d3[2] + + maxs[i, 5] = d4[0] + maxs[i, 6] = d4[1] + maxs[i, 7] = d4[2] + maxs[i, 8] = d4[3] + + maxs[i, 9] = d5[0] + maxs[i, 10] = d5[1] + maxs[i, 11] = d5[2] + maxs[i, 12] = d5[3] + maxs[i, 13] = d5[4] + + kernel = getkernel(check_vec_min_max, suffix=dtype.__name__) + output_select_kernel = get_select_kernel2(wptype) + + if register_kernels: + return + + a = wp.array(randvals(rng, (10, 14), dtype), dtype=wptype, requires_grad=True, device=device) + b = wp.array(randvals(rng, (10, 14), dtype), dtype=wptype, requires_grad=True, device=device) + + mins = wp.zeros((10, 14), dtype=wptype, requires_grad=True, device=device) + maxs = wp.zeros((10, 14), dtype=wptype, requires_grad=True, device=device) + + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[a, b], outputs=[mins, maxs], device=device) + + assert_np_equal(mins.numpy(), 2 * np.minimum(a.numpy(), b.numpy()), tol=tol) + assert_np_equal(maxs.numpy(), 2 * np.maximum(a.numpy(), b.numpy()), tol=tol) + + out = wp.zeros(1, dtype=wptype, requires_grad=True, device=device) + if dtype in np_float_types: + for i in range(10): + for j in range(14): + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[a, b], outputs=[mins, maxs], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[mins, i, j], outputs=[out], device=device) + + tape.backward(loss=out) + expected = np.zeros_like(a.numpy()) + expected[i, j] = 2 if (a.numpy()[i, j] < b.numpy()[i, j]) else 0 + assert_np_equal(tape.gradients[a].numpy(), expected, tol=tol) + expected[i, j] = 2 if (b.numpy()[i, j] < a.numpy()[i, j]) else 0 + assert_np_equal(tape.gradients[b].numpy(), expected, tol=tol) + tape.zero() + + tape = wp.Tape() + with tape: + wp.launch(kernel, dim=1, inputs=[a, b], outputs=[mins, maxs], device=device) + wp.launch(output_select_kernel, dim=1, inputs=[maxs, i, j], outputs=[out], device=device) + + tape.backward(loss=out) + expected = np.zeros_like(a.numpy()) + expected[i, j] = 2 if (a.numpy()[i, j] > b.numpy()[i, j]) else 0 + assert_np_equal(tape.gradients[a].numpy(), expected, tol=tol) + expected[i, j] = 2 if (b.numpy()[i, j] > a.numpy()[i, j]) else 0 + assert_np_equal(tape.gradients[b].numpy(), expected, tol=tol) + tape.zero() + + +devices = get_test_devices() + + +class TestVecScalarOps(unittest.TestCase): + pass + + +for dtype in np_scalar_types: + add_function_test(TestVecScalarOps, f"test_arrays_{dtype.__name__}", test_arrays, devices=devices, dtype=dtype) + add_function_test(TestVecScalarOps, f"test_components_{dtype.__name__}", test_components, devices=None, dtype=dtype) + add_function_test( + TestVecScalarOps, f"test_py_arithmetic_ops_{dtype.__name__}", test_py_arithmetic_ops, devices=None, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_constructors_{dtype.__name__}", test_constructors, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, + f"test_anon_type_instance_{dtype.__name__}", + test_anon_type_instance, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_indexing_{dtype.__name__}", test_indexing, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_equality_{dtype.__name__}", test_equality, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, + f"test_scalar_multiplication_{dtype.__name__}", + test_scalar_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestVecScalarOps, + f"test_scalar_multiplication_rightmul_{dtype.__name__}", + test_scalar_multiplication_rightmul, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestVecScalarOps, + f"test_cw_multiplication_{dtype.__name__}", + test_cw_multiplication, + devices=devices, + dtype=dtype, + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_scalar_division_{dtype.__name__}", test_scalar_division, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_cw_division_{dtype.__name__}", test_cw_division, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_addition_{dtype.__name__}", test_addition, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_dotproduct_{dtype.__name__}", test_dotproduct, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_equivalent_types_{dtype.__name__}", test_equivalent_types, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_conversions_{dtype.__name__}", test_conversions, devices=devices, dtype=dtype + ) + add_function_test_register_kernel( + TestVecScalarOps, f"test_constants_{dtype.__name__}", test_constants, devices=devices, dtype=dtype + ) + + # the kernels in this test compile incredibly slowly... + # add_function_test_register_kernel(TestVecScalarOps, f"test_minmax_{dtype.__name__}", test_minmax, devices=devices, dtype=dtype) + + +if __name__ == "__main__": + wp.build.clear_kernel_cache() + unittest.main(verbosity=2, failfast=True) diff --git a/warp/tests/test_volume.py b/warp/tests/test_volume.py index 6c26e7946..40bbb3808 100644 --- a/warp/tests/test_volume.py +++ b/warp/tests/test_volume.py @@ -10,7 +10,7 @@ import numpy as np import warp as wp -from warp.tests.test_base import * +from warp.tests.unittest_utils import * wp.init() @@ -330,398 +330,407 @@ def test_volume_store_i(volume: wp.uint64, points: wp.array(dtype=wp.vec3), valu values[tid] = wp.volume_lookup_i(volume, i, j, k) -def register(parent): - devices = get_test_devices() - rng = np.random.default_rng(101215) - - # Note about the test grids: - # test_grid and test_int32_grid - # active region: [-10,10]^3 - # values: v[i,j,k] = i * j * k - # voxel size: 0.25 - # - # test_vec_grid - # active region: [-10,10]^3 - # values: v[i,j,k] = (i + 2*j + 3*k, 4*i + 5*j + 6*k, 7*i + 8*j + 9*k) - # voxel size: 0.25 - # - # torus - # index to world transformation: - # [0.1, 0, 0, 0] - # [0, 0, 0.1, 0] - # [0, 0.1, 0, 0] - # [1, 2, 3, 1] - # (-90 degrees rotation along X) - # voxel size: 0.1 - volume_paths = { - "float": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_grid.nvdb")), - "int32": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_int32_grid.nvdb")), - "vec3f": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_vec_grid.nvdb")), - "torus": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/torus.nvdb")), - "float_write": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_grid.nvdb")), - } - - test_volume_tiles = ( - np.array([[i, j, k] for i in range(-2, 2) for j in range(-2, 2) for k in range(-2, 2)], dtype=np.int32) * 8 - ) +devices = get_test_devices() +rng = np.random.default_rng(101215) + +# Note about the test grids: +# test_grid and test_int32_grid +# active region: [-10,10]^3 +# values: v[i,j,k] = i * j * k +# voxel size: 0.25 +# +# test_vec_grid +# active region: [-10,10]^3 +# values: v[i,j,k] = (i + 2*j + 3*k, 4*i + 5*j + 6*k, 7*i + 8*j + 9*k) +# voxel size: 0.25 +# +# torus +# index to world transformation: +# [0.1, 0, 0, 0] +# [0, 0, 0.1, 0] +# [0, 0.1, 0, 0] +# [1, 2, 3, 1] +# (-90 degrees rotation along X) +# voxel size: 0.1 +volume_paths = { + "float": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_grid.nvdb")), + "int32": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_int32_grid.nvdb")), + "vec3f": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_vec_grid.nvdb")), + "torus": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/torus.nvdb")), + "float_write": os.path.abspath(os.path.join(os.path.dirname(__file__), "assets/test_grid.nvdb")), +} + +test_volume_tiles = ( + np.array([[i, j, k] for i in range(-2, 2) for j in range(-2, 2) for k in range(-2, 2)], dtype=np.int32) * 8 +) + +volumes = {} +for value_type, path in volume_paths.items(): + volumes[value_type] = {} + volume_data = open(path, "rb").read() + for device in devices: + try: + volume = wp.Volume.load_from_nvdb(volume_data, device) + except RuntimeError as e: + raise RuntimeError(f'Failed to load volume from "{path}" to {device} memory:\n{e}') + + volumes[value_type][device.alias] = volume + +axis = np.linspace(-1, 1, 3) +point_grid = np.array([[x, y, z] for x in axis for y in axis for z in axis], dtype=np.float32) + + +def test_volume_sample_linear_f_gradient(test, device): + points = rng.uniform(-10.0, 10.0, size=(100, 3)) + values = wp.array(np.zeros(1), dtype=wp.float32, device=device, requires_grad=True) + for test_case in points: + uvws = wp.array(test_case, dtype=wp.vec3, device=device, requires_grad=True) + xyzs = wp.array(test_case * 0.25, dtype=wp.vec3, device=device, requires_grad=True) + + tape = wp.Tape() + with tape: + wp.launch( + test_volume_sample_local_f_linear_values, + dim=1, + inputs=[volumes["float"][device.alias].id, uvws, values], + device=device, + ) + tape.backward(values) + + x, y, z = test_case + grad_expected = np.array([y * z, x * z, x * y]) + grad_computed = tape.gradients[uvws].numpy()[0] + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) + + tape = wp.Tape() + with tape: + wp.launch( + test_volume_sample_world_f_linear_values, + dim=1, + inputs=[volumes["float"][device.alias].id, xyzs, values], + device=device, + ) + tape.backward(values) - volumes = {} - points = {} - points_jittered = {} - for value_type, path in volume_paths.items(): - volumes[value_type] = {} - volume_data = open(path, "rb").read() - for device in devices: - try: - volume = wp.Volume.load_from_nvdb(volume_data, device) - except RuntimeError as e: - raise RuntimeError(f'Failed to load volume from "{path}" to {device} memory:\n{e}') - - volumes[value_type][device.alias] = volume - - axis = np.linspace(-1, 1, 3) - point_grid = np.array([[x, y, z] for x in axis for y in axis for z in axis], dtype=np.float32) - - class TestVolumes(parent): - def test_volume_sample_linear_f_gradient(self): - for device in devices: - points = rng.uniform(-10.0, 10.0, size=(100, 3)) - values = wp.array(np.zeros(1), dtype=wp.float32, device=device, requires_grad=True) - for case in points: - uvws = wp.array(case, dtype=wp.vec3, device=device, requires_grad=True) - xyzs = wp.array(case * 0.25, dtype=wp.vec3, device=device, requires_grad=True) - - tape = wp.Tape() - with tape: - wp.launch( - test_volume_sample_local_f_linear_values, - dim=1, - inputs=[volumes["float"][device.alias].id, uvws, values], - device=device, - ) - tape.backward(values) - - x, y, z = case - grad_expected = np.array([y * z, x * z, x * y]) - grad_computed = tape.gradients[uvws].numpy()[0] - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - - tape = wp.Tape() - with tape: - wp.launch( - test_volume_sample_world_f_linear_values, - dim=1, - inputs=[volumes["float"][device.alias].id, xyzs, values], - device=device, - ) - tape.backward(values) - - x, y, z = case - grad_expected = np.array([y * z, x * z, x * y]) / 0.25 - grad_computed = tape.gradients[xyzs].numpy()[0] - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - - def test_volume_sample_grad_linear_f_gradient(self): - for device in devices: - points = rng.uniform(-10.0, 10.0, size=(100, 3)) - values = wp.array(np.zeros(1), dtype=wp.float32, device=device, requires_grad=True) - for case in points: - uvws = wp.array(case, dtype=wp.vec3, device=device, requires_grad=True) - xyzs = wp.array(case * 0.25, dtype=wp.vec3, device=device, requires_grad=True) - - for case_num in range(4): - tape = wp.Tape() - with tape: - wp.launch( - test_volume_sample_grad_local_f_linear_values, - dim=1, - inputs=[volumes["float"][device.alias].id, uvws, values, case_num], - device=device, - ) - tape.backward(values) - - x, y, z = case - grad_computed = tape.gradients[uvws].numpy()[0] - if case_num == 0: - grad_expected = np.array([y * z, x * z, x * y]) - elif case_num == 1: - grad_expected = np.array([0.0, z, y]) - elif case_num == 2: - grad_expected = np.array([z, 0.0, x]) - elif case_num == 3: - grad_expected = np.array([y, x, 0.0]) - - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - tape.zero() - - for case_num in range(4): - tape = wp.Tape() - with tape: - wp.launch( - test_volume_sample_grad_world_f_linear_values, - dim=1, - inputs=[volumes["float"][device.alias].id, xyzs, values, case_num], - device=device, - ) - tape.backward(values) - - x, y, z = case - grad_computed = tape.gradients[xyzs].numpy()[0] - if case_num == 0: - grad_expected = np.array([y * z, x * z, x * y]) / 0.25 - elif case_num == 1: - grad_expected = np.array([0.0, z, y]) / 0.25 - elif case_num == 2: - grad_expected = np.array([z, 0.0, x]) / 0.25 - elif case_num == 3: - grad_expected = np.array([y, x, 0.0]) / 0.25 - - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - tape.zero() - - def test_volume_sample_linear_v_gradient(self): - for device in devices: - points = rng.uniform(-10.0, 10.0, size=(100, 3)) - values = wp.zeros(1, dtype=wp.float32, device=device, requires_grad=True) - for case in points: - uvws = wp.array(case, dtype=wp.vec3, device=device, requires_grad=True) - xyzs = wp.array(case * 0.25, dtype=wp.vec3, device=device, requires_grad=True) - - tape = wp.Tape() - with tape: - wp.launch( - test_volume_sample_local_v_linear_values, - dim=1, - inputs=[volumes["vec3f"][device.alias].id, uvws, values], - device=device, - ) - tape.backward(values) - - grad_expected = np.array([6.0, 15.0, 24.0]) - grad_computed = tape.gradients[uvws].numpy()[0] - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - - tape = wp.Tape() - with tape: - wp.launch( - test_volume_sample_world_v_linear_values, - dim=1, - inputs=[volumes["vec3f"][device.alias].id, xyzs, values], - device=device, - ) - tape.backward(values) - - grad_expected = np.array([6.0, 15.0, 24.0]) / 0.25 - grad_computed = tape.gradients[xyzs].numpy()[0] - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - - def test_volume_transform_gradient(self): - for device in devices: - values = wp.zeros(1, dtype=wp.float32, device=device, requires_grad=True) - grad_values = wp.zeros(1, dtype=wp.vec3, device=device) - points = rng.uniform(-10.0, 10.0, size=(10, 3)) - for case in points: - points = wp.array(case, dtype=wp.vec3, device=device, requires_grad=True) - tape = wp.Tape() - with tape: - wp.launch( - test_volume_index_to_world, - dim=1, - inputs=[volumes["torus"][device.alias].id, points, values, grad_values], - device=device, - ) - tape.backward(values) - - grad_computed = tape.gradients[points].numpy() - grad_expected = grad_values.numpy() - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - - grad_computed = tape.gradients[points].numpy() - grad_expected = grad_values.numpy() - np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - - def test_volume_store(self): - values_ref = np.array([x + 100 * y + 10000 * z for x, y, z in point_grid]) - for device in devices: - points = wp.array(point_grid, dtype=wp.vec3, device=device) - values = wp.empty(len(point_grid), dtype=wp.float32, device=device) - wp.launch( - test_volume_store_f, - dim=len(point_grid), - inputs=[volumes["float_write"][device.alias].id, points, values], - device=device, - ) + x, y, z = test_case + grad_expected = np.array([y * z, x * z, x * y]) / 0.25 + grad_computed = tape.gradients[xyzs].numpy()[0] + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) - values_res = values.numpy() - np.testing.assert_equal(values_res, values_ref) - def test_volume_allocation_f(self): - bg_value = -123.0 - points_np = np.append(point_grid, [[8096, 8096, 8096]], axis=0) - values_ref = np.append(np.array([x + 100 * y + 10000 * z for x, y, z in point_grid]), bg_value) - for device in devices: - if device.is_cpu: - continue +def test_volume_sample_grad_linear_f_gradient(test, device): + points = rng.uniform(-10.0, 10.0, size=(100, 3)) + values = wp.array(np.zeros(1), dtype=wp.float32, device=device, requires_grad=True) + for test_case in points: + uvws = wp.array(test_case, dtype=wp.vec3, device=device, requires_grad=True) + xyzs = wp.array(test_case * 0.25, dtype=wp.vec3, device=device, requires_grad=True) - volume = wp.Volume.allocate( - min=[-11, -11, -11], max=[11, 11, 11], voxel_size=0.1, bg_value=bg_value, device=device + for case_num in range(4): + tape = wp.Tape() + with tape: + wp.launch( + test_volume_sample_grad_local_f_linear_values, + dim=1, + inputs=[volumes["float"][device.alias].id, uvws, values, case_num], + device=device, ) - points = wp.array(points_np, dtype=wp.vec3, device=device) - values = wp.empty(len(points_np), dtype=wp.float32, device=device) - wp.launch(test_volume_store_f, dim=len(points_np), inputs=[volume.id, points, values], device=device) - - values_res = values.numpy() - np.testing.assert_equal(values_res, values_ref) - - def test_volume_allocation_v(self): - bg_value = (-1, 2.0, -3) - points_np = np.append(point_grid, [[8096, 8096, 8096]], axis=0) - values_ref = np.append(point_grid, [bg_value], axis=0) - for device in devices: - if device.is_cpu: - continue - - volume = wp.Volume.allocate( - min=[-11, -11, -11], max=[11, 11, 11], voxel_size=0.1, bg_value=bg_value, device=device + tape.backward(values) + + x, y, z = test_case + grad_computed = tape.gradients[uvws].numpy()[0] + if case_num == 0: + grad_expected = np.array([y * z, x * z, x * y]) + elif case_num == 1: + grad_expected = np.array([0.0, z, y]) + elif case_num == 2: + grad_expected = np.array([z, 0.0, x]) + elif case_num == 3: + grad_expected = np.array([y, x, 0.0]) + + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) + tape.zero() + + for case_num in range(4): + tape = wp.Tape() + with tape: + wp.launch( + test_volume_sample_grad_world_f_linear_values, + dim=1, + inputs=[volumes["float"][device.alias].id, xyzs, values, case_num], + device=device, ) - points = wp.array(points_np, dtype=wp.vec3, device=device) - values = wp.empty(len(points_np), dtype=wp.vec3, device=device) - wp.launch(test_volume_store_v, dim=len(points_np), inputs=[volume.id, points, values], device=device) - - values_res = values.numpy() - np.testing.assert_equal(values_res, values_ref) - - def test_volume_allocation_i(self): - bg_value = -123 - points_np = np.append(point_grid, [[8096, 8096, 8096]], axis=0) - values_ref = np.append( - np.array([x + 100 * y + 10000 * z for x, y, z in point_grid], dtype=np.int32), bg_value + tape.backward(values) + + x, y, z = test_case + grad_computed = tape.gradients[xyzs].numpy()[0] + if case_num == 0: + grad_expected = np.array([y * z, x * z, x * y]) / 0.25 + elif case_num == 1: + grad_expected = np.array([0.0, z, y]) / 0.25 + elif case_num == 2: + grad_expected = np.array([z, 0.0, x]) / 0.25 + elif case_num == 3: + grad_expected = np.array([y, x, 0.0]) / 0.25 + + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) + tape.zero() + + +def test_volume_sample_linear_v_gradient(test, device): + points = rng.uniform(-10.0, 10.0, size=(100, 3)) + values = wp.zeros(1, dtype=wp.float32, device=device, requires_grad=True) + for test_case in points: + uvws = wp.array(test_case, dtype=wp.vec3, device=device, requires_grad=True) + xyzs = wp.array(test_case * 0.25, dtype=wp.vec3, device=device, requires_grad=True) + + tape = wp.Tape() + with tape: + wp.launch( + test_volume_sample_local_v_linear_values, + dim=1, + inputs=[volumes["vec3f"][device.alias].id, uvws, values], + device=device, + ) + tape.backward(values) + + grad_expected = np.array([6.0, 15.0, 24.0]) + grad_computed = tape.gradients[uvws].numpy()[0] + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) + + tape = wp.Tape() + with tape: + wp.launch( + test_volume_sample_world_v_linear_values, + dim=1, + inputs=[volumes["vec3f"][device.alias].id, xyzs, values], + device=device, + ) + tape.backward(values) + + grad_expected = np.array([6.0, 15.0, 24.0]) / 0.25 + grad_computed = tape.gradients[xyzs].numpy()[0] + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) + + +def test_volume_transform_gradient(test, device): + values = wp.zeros(1, dtype=wp.float32, device=device, requires_grad=True) + grad_values = wp.zeros(1, dtype=wp.vec3, device=device) + test_points = rng.uniform(-10.0, 10.0, size=(10, 3)) + for test_case in test_points: + points = wp.array(test_case, dtype=wp.vec3, device=device, requires_grad=True) + tape = wp.Tape() + with tape: + wp.launch( + test_volume_index_to_world, + dim=1, + inputs=[volumes["torus"][device.alias].id, points, values, grad_values], + device=device, ) - for device in devices: - if device.is_cpu: - continue + tape.backward(values) + + grad_computed = tape.gradients[points].numpy() + grad_expected = grad_values.numpy() + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) + + grad_computed = tape.gradients[points].numpy() + grad_expected = grad_values.numpy() + np.testing.assert_allclose(grad_computed, grad_expected, rtol=1e-4) + + +def test_volume_store(test, device): + values_ref = np.array([x + 100 * y + 10000 * z for x, y, z in point_grid]) + points = wp.array(point_grid, dtype=wp.vec3, device=device) + values = wp.empty(len(point_grid), dtype=wp.float32, device=device) + wp.launch( + test_volume_store_f, + dim=len(point_grid), + inputs=[volumes["float_write"][device.alias].id, points, values], + device=device, + ) - volume = wp.Volume.allocate( - min=[-11, -11, -11], max=[11, 11, 11], voxel_size=0.1, bg_value=bg_value, device=device - ) - points = wp.array(points_np, dtype=wp.vec3, device=device) - values = wp.empty(len(points_np), dtype=wp.int32, device=device) - wp.launch(test_volume_store_i, dim=len(points_np), inputs=[volume.id, points, values], device=device) - - values_res = values.numpy() - np.testing.assert_equal(values_res, values_ref) - - def test_volume_introspection(self): - for volume_names in ("float", "vec3f"): - for device in devices: - volume = volumes[volume_names][device.alias] - tiles_actual = volume.get_tiles().numpy() - tiles_sorted = tiles_actual[np.lexsort(tiles_actual.T[::-1])] - voxel_size = np.array(volume.get_voxel_size()) - - np.testing.assert_equal(test_volume_tiles, tiles_sorted) - np.testing.assert_equal([0.25] * 3, voxel_size) - - def test_volume_from_numpy(self): - # Volume.allocate_from_tiles() is only available with CUDA - if wp.is_cuda_available(): - mins = np.array([-3.0, -3.0, -3.0]) - voxel_size = 0.2 - maxs = np.array([3.0, 3.0, 3.0]) - nums = np.ceil((maxs - mins) / (voxel_size)).astype(dtype=int) - center = np.array([0.0, 0.0, 0.0]) - rad = 2.5 - sphere_sdf_np = np.zeros(tuple(nums)) - for x in range(nums[0]): - for y in range(nums[1]): - for z in range(nums[2]): - pos = mins + voxel_size * np.array([x, y, z]) - dis = np.linalg.norm(pos - center) - sphere_sdf_np[x, y, z] = dis - rad - sphere_vdb = wp.Volume.load_from_numpy(sphere_sdf_np, mins, voxel_size, rad + 3.0 * voxel_size) - - self.assertNotEqual(sphere_vdb.id, 0) - - sphere_vdb_array = sphere_vdb.array() - self.assertEqual(sphere_vdb_array.dtype, wp.uint8) - self.assertFalse(sphere_vdb_array.owner) + values_res = values.numpy() + np.testing.assert_equal(values_res, values_ref) + + +def test_volume_allocation_f(test, device): + bg_value = -123.0 + points_np = np.append(point_grid, [[8096, 8096, 8096]], axis=0) + values_ref = np.append(np.array([x + 100 * y + 10000 * z for x, y, z in point_grid]), bg_value) + + volume = wp.Volume.allocate(min=[-11, -11, -11], max=[11, 11, 11], voxel_size=0.1, bg_value=bg_value, device=device) + points = wp.array(points_np, dtype=wp.vec3, device=device) + values = wp.empty(len(points_np), dtype=wp.float32, device=device) + wp.launch(test_volume_store_f, dim=len(points_np), inputs=[volume.id, points, values], device=device) + + values_res = values.numpy() + np.testing.assert_equal(values_res, values_ref) + + +def test_volume_allocation_v(test, device): + bg_value = (-1, 2.0, -3) + points_np = np.append(point_grid, [[8096, 8096, 8096]], axis=0) + values_ref = np.append(point_grid, [bg_value], axis=0) + + volume = wp.Volume.allocate(min=[-11, -11, -11], max=[11, 11, 11], voxel_size=0.1, bg_value=bg_value, device=device) + points = wp.array(points_np, dtype=wp.vec3, device=device) + values = wp.empty(len(points_np), dtype=wp.vec3, device=device) + wp.launch(test_volume_store_v, dim=len(points_np), inputs=[volume.id, points, values], device=device) + + values_res = values.numpy() + np.testing.assert_equal(values_res, values_ref) + + +def test_volume_allocation_i(test, device): + bg_value = -123 + points_np = np.append(point_grid, [[8096, 8096, 8096]], axis=0) + values_ref = np.append(np.array([x + 100 * y + 10000 * z for x, y, z in point_grid], dtype=np.int32), bg_value) + + volume = wp.Volume.allocate(min=[-11, -11, -11], max=[11, 11, 11], voxel_size=0.1, bg_value=bg_value, device=device) + points = wp.array(points_np, dtype=wp.vec3, device=device) + values = wp.empty(len(points_np), dtype=wp.int32, device=device) + wp.launch(test_volume_store_i, dim=len(points_np), inputs=[volume.id, points, values], device=device) + + values_res = values.numpy() + np.testing.assert_equal(values_res, values_ref) + + +def test_volume_introspection(test, device): + for volume_names in ("float", "vec3f"): + with test.subTest(volume_names=volume_names): + volume = volumes[volume_names][device.alias] + tiles_actual = volume.get_tiles().numpy() + tiles_sorted = tiles_actual[np.lexsort(tiles_actual.T[::-1])] + voxel_size = np.array(volume.get_voxel_size()) + + np.testing.assert_equal(test_volume_tiles, tiles_sorted) + np.testing.assert_equal([0.25] * 3, voxel_size) + + +def test_volume_from_numpy(test, device): + # Volume.allocate_from_tiles() is only available with CUDA + mins = np.array([-3.0, -3.0, -3.0]) + voxel_size = 0.2 + maxs = np.array([3.0, 3.0, 3.0]) + nums = np.ceil((maxs - mins) / (voxel_size)).astype(dtype=int) + center = np.array([0.0, 0.0, 0.0]) + rad = 2.5 + sphere_sdf_np = np.zeros(tuple(nums)) + for x in range(nums[0]): + for y in range(nums[1]): + for z in range(nums[2]): + pos = mins + voxel_size * np.array([x, y, z]) + dis = np.linalg.norm(pos - center) + sphere_sdf_np[x, y, z] = dis - rad + sphere_vdb = wp.Volume.load_from_numpy(sphere_sdf_np, mins, voxel_size, rad + 3.0 * voxel_size, device=device) + + test.assertNotEqual(sphere_vdb.id, 0) + + sphere_vdb_array = sphere_vdb.array() + test.assertEqual(sphere_vdb_array.dtype, wp.uint8) + test.assertFalse(sphere_vdb_array.owner) + + +class TestVolume(unittest.TestCase): + pass + + +add_function_test( + TestVolume, "test_volume_sample_linear_f_gradient", test_volume_sample_linear_f_gradient, devices=devices +) +add_function_test( + TestVolume, "test_volume_sample_grad_linear_f_gradient", test_volume_sample_grad_linear_f_gradient, devices=devices +) +add_function_test( + TestVolume, "test_volume_sample_linear_v_gradient", test_volume_sample_linear_v_gradient, devices=devices +) +add_function_test(TestVolume, "test_volume_transform_gradient", test_volume_transform_gradient, devices=devices) +add_function_test(TestVolume, "test_volume_store", test_volume_store, devices=devices) +add_function_test( + TestVolume, "test_volume_allocation_f", test_volume_allocation_f, devices=get_unique_cuda_test_devices() +) +add_function_test( + TestVolume, "test_volume_allocation_v", test_volume_allocation_v, devices=get_unique_cuda_test_devices() +) +add_function_test( + TestVolume, "test_volume_allocation_i", test_volume_allocation_i, devices=get_unique_cuda_test_devices() +) +add_function_test(TestVolume, "test_volume_introspection", test_volume_introspection, devices=devices) +add_function_test(TestVolume, "test_volume_from_numpy", test_volume_from_numpy, devices=get_unique_cuda_test_devices()) + +points = {} +points_jittered = {} +for device in devices: + points_jittered_np = point_grid + rng.uniform(-0.5, 0.5, size=point_grid.shape) + points[device.alias] = wp.array(point_grid, dtype=wp.vec3, device=device) + points_jittered[device.alias] = wp.array(points_jittered_np, dtype=wp.vec3, device=device) + + add_kernel_test( + TestVolume, + test_volume_lookup_f, + dim=len(point_grid), + inputs=[volumes["float"][device.alias].id, points[device.alias]], + devices=[device], + ) + add_kernel_test( + TestVolume, + test_volume_sample_closest_f, + dim=len(point_grid), + inputs=[volumes["float"][device.alias].id, points_jittered[device.alias]], + devices=[device.alias], + ) + add_kernel_test( + TestVolume, + test_volume_sample_linear_f, + dim=len(point_grid), + inputs=[volumes["float"][device.alias].id, points_jittered[device.alias]], + devices=[device.alias], + ) + add_kernel_test( + TestVolume, + test_volume_sample_grad_linear_f, + dim=len(point_grid), + inputs=[volumes["float"][device.alias].id, points_jittered[device.alias]], + devices=[device.alias], + ) - for device in devices: - points_jittered_np = point_grid + rng.uniform(-0.5, 0.5, size=point_grid.shape) - points[device.alias] = wp.array(point_grid, dtype=wp.vec3, device=device) - points_jittered[device.alias] = wp.array(points_jittered_np, dtype=wp.vec3, device=device) - - add_kernel_test( - TestVolumes, - test_volume_lookup_f, - dim=len(point_grid), - inputs=[volumes["float"][device.alias].id, points[device.alias]], - devices=[device], - ) - add_kernel_test( - TestVolumes, - test_volume_sample_closest_f, - dim=len(point_grid), - inputs=[volumes["float"][device.alias].id, points_jittered[device.alias]], - devices=[device.alias], - ) - add_kernel_test( - TestVolumes, - test_volume_sample_linear_f, - dim=len(point_grid), - inputs=[volumes["float"][device.alias].id, points_jittered[device.alias]], - devices=[device.alias], - ) - add_kernel_test( - TestVolumes, - test_volume_sample_grad_linear_f, - dim=len(point_grid), - inputs=[volumes["float"][device.alias].id, points_jittered[device.alias]], - devices=[device.alias], - ) - - add_kernel_test( - TestVolumes, - test_volume_lookup_v, - dim=len(point_grid), - inputs=[volumes["vec3f"][device.alias].id, points[device.alias]], - devices=[device.alias], - ) - add_kernel_test( - TestVolumes, - test_volume_sample_closest_v, - dim=len(point_grid), - inputs=[volumes["vec3f"][device.alias].id, points_jittered[device.alias]], - devices=[device.alias], - ) - add_kernel_test( - TestVolumes, - test_volume_sample_linear_v, - dim=len(point_grid), - inputs=[volumes["vec3f"][device.alias].id, points_jittered[device.alias]], - devices=[device.alias], - ) - - add_kernel_test( - TestVolumes, - test_volume_lookup_i, - dim=len(point_grid), - inputs=[volumes["int32"][device.alias].id, points[device.alias]], - devices=[device.alias], - ) - add_kernel_test( - TestVolumes, - test_volume_sample_i, - dim=len(point_grid), - inputs=[volumes["int32"][device.alias].id, points_jittered[device.alias]], - devices=[device.alias], - ) - - return TestVolumes + add_kernel_test( + TestVolume, + test_volume_lookup_v, + dim=len(point_grid), + inputs=[volumes["vec3f"][device.alias].id, points[device.alias]], + devices=[device.alias], + ) + add_kernel_test( + TestVolume, + test_volume_sample_closest_v, + dim=len(point_grid), + inputs=[volumes["vec3f"][device.alias].id, points_jittered[device.alias]], + devices=[device.alias], + ) + add_kernel_test( + TestVolume, + test_volume_sample_linear_v, + dim=len(point_grid), + inputs=[volumes["vec3f"][device.alias].id, points_jittered[device.alias]], + devices=[device.alias], + ) + + add_kernel_test( + TestVolume, + test_volume_lookup_i, + dim=len(point_grid), + inputs=[volumes["int32"][device.alias].id, points[device.alias]], + devices=[device.alias], + ) + add_kernel_test( + TestVolume, + test_volume_sample_i, + dim=len(point_grid), + inputs=[volumes["int32"][device.alias].id, points_jittered[device.alias]], + devices=[device.alias], + ) if __name__ == "__main__": wp.build.clear_kernel_cache() - wp.force_load() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/test_volume_write.py b/warp/tests/test_volume_write.py index 48532f22e..3c460e214 100644 --- a/warp/tests/test_volume_write.py +++ b/warp/tests/test_volume_write.py @@ -7,11 +7,11 @@ import unittest -import warp as wp -from warp.tests.test_base import * - import numpy as np +import warp as wp +from warp.tests.unittest_utils import * + wp.init() # wp.config.cache_kernels = False @@ -139,140 +139,127 @@ def test_volume_tile_readback_v(volume: wp.uint64, tiles: wp.array2d(dtype=wp.in values[tid * 512 + r] = wp.volume_lookup_v(volume, ii, jj, kk) -rng = np.random.default_rng(101215) - - -def register(parent): - devices = get_test_devices() - - class TestVolumes(parent): - def test_volume_allocation(self): - voxel_size = 0.125 - background_value = 123.456 - translation = wp.vec3(-12.3, 4.56, -789) - - axis = np.linspace(-11, 11, 23) - points_ref = np.array([[x, y, z] for x in axis for y in axis for z in axis]) - values_ref = np.array([x + 100 * y + 10000 * z for x in axis for y in axis for z in axis]) - num_points = len(points_ref) - bb_max = np.array([11, 11, 11]) - for device in devices: - if device.is_cpu: - continue - - volume_a = wp.Volume.allocate( - -bb_max, - bb_max, - voxel_size=voxel_size, - bg_value=background_value, - translation=translation, - device=device, - ) - volume_b = wp.Volume.allocate( - -bb_max * voxel_size + translation, - bb_max * voxel_size + translation, - voxel_size=voxel_size, - bg_value=background_value, - translation=translation, - points_in_world_space=True, - device=device, - ) - points = wp.array(points_ref, dtype=wp.vec3, device=device) - values_a = wp.empty(num_points, dtype=wp.float32, device=device) - values_b = wp.empty(num_points, dtype=wp.float32, device=device) - wp.launch(test_volume_store_f, dim=num_points, inputs=[volume_a.id, points], device=device) - wp.launch(test_volume_store_f, dim=num_points, inputs=[volume_b.id, points], device=device) - wp.launch(test_volume_readback_f, dim=num_points, inputs=[volume_a.id, points, values_a], device=device) - wp.launch(test_volume_readback_f, dim=num_points, inputs=[volume_b.id, points, values_b], device=device) - - np.testing.assert_equal(values_a.numpy(), values_ref) - np.testing.assert_equal(values_b.numpy(), values_ref) - - def test_volume_allocate_by_tiles_f(self): - voxel_size = 0.125 - background_value = 123.456 - translation = wp.vec3(-12.3, 4.56, -789) - - num_tiles = 1000 - tiles = rng.integers(-512, 512, size=(num_tiles, 3), dtype=np.int32) - points_is = tiles * 8 # points in index space - points_ws = points_is * voxel_size + translation # points in world space - - values_ref = np.empty(num_tiles * 512) - for t in range(num_tiles): - ti, tj, tk = points_is[t] - for i in range(8): - for j in range(8): - for k in range(8): - values_ref[t * 512 + i * 64 + j * 8 + k] = float(100 * (ti + i) + 10 * (tj + j) + (tk + k)) - - for device in devices: - if device.is_cpu: - continue - - points_is_d = wp.array(points_is, dtype=wp.int32, device=device) - points_ws_d = wp.array(points_ws, dtype=wp.vec3, device=device) - volume_a = wp.Volume.allocate_by_tiles( - points_is_d, voxel_size, background_value, translation, device=device - ) - volume_b = wp.Volume.allocate_by_tiles( - points_ws_d, voxel_size, background_value, translation, device=device - ) - values_a = wp.empty(num_tiles * 512, dtype=wp.float32, device=device) - values_b = wp.empty(num_tiles * 512, dtype=wp.float32, device=device) - - wp.launch(test_volume_tile_store_f, dim=num_tiles, inputs=[volume_a.id, points_is_d], device=device) - wp.launch(test_volume_tile_store_ws_f, dim=num_tiles, inputs=[volume_b.id, points_ws_d], device=device) - wp.launch( - test_volume_tile_readback_f, - dim=num_tiles, - inputs=[volume_a.id, points_is_d, values_a], - device=device, - ) - wp.launch( - test_volume_tile_readback_f, - dim=num_tiles, - inputs=[volume_b.id, points_is_d, values_b], - device=device, - ) - - np.testing.assert_equal(values_a.numpy(), values_ref) - np.testing.assert_equal(values_b.numpy(), values_ref) - - def test_volume_allocate_by_tiles_v(self): - num_tiles = 1000 - tiles = rng.integers(-512, 512, size=(num_tiles, 3), dtype=np.int32) - points_is = tiles * 8 - - values_ref = np.empty((len(tiles) * 512, 3)) - for t in range(len(tiles)): - ti, tj, tk = points_is[t] - for i in range(8): - for j in range(8): - for k in range(8): - values_ref[t * 512 + i * 64 + j * 8 + k] = [ti + i, tj + j, tk + k] - - for device in devices: - if device.is_cpu: - continue - - points_d = wp.array(points_is, dtype=wp.int32, device=device) - volume = wp.Volume.allocate_by_tiles(points_d, 0.1, wp.vec3(1, 2, 3), device=device) - values = wp.empty(len(points_d) * 512, dtype=wp.vec3, device=device) - - wp.launch(test_volume_tile_store_v, dim=len(points_d), inputs=[volume.id, points_d], device=device) - wp.launch( - test_volume_tile_readback_v, dim=len(points_d), inputs=[volume.id, points_d, values], device=device - ) - - values_res = values.numpy() - np.testing.assert_equal(values_res, values_ref) - - return TestVolumes +def test_volume_allocation(test, device): + voxel_size = 0.125 + background_value = 123.456 + translation = wp.vec3(-12.3, 4.56, -789) + + axis = np.linspace(-11, 11, 23) + points_ref = np.array([[x, y, z] for x in axis for y in axis for z in axis]) + values_ref = np.array([x + 100 * y + 10000 * z for x in axis for y in axis for z in axis]) + num_points = len(points_ref) + bb_max = np.array([11, 11, 11]) + volume_a = wp.Volume.allocate( + -bb_max, + bb_max, + voxel_size=voxel_size, + bg_value=background_value, + translation=translation, + device=device, + ) + volume_b = wp.Volume.allocate( + -bb_max * voxel_size + translation, + bb_max * voxel_size + translation, + voxel_size=voxel_size, + bg_value=background_value, + translation=translation, + points_in_world_space=True, + device=device, + ) + points = wp.array(points_ref, dtype=wp.vec3, device=device) + values_a = wp.empty(num_points, dtype=wp.float32, device=device) + values_b = wp.empty(num_points, dtype=wp.float32, device=device) + wp.launch(test_volume_store_f, dim=num_points, inputs=[volume_a.id, points], device=device) + wp.launch(test_volume_store_f, dim=num_points, inputs=[volume_b.id, points], device=device) + wp.launch(test_volume_readback_f, dim=num_points, inputs=[volume_a.id, points, values_a], device=device) + wp.launch(test_volume_readback_f, dim=num_points, inputs=[volume_b.id, points, values_b], device=device) + + np.testing.assert_equal(values_a.numpy(), values_ref) + np.testing.assert_equal(values_b.numpy(), values_ref) + + +def test_volume_allocate_by_tiles_f(test, device): + voxel_size = 0.125 + background_value = 123.456 + translation = wp.vec3(-12.3, 4.56, -789) + + num_tiles = 1000 + rng = np.random.default_rng(101215) + tiles = rng.integers(-512, 512, size=(num_tiles, 3), dtype=np.int32) + points_is = tiles * 8 # points in index space + points_ws = points_is * voxel_size + translation # points in world space + + values_ref = np.empty(num_tiles * 512) + for t in range(num_tiles): + ti, tj, tk = points_is[t] + for i in range(8): + for j in range(8): + for k in range(8): + values_ref[t * 512 + i * 64 + j * 8 + k] = float(100 * (ti + i) + 10 * (tj + j) + (tk + k)) + + points_is_d = wp.array(points_is, dtype=wp.int32, device=device) + points_ws_d = wp.array(points_ws, dtype=wp.vec3, device=device) + volume_a = wp.Volume.allocate_by_tiles(points_is_d, voxel_size, background_value, translation, device=device) + volume_b = wp.Volume.allocate_by_tiles(points_ws_d, voxel_size, background_value, translation, device=device) + values_a = wp.empty(num_tiles * 512, dtype=wp.float32, device=device) + values_b = wp.empty(num_tiles * 512, dtype=wp.float32, device=device) + + wp.launch(test_volume_tile_store_f, dim=num_tiles, inputs=[volume_a.id, points_is_d], device=device) + wp.launch(test_volume_tile_store_ws_f, dim=num_tiles, inputs=[volume_b.id, points_ws_d], device=device) + wp.launch( + test_volume_tile_readback_f, + dim=num_tiles, + inputs=[volume_a.id, points_is_d, values_a], + device=device, + ) + wp.launch( + test_volume_tile_readback_f, + dim=num_tiles, + inputs=[volume_b.id, points_is_d, values_b], + device=device, + ) + + np.testing.assert_equal(values_a.numpy(), values_ref) + np.testing.assert_equal(values_b.numpy(), values_ref) + + +def test_volume_allocate_by_tiles_v(test, device): + num_tiles = 1000 + rng = np.random.default_rng(101215) + tiles = rng.integers(-512, 512, size=(num_tiles, 3), dtype=np.int32) + points_is = tiles * 8 + + values_ref = np.empty((len(tiles) * 512, 3)) + for t in range(len(tiles)): + ti, tj, tk = points_is[t] + for i in range(8): + for j in range(8): + for k in range(8): + values_ref[t * 512 + i * 64 + j * 8 + k] = [ti + i, tj + j, tk + k] + + points_d = wp.array(points_is, dtype=wp.int32, device=device) + volume = wp.Volume.allocate_by_tiles(points_d, 0.1, wp.vec3(1, 2, 3), device=device) + values = wp.empty(len(points_d) * 512, dtype=wp.vec3, device=device) + + wp.launch(test_volume_tile_store_v, dim=len(points_d), inputs=[volume.id, points_d], device=device) + wp.launch(test_volume_tile_readback_v, dim=len(points_d), inputs=[volume.id, points_d, values], device=device) + + values_res = values.numpy() + np.testing.assert_equal(values_res, values_ref) + + +devices = get_unique_cuda_test_devices() + + +class TestVolumeWrite(unittest.TestCase): + pass + + +add_function_test(TestVolumeWrite, "test_volume_allocation", test_volume_allocation, devices=devices) +add_function_test(TestVolumeWrite, "test_volume_allocate_by_tiles_f", test_volume_allocate_by_tiles_f, devices=devices) +add_function_test(TestVolumeWrite, "test_volume_allocate_by_tiles_v", test_volume_allocate_by_tiles_v, devices=devices) if __name__ == "__main__": wp.build.clear_kernel_cache() - wp.force_load() - _ = register(unittest.TestCase) unittest.main(verbosity=2) diff --git a/warp/tests/unittest_serial.py b/warp/tests/unittest_serial.py new file mode 100644 index 000000000..80146b059 --- /dev/null +++ b/warp/tests/unittest_serial.py @@ -0,0 +1,35 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +import warp as wp +from warp.tests.unittest_utils import TeamCityTestRunner + + +def run_suite() -> bool: + """Run a test suite""" + + import warp.tests.unittest_suites + + # force rebuild of all kernels + wp.build.clear_kernel_cache() + print("Cleared Warp kernel cache") + + runner = TeamCityTestRunner(verbosity=2, failfast=False) + + # Can swap out warp.tests.unittest_suites.explicit_suite() + suite = warp.tests.unittest_suites.auto_discover_suite() + print(f"Test suite has {suite.countTestCases()} tests") + + ret = not runner.run(suite, "WarpTests").wasSuccessful() + return ret + + +if __name__ == "__main__": + ret = run_suite() + import sys + + sys.exit(ret) diff --git a/warp/tests/unittest_suites.py b/warp/tests/unittest_suites.py new file mode 100644 index 000000000..e64e107c0 --- /dev/null +++ b/warp/tests/unittest_suites.py @@ -0,0 +1,291 @@ +# Copyright (c) 2023 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + +"""Warp Test Suites + +This file is intended to define functions that return TestSuite objects, which +can be used in parallel or serial unit tests (with optional code coverage) +""" + +import os +import unittest + +START_DIRECTORY = os.path.realpath(os.path.dirname(__file__)) +TOP_LEVEL_DIRECTORY = os.path.realpath(os.path.join(START_DIRECTORY, "..", "..")) + + +def _create_suite_from_test_classes(test_classes): + suite = unittest.TestSuite() + + for test in test_classes: + sub_suite = unittest.TestSuite() + sub_suite.addTest(unittest.defaultTestLoader.loadTestsFromTestCase(test)) + suite.addTest(sub_suite) + + return suite + + +def auto_discover_suite(loader=unittest.defaultTestLoader, pattern="test*.py"): + """Uses unittest auto-discovery to build a test suite (test_*.py pattern)""" + + return loader.discover(start_dir=START_DIRECTORY, pattern=pattern, top_level_dir=TOP_LEVEL_DIRECTORY) + + +def explicit_suite(): + """Example of a manually constructed test suite. + + Intended to be modified to create additional test suites + """ + from warp.tests.test_adam import TestAdam + from warp.tests.test_arithmetic import TestArithmetic + from warp.tests.test_array import TestArray + from warp.tests.test_array_reduce import TestArrayReduce + from warp.tests.test_atomic import TestAtomic + from warp.tests.test_bool import TestBool + from warp.tests.test_builtins_resolution import TestBuiltinsResolution + from warp.tests.test_bvh import TestBvh + from warp.tests.test_closest_point_edge_edge import TestClosestPointEdgeEdgeMethods + from warp.tests.test_codegen import TestCodeGen + from warp.tests.test_compile_consts import TestConstants + from warp.tests.test_conditional import TestConditional + from warp.tests.test_copy import TestCopy + from warp.tests.test_ctypes import TestCTypes + from warp.tests.test_dense import TestDense + from warp.tests.test_devices import TestDevices + from warp.tests.test_dlpack import TestDLPack + from warp.tests.test_examples import TestExamples, TestFemExamples, TestSimExamples + from warp.tests.test_fabricarray import TestFabricArray + from warp.tests.test_fast_math import TestFastMath + from warp.tests.test_fem import TestFem + from warp.tests.test_fp16 import TestFp16 + from warp.tests.test_func import TestFunc + from warp.tests.test_generics import TestGenerics + from warp.tests.test_grad import TestGrad + from warp.tests.test_grad_customs import TestGradCustoms + from warp.tests.test_hash_grid import TestHashGrid + from warp.tests.test_import import TestImport + from warp.tests.test_indexedarray import TestIndexedArray + from warp.tests.test_intersect import TestIntersect + from warp.tests.test_large import TestLarge + from warp.tests.test_launch import TestLaunch + from warp.tests.test_lerp import TestLerp + from warp.tests.test_lvalue import TestLValue + from warp.tests.test_marching_cubes import TestMarchingCubes + from warp.tests.test_mat import TestMat + from warp.tests.test_mat_lite import TestMatLite + from warp.tests.test_mat_scalar_ops import TestMatScalarOps + from warp.tests.test_math import TestMath + from warp.tests.test_matmul import TestMatmul + from warp.tests.test_matmul_lite import TestMatmulLite + from warp.tests.test_mesh import TestMesh + from warp.tests.test_mesh_query_aabb import TestMeshQueryAABBMethods + from warp.tests.test_mesh_query_point import TestMeshQueryPoint + from warp.tests.test_mesh_query_ray import TestMeshQueryRay + from warp.tests.test_mlp import TestMLP + from warp.tests.test_model import TestModel + from warp.tests.test_modules_lite import TestModuleLite + from warp.tests.test_multigpu import TestMultiGPU + from warp.tests.test_noise import TestNoise + from warp.tests.test_operators import TestOperators + from warp.tests.test_options import TestOptions + from warp.tests.test_pinned import TestPinned + from warp.tests.test_print import TestPrint + from warp.tests.test_quat import TestQuat + from warp.tests.test_rand import TestRand + from warp.tests.test_reload import TestReload + from warp.tests.test_rounding import TestRounding + from warp.tests.test_runlength_encode import TestRunlengthEncode + from warp.tests.test_smoothstep import TestSmoothstep + from warp.tests.test_snippet import TestSnippets + from warp.tests.test_sparse import TestSparse + from warp.tests.test_spatial import TestSpatial + from warp.tests.test_streams import TestStreams + from warp.tests.test_struct import TestStruct + from warp.tests.test_tape import TestTape + from warp.tests.test_torch import TestTorch + from warp.tests.test_transient_module import TestTransientModule + from warp.tests.test_types import TestTypes + from warp.tests.test_utils import TestUtils + from warp.tests.test_vec import TestVec + from warp.tests.test_vec_lite import TestVecLite + from warp.tests.test_vec_scalar_ops import TestVecScalarOps + from warp.tests.test_volume import TestVolume + from warp.tests.test_volume_write import TestVolumeWrite + + test_classes = [ + TestAdam, + TestArithmetic, + TestArray, + TestArrayReduce, + TestAtomic, + TestBool, + TestBuiltinsResolution, + TestBvh, + TestClosestPointEdgeEdgeMethods, + TestCodeGen, + TestConstants, + TestConditional, + TestCopy, + TestCTypes, + TestDense, + TestDevices, + TestDLPack, + TestExamples, + TestFemExamples, + TestSimExamples, + TestFabricArray, + TestFastMath, + TestFem, + TestFp16, + TestFunc, + TestGenerics, + TestGrad, + TestGradCustoms, + TestHashGrid, + TestImport, + TestIndexedArray, + TestIntersect, + TestLarge, + TestLaunch, + TestLerp, + TestLValue, + TestMarchingCubes, + TestMat, + TestMatLite, + TestMatScalarOps, + TestMath, + TestMatmul, + TestMatmulLite, + TestMesh, + TestMeshQueryAABBMethods, + TestMeshQueryPoint, + TestMeshQueryRay, + TestMLP, + TestModel, + TestModuleLite, + TestMultiGPU, + TestNoise, + TestOperators, + TestOptions, + TestPinned, + TestPrint, + TestQuat, + TestRand, + TestReload, + TestRounding, + TestRunlengthEncode, + TestSmoothstep, + TestSparse, + TestSnippets, + TestSpatial, + TestStreams, + TestStruct, + TestTape, + TestTorch, + TestTransientModule, + TestTypes, + TestUtils, + TestVec, + TestVecLite, + TestVecScalarOps, + TestVolume, + TestVolumeWrite, + ] + + return _create_suite_from_test_classes(test_classes) + + +def kit_suite(): + """Tries to mimic the test suite used for testing omni.warp.core in Kit + + Requires manual updates with test_ext.py for now. + """ + from warp.tests.test_array import TestArray + from warp.tests.test_array_reduce import TestArrayReduce + from warp.tests.test_bvh import TestBvh + from warp.tests.test_codegen import TestCodeGen + from warp.tests.test_compile_consts import TestConstants + from warp.tests.test_conditional import TestConditional + from warp.tests.test_ctypes import TestCTypes + from warp.tests.test_devices import TestDevices + from warp.tests.test_dlpack import TestDLPack + from warp.tests.test_fabricarray import TestFabricArray + from warp.tests.test_func import TestFunc + from warp.tests.test_generics import TestGenerics + from warp.tests.test_grad_customs import TestGradCustoms + from warp.tests.test_hash_grid import TestHashGrid + from warp.tests.test_indexedarray import TestIndexedArray + from warp.tests.test_launch import TestLaunch + from warp.tests.test_marching_cubes import TestMarchingCubes + from warp.tests.test_mat_lite import TestMatLite + from warp.tests.test_math import TestMath + from warp.tests.test_matmul_lite import TestMatmulLite + from warp.tests.test_mesh import TestMesh + from warp.tests.test_mesh_query_aabb import TestMeshQueryAABBMethods + from warp.tests.test_mesh_query_point import TestMeshQuery + from warp.tests.test_mesh_query_ray import TestMeshQueryRay + from warp.tests.test_modules_lite import TestModuleLite + from warp.tests.test_noise import TestNoise + from warp.tests.test_operators import TestOperators + from warp.tests.test_quat import TestQuat + from warp.tests.test_rand import TestRand + from warp.tests.test_rounding import TestRounding + from warp.tests.test_runlength_encode import TestRunlengthEncode + from warp.tests.test_sparse import TestSparse + from warp.tests.test_streams import TestStreams + from warp.tests.test_tape import TestTape + from warp.tests.test_transient_module import TestTransientModule + from warp.tests.test_types import TestTypes + from warp.tests.test_utils import TestUtils + from warp.tests.test_vec_lite import TestVecLite + from warp.tests.test_volume import TestVolume + from warp.tests.test_volume_write import TestVolumeWrite + + test_classes = [ + TestArray, + TestArrayReduce, + TestBvh, + TestCodeGen, + TestConstants, + TestConditional, + TestCTypes, + TestDevices, + TestDLPack, + TestFabricArray, + TestFunc, + TestGenerics, + TestGradCustoms, + TestHashGrid, + TestIndexedArray, + TestLaunch, + TestMarchingCubes, + TestMatLite, + TestMath, + TestMatmulLite, + TestMesh, + TestMeshQueryAABBMethods, + TestMeshQuery, + TestMeshQueryRay, + TestModuleLite, + TestNoise, + TestOperators, + TestQuat, + TestRand, + TestRounding, + TestRunlengthEncode, + TestSparse, + TestStreams, + TestTape, + TestTransientModule, + TestTypes, + TestUtils, + TestVecLite, + TestVolume, + TestVolumeWrite, + ] + + return _create_suite_from_test_classes(test_classes) diff --git a/warp/tests/test_base.py b/warp/tests/unittest_utils.py similarity index 54% rename from warp/tests/test_base.py rename to warp/tests/unittest_utils.py index e5eb830f1..39f50fcaa 100644 --- a/warp/tests/test_base.py +++ b/warp/tests/unittest_utils.py @@ -9,15 +9,25 @@ import ctypes.util import os import sys +import unittest import numpy as np + import warp as wp +try: + import pxr # noqa: F401 + + USD_AVAILABLE = True +except ImportError as e: + USD_AVAILABLE = False + print(f"Skipping USD tests for reason: {e}") + # default test mode (see get_test_devices()) # "basic" - only run on CPU and first GPU device # "unique" - run on CPU and all unique GPU arches # "all" - run on all devices -test_mode = "basic" +test_mode = "unique" try: if sys.platform == "win32": @@ -29,7 +39,40 @@ LIBC = None +def get_unique_cuda_test_devices(mode=None): + """Returns a list of unique CUDA devices according to the CUDA arch. + + If ``mode`` is ``None``, the ``global test_mode`` value will be used and + this list will be a subset of the devices returned from ``get_test_devices()``. + """ + + if mode is None: + global test_mode + mode = test_mode + + if mode == "basic": + cuda_devices = [wp.get_device("cuda:0")] + else: + cuda_devices = wp.get_cuda_devices() + + unique_cuda_devices = {} + for d in cuda_devices: + if d.arch not in unique_cuda_devices: + unique_cuda_devices[d.arch] = d + + return list(unique_cuda_devices.values()) + + def get_test_devices(mode=None): + """Returns a list of devices based on the mode selected. + + Args: + mode (str, optional): The testing mode to specify which devices to include. If not provided or ``None``, the + ``global test_mode`` value will be used. + "basic" (default): Returns the CPU and the first GPU device when available. + "unique": Returns the CPU and all unique GPU architectures. + "all": Returns all available devices. + """ if mode is None: global test_mode mode = test_mode @@ -48,14 +91,7 @@ def get_test_devices(mode=None): if wp.is_cpu_available(): devices.append(wp.get_device("cpu")) - cuda_devices = wp.get_cuda_devices() - - unique_cuda_devices = {} - for d in cuda_devices: - if d.arch not in unique_cuda_devices: - unique_cuda_devices[d.arch] = d - - devices.extend(list(unique_cuda_devices.values())) + devices.extend(get_unique_cuda_test_devices()) # run on all devices elif mode == "all": @@ -78,7 +114,8 @@ def begin(self): self.target = os.dup(self.saved.fileno()) # create temporary capture stream - import io, tempfile + import io + import tempfile self.tempfile = io.TextIOWrapper( tempfile.TemporaryFile(buffering=0), encoding="utf-8", errors="replace", newline="", write_through=True @@ -126,12 +163,8 @@ def __exit__(self, exc_type, exc_value, traceback): self.test.fail(f"Unexpected output:\n'{s.rstrip()}'") -def assert_array_equal(result, expect): - a = result.numpy() - b = expect.numpy() - - if (a == b).all() == False: - raise AssertionError(f"Unexpected result, got: {a} expected: {b}") +def assert_array_equal(result: wp.array, expect: wp.array): + np.testing.assert_equal(result.numpy(), expect.numpy()) def assert_np_equal(result, expect, tol=0.0): @@ -139,7 +172,7 @@ def assert_np_equal(result, expect, tol=0.0): b = expect.flatten() if tol == 0.0: - if (a == b).all() == False: + if (a == b).all() is False: raise AssertionError(f"Unexpected result, got: {a} expected: {b}") else: @@ -153,7 +186,6 @@ def assert_np_equal(result, expect, tol=0.0): # if check_output is True any output to stdout will be treated as an error def create_test_func(func, device, check_output, **kwargs): - # pass args to func def test_func(self): if check_output: @@ -165,6 +197,11 @@ def test_func(self): return test_func +def skip_test_func(self): + # A function to use so we can tell unittest that the test was skipped. + self.skipTest("No suitable devices to run the test.") + + def sanitize_identifier(s): """replace all non-identifier characters with '_'""" @@ -174,15 +211,25 @@ def sanitize_identifier(s): else: import re - return re.sub("\W|^(?=\d)", "_", s) + return re.sub(r"\W|^(?=\d)", "_", s) def add_function_test(cls, name, func, devices=None, check_output=True, **kwargs): if devices is None: setattr(cls, name, create_test_func(func, None, check_output, **kwargs)) + elif isinstance(devices, list): + if not devices: + # No devices to run this test + setattr(cls, name, skip_test_func) + else: + for device in devices: + setattr( + cls, + name + "_" + sanitize_identifier(device), + create_test_func(func, device, check_output, **kwargs), + ) else: - for device in devices: - setattr(cls, name + "_" + sanitize_identifier(device), create_test_func(func, device, check_output, **kwargs)) + setattr(cls, name + "_" + sanitize_identifier(devices), create_test_func(func, devices, check_output, **kwargs)) def add_kernel_test(cls, kernel, dim, name=None, expect=None, inputs=None, devices=None): @@ -217,13 +264,79 @@ def test_func(self, device): # register test func with class for the given devices for d in devices: - # use a lambda to forward the device to the inner test function - test_lambda = lambda test, device=d: test_func(test, device) - setattr(cls, name + "_" + sanitize_identifier(d), test_lambda) + # use a function to forward the device to the inner test function + def test_func_wrapper(test, device=d): + test_func(test, device) + + setattr(cls, name + "_" + sanitize_identifier(d), test_func_wrapper) -# helper that first calls the test function to generate all kernel permuations +# helper that first calls the test function to generate all kernel permutations # so that compilation is done in one-shot instead of per-test def add_function_test_register_kernel(cls, name, func, devices=None, **kwargs): func(None, None, **kwargs, register_kernels=True) add_function_test(cls, name, func, devices=devices, **kwargs) + + +class TeamCityTestResult(unittest.TextTestResult): + """This class will report each test result to TeamCity""" + + def __init__(self, stream, descriptions, verbosity): + super(TeamCityTestResult, self).__init__(stream, descriptions, verbosity) + + def addSuccess(self, test): + super(TeamCityTestResult, self).addSuccess(test) + self.reportSuccess(test) + + def addError(self, test, err): + super(TeamCityTestResult, self).addError(test, err) + self.reportFailure(test) + + def addFailure(self, test, err): + super(TeamCityTestResult, self).addFailure(test, err) + self.reportFailure(test) + + def addSkip(self, test, reason): + super(TeamCityTestResult, self).addSkip(test, reason) + + def addExpectedFailure(self, test, err): + super(TeamCityTestResult, self).addExpectedFailure(test, err) + self.reportSuccess(test) + + def addUnexpectedSuccess(self, test): + super(TeamCityTestResult, self).addUnexpectedSuccess(test) + self.reportFailure(test) + + def reportSuccess(self, test): + test_id = test.id() + print(f"##teamcity[testStarted name='{test_id}']") + print(f"##teamcity[testFinished name='{test_id}']") + + def reportFailure(self, test): + test_id = test.id() + print(f"##teamcity[testStarted name='{test_id}']") + print(f"##teamcity[testFailed name='{test_id}']") + print(f"##teamcity[testFinished name='{test_id}']") + + +class TeamCityTestRunner(unittest.TextTestRunner): + """Test runner that will report test results to TeamCity if running in TeamCity""" + + def __init__(self, **kwargs): + self.running_in_teamcity = os.environ.get("TEAMCITY_VERSION") is not None + if self.running_in_teamcity: + kwargs["resultclass"] = TeamCityTestResult + super(TeamCityTestRunner, self).__init__(**kwargs) + + def run(self, test, name): + if self.running_in_teamcity: + print(f"##teamcity[testSuiteStarted name='{name}']") + + result = super(TeamCityTestRunner, self).run(test) + + if self.running_in_teamcity: + print(f"##teamcity[testSuiteFinished name='{name}']") + if not result.wasSuccessful(): + print("##teamcity[buildStatus status='FAILURE']") + + return result diff --git a/warp/tests/test_misc.py b/warp/tests/unused_test_misc.py similarity index 65% rename from warp/tests/test_misc.py rename to warp/tests/unused_test_misc.py index af84ba7e1..7bcded557 100644 --- a/warp/tests/test_misc.py +++ b/warp/tests/unused_test_misc.py @@ -1,8 +1,17 @@ -import warp as wp +# Copyright (c) 2021 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import numpy as np +import warp as wp + wp.init() + @wp.kernel def arange(out: wp.array(dtype=int)): tid = wp.tid() @@ -28,7 +37,7 @@ def arange(out: wp.array(dtype=int)): graph = wp.capture_end() -#--------------------------------------- +# --------------------------------------- ref = np.arange(0, n, dtype=int) wp.capture_launch(graph) @@ -37,7 +46,7 @@ def arange(out: wp.array(dtype=int)): print(arrays[i].numpy()) -#--------------------------------------- +# --------------------------------------- n = 16 arrays = [] @@ -49,7 +58,7 @@ def arange(out: wp.array(dtype=int)): for i in range(5): cmd.set_dim(n) cmd.set_param(arrays[i]) - + cmd.update_graph() @@ -60,4 +69,3 @@ def arange(out: wp.array(dtype=int)): for i in range(5): print(arrays[i].numpy()) - diff --git a/warp/tests/test_debug.py b/warp/tests/walkthough_debug.py similarity index 88% rename from warp/tests/test_debug.py rename to warp/tests/walkthough_debug.py index af2570016..2d501956c 100644 --- a/warp/tests/test_debug.py +++ b/warp/tests/walkthough_debug.py @@ -49,10 +49,7 @@ # #################################################################################################### -import unittest - import warp as wp -from warp.tests.test_base import * # The init() function prints the directory of the kernel cache which contains the .cpp files # generated from Warp kernels. You can put breakpoints in these C++ files through Visual Studio Code, @@ -67,7 +64,7 @@ @wp.kernel -def test_breakpoint(n: int): +def example_breakpoint(n: int): a = int(0) for i in range(0, n): @@ -83,16 +80,6 @@ def test_breakpoint(n: int): wp.expect_eq(a, 5) -def register(parent): - class TestDebug(parent): - pass - - add_kernel_test(TestDebug, name="test_breakpoint", kernel=test_breakpoint, dim=1, inputs=[10], devices=["cpu"]) - - return TestDebug - - if __name__ == "__main__": wp.build.clear_kernel_cache() - _ = register(unittest.TestCase) - unittest.main(verbosity=2, failfast=True) + wp.launch(example_breakpoint, dim=1, inputs=[10], device="cpu") diff --git a/warp/thirdparty/unittest_parallel.py b/warp/thirdparty/unittest_parallel.py index 4face9684..a5eefca0d 100644 --- a/warp/thirdparty/unittest_parallel.py +++ b/warp/thirdparty/unittest_parallel.py @@ -1,11 +1,22 @@ # Licensed under the MIT License # https://github.com/craigahobbs/unittest-parallel/blob/main/LICENSE +# SPDX-FileCopyrightText: Copyright (c) 2023 NVIDIA CORPORATION & AFFILIATES. All rights reserved. +# SPDX-License-Identifier: LicenseRef-NvidiaProprietary +# +# NVIDIA CORPORATION, its affiliates and licensors retain all intellectual +# property and proprietary rights in and to this material, related +# documentation and any modifications thereto. Any use, reproduction, +# disclosure or distribution of this material and related documentation +# without an express license agreement from NVIDIA CORPORATION or +# its affiliates is strictly prohibited. + """ unittest-parallel command-line script main module """ import argparse +import concurrent.futures # NVIDIA Modification import multiprocessing import os import sys @@ -15,7 +26,20 @@ from contextlib import contextmanager from io import StringIO -import coverage +import warp.tests.unittest_suites # NVIDIA Modification + +try: + import coverage + + COVERAGE_AVAILABLE = True # NVIDIA Modification +except ImportError: + COVERAGE_AVAILABLE = False # NVIDIA Modification + + +# The following variables are NVIDIA Modifications +RUNNING_IN_TEAMCITY = os.environ.get("TEAMCITY_VERSION") is not None +TEST_SUITE_NAME = "WarpTests" +START_DIRECTORY = os.path.dirname(__file__) # The directory to start test discovery def main(argv=None): @@ -25,8 +49,8 @@ def main(argv=None): # Command line arguments parser = argparse.ArgumentParser(prog="unittest-parallel") - parser.add_argument("-v", "--verbose", action="store_const", const=2, default=1, help="Verbose output") - parser.add_argument("-q", "--quiet", dest="verbose", action="store_const", const=0, default=1, help="Quiet output") + # parser.add_argument("-v", "--verbose", action="store_const", const=2, default=1, help="Verbose output") + parser.add_argument("-q", "--quiet", dest="verbose", action="store_const", const=0, default=2, help="Quiet output") parser.add_argument("-f", "--failfast", action="store_true", default=False, help="Stop on first fail or error") parser.add_argument( "-b", "--buffer", action="store_true", default=False, help="Buffer stdout and stderr during tests" @@ -38,9 +62,6 @@ def main(argv=None): type=_convert_select_pattern, help="Only run tests which match the given substring", ) - parser.add_argument( - "-s", "--start-directory", metavar="START", default=".", help="Directory to start discovery ('.' default)" - ) parser.add_argument( "-p", "--pattern", metavar="PATTERN", default="test*.py", help="Pattern to match tests ('test*.py' default)" ) @@ -59,11 +80,19 @@ def main(argv=None): default=0, help="The number of test processes (default is 0, all cores)", ) + group_parallel.add_argument( + "-m", + "--maxjobs", + metavar="MAXCOUNT", + type=int, + default=8, + help="The maximum number of test processes (default is 8)", + ) # NVIDIA Modification group_parallel.add_argument( "--level", choices=["module", "class", "test"], - default="module", - help="Set the test parallelism level (default is 'module')", + default="class", + help="Set the test parallelism level (default is 'class')", ) group_parallel.add_argument( "--disable-process-pooling", @@ -71,40 +100,45 @@ def main(argv=None): default=False, help="Do not reuse processes used to run test suites", ) + group_parallel.add_argument( + "--disable-concurrent-futures", + action="store_true", + default=False, + help="Use multiprocessing instead of concurrent.futures.", + ) # NVIDIA Modification + group_parallel.add_argument( + "--serial-fallback", + action="store_true", + default=False, + help="Run in a single-process (no spawning) mode without multiprocessing or concurrent.futures.", + ) # NVIDIA Modification group_coverage = parser.add_argument_group("coverage options") group_coverage.add_argument("--coverage", action="store_true", help="Run tests with coverage") group_coverage.add_argument("--coverage-branch", action="store_true", help="Run tests with branch coverage") - group_coverage.add_argument("--coverage-rcfile", metavar="RCFILE", help="Specify coverage configuration file") - group_coverage.add_argument( - "--coverage-include", - metavar="PAT", - action="append", - help="Include only files matching one of these patterns. Accepts shell-style (quoted) wildcards.", - ) - group_coverage.add_argument( - "--coverage-omit", - metavar="PAT", - action="append", - help="Omit files matching one of these patterns. Accepts shell-style (quoted) wildcards.", - ) group_coverage.add_argument( - "--coverage-source", - metavar="SRC", - action="append", - help="A list of packages or directories of code to be measured", + "--coverage-html", + metavar="DIR", + help="Generate coverage HTML report", + default=os.path.join(START_DIRECTORY, "..", "..", "htmlcov"), ) - group_coverage.add_argument("--coverage-html", metavar="DIR", help="Generate coverage HTML report") group_coverage.add_argument("--coverage-xml", metavar="FILE", help="Generate coverage XML report") group_coverage.add_argument( "--coverage-fail-under", metavar="MIN", type=float, help="Fail if coverage percentage under min" ) args = parser.parse_args(args=argv) + if args.coverage_branch: args.coverage = args.coverage_branch + if args.coverage and not COVERAGE_AVAILABLE: + parser.exit( + status=2, message="--coverage was used, but coverage was not found. Is it installed?\n" + ) # NVIDIA Modification + process_count = max(0, args.jobs) if process_count == 0: process_count = multiprocessing.cpu_count() + process_count = min(process_count, args.maxjobs) # NVIDIA Modification # Create the temporary directory (for coverage files) with tempfile.TemporaryDirectory() as temp_dir: @@ -113,9 +147,10 @@ def main(argv=None): test_loader = unittest.TestLoader() if args.testNamePatterns: test_loader.testNamePatterns = args.testNamePatterns - discover_suite = test_loader.discover( - args.start_directory, pattern=args.pattern, top_level_dir=args.top_level_directory - ) + discover_suite = warp.tests.unittest_suites.auto_discover_suite( + test_loader, args.pattern + ) # NVIDIA Modification + # discover_suite = warp.tests.unittest_suites.explicit_suite() # Get the parallelizable test suites if args.level == "test": @@ -128,26 +163,69 @@ def main(argv=None): # Don't use more processes than test suites process_count = max(1, min(len(test_suites), process_count)) - # Report test suites and processes - print( - f"Running {len(test_suites)} test suites ({discover_suite.countTestCases()} total tests) across {process_count} processes", - file=sys.stderr, - ) - if args.verbose > 1: - print(file=sys.stderr) + if RUNNING_IN_TEAMCITY: + print(f"##teamcity[testSuiteStarted name='{TEST_SUITE_NAME}']") # NVIDIA Modification for TC + + if not args.serial_fallback: + # Report test suites and processes + print( + f"Running {len(test_suites)} test suites ({discover_suite.countTestCases()} total tests) across {process_count} processes", + file=sys.stderr, + ) + if args.verbose > 1: + print(file=sys.stderr) + + # Run the tests in parallel + start_time = time.perf_counter() + + if args.disable_concurrent_futures: + multiprocessing_context = multiprocessing.get_context(method="spawn") + maxtasksperchild = 1 if args.disable_process_pooling else None + with multiprocessing_context.Pool( + process_count, + maxtasksperchild=maxtasksperchild, + initializer=set_worker_cache, + initargs=(args, temp_dir), + ) as pool, multiprocessing.Manager() as manager: + test_manager = ParallelTestManager(manager, args, temp_dir) + results = pool.map(test_manager.run_tests, test_suites) + else: + # NVIDIA Modification added concurrent.futures + with concurrent.futures.ProcessPoolExecutor( + max_workers=process_count, + mp_context=multiprocessing.get_context(method="spawn"), + initializer=set_worker_cache, + initargs=(args, temp_dir), + ) as executor, multiprocessing.Manager() as manager: + test_manager = ParallelTestManager(manager, args, temp_dir) + results = list(executor.map(test_manager.run_tests, test_suites, timeout=3600)) + else: + # This entire path is an NVIDIA Modification + + # Report test suites and processes + print(f"Running {discover_suite.countTestCases()} total tests (serial fallback)", file=sys.stderr) + if args.verbose > 1: + print(file=sys.stderr) + + import warp as wp + + # force rebuild of all kernels + wp.build.clear_kernel_cache() + print("Cleared Warp kernel cache") + + # Run the tests in serial + start_time = time.perf_counter() + + with multiprocessing.Manager() as manager: + test_manager = ParallelTestManager(manager, args, temp_dir) + results = [test_manager.run_tests(discover_suite)] - # Run the tests in parallel - start_time = time.perf_counter() - multiprocessing_context = multiprocessing.get_context(method="spawn") - maxtasksperchild = 1 if args.disable_process_pooling else None - with multiprocessing_context.Pool( - process_count, maxtasksperchild=maxtasksperchild - ) as pool, multiprocessing.Manager() as manager: - test_manager = ParallelTestManager(manager, args, temp_dir) - results = pool.map(test_manager.run_tests, test_suites) stop_time = time.perf_counter() test_duration = stop_time - start_time + if RUNNING_IN_TEAMCITY: + print(f"##teamcity[testSuiteFinished name='{TEST_SUITE_NAME}']") # NVIDIA Modification for TC + # Aggregate parallel test run results tests_run = 0 errors = [] @@ -195,14 +273,15 @@ def main(argv=None): # Return an error status on failure if not is_success: + if RUNNING_IN_TEAMCITY: + print("##teamcity[buildStatus status='FAILURE']") # NVIDIA Modification for TC parser.exit(status=len(errors) + len(failures) + unexpected_successes) # Coverage? if args.coverage: # Combine the coverage files cov_options = {} - if args.coverage_rcfile is not None: - cov_options["config_file"] = args.coverage_rcfile + cov_options["config_file"] = True # Grab configuration from pyproject.toml (must install coverage[toml]) cov = coverage.Coverage(**cov_options) cov.combine(data_paths=[os.path.join(temp_dir, x) for x in os.listdir(temp_dir)]) @@ -225,7 +304,7 @@ def main(argv=None): def _convert_select_pattern(pattern): - if not "*" in pattern: + if "*" not in pattern: return f"*{pattern}*" return pattern @@ -242,12 +321,9 @@ def _coverage(args, temp_dir): cov_options = { "branch": args.coverage_branch, "data_file": coverage_file.name, - "include": args.coverage_include, - "omit": (args.coverage_omit if args.coverage_omit else []) + [__file__], - "source": args.coverage_source, + # NVIDIA Modification removed unneeded options } - if args.coverage_rcfile is not None: - cov_options["config_file"] = args.coverage_rcfile + cov_options["config_file"] = True # Grab configuration from pyproject.toml (must install coverage[toml]) cov = coverage.Coverage(**cov_options) try: # Start measuring code coverage @@ -307,7 +383,9 @@ def run_tests(self, test_suite): with _coverage(self.args, self.temp_dir): runner = unittest.TextTestRunner( stream=StringIO(), - resultclass=ParallelTextTestResult, + resultclass=ParallelTeamCityTestResult + if RUNNING_IN_TEAMCITY + else ParallelTextTestResult, # NVIDIA Modification for TC verbosity=self.args.verbose, failfast=self.args.failfast, buffer=self.args.buffer, @@ -384,3 +462,130 @@ def addUnexpectedSuccess(self, test): def printErrors(self): pass + + +# NVIDIA Modifications from here until end of file + + +def set_worker_cache(args, temp_dir): + """This function is run at the start of ever new process. It changes the Warp cache to avoid conflicts.""" + + with _coverage(args, temp_dir): + import warp as wp + from warp.thirdparty import appdirs + + pid = os.getpid() + cache_root_dir = appdirs.user_cache_dir( + appname="warp", appauthor="NVIDIA Corporation", version=f"{wp.config.version}-{pid}" + ) + + wp.config.kernel_cache_dir = cache_root_dir + + # wp.config.verify_cuda = True # TESTING + + wp.build.clear_kernel_cache() + + +def _tc_escape(s): + s = s.replace("|", "||") + s = s.replace("\n", "|n") + s = s.replace("\r", "|r") + s = s.replace("'", "|'") + s = s.replace("[", "|[") + s = s.replace("]", "|]") + return s + + +class ParallelTeamCityTestResult(unittest.TextTestResult): + def __init__(self, stream, descriptions, verbosity): + stream = type(stream)(sys.stderr) + super().__init__(stream, descriptions, verbosity) + + def startTest(self, test): + if self.showAll: + self.stream.writeln(f"{self.getDescription(test)} ...") + self.stream.flush() + self.start_time = time.perf_counter_ns() + super(unittest.TextTestResult, self).startTest(test) + + def _add_helper(self, test, dots_message, show_all_message): + if self.showAll: + self.stream.writeln(f"{self.getDescription(test)} ... {show_all_message}") + elif self.dots: + self.stream.write(dots_message) + self.stream.flush() + + def addSuccess(self, test): + super(unittest.TextTestResult, self).addSuccess(test) + self._add_helper(test, ".", "ok") + self.reportSuccess(test) + + def addError(self, test, err): + super(unittest.TextTestResult, self).addError(test, err) + self._add_helper(test, "E", "ERROR") + self.reportFailure(test, err) + + def addFailure(self, test, err): + super(unittest.TextTestResult, self).addFailure(test, err) + self._add_helper(test, "F", "FAIL") + self.reportFailure(test, err) + + def addSkip(self, test, reason): + super(unittest.TextTestResult, self).addSkip(test, reason) + self._add_helper(test, "s", f"skipped {reason!r}") + self.reportIgnored(test, reason) + + def addExpectedFailure(self, test, err): + super(unittest.TextTestResult, self).addExpectedFailure(test, err) + self._add_helper(test, "x", "expected failure") + self.reportSuccess(test) + + def addUnexpectedSuccess(self, test): + super(unittest.TextTestResult, self).addUnexpectedSuccess(test) + self._add_helper(test, "u", "unexpected success") + self.reportFailure(test, "unexpected success") + + def addSubTest(self, test, subtest, err): + super(unittest.TextTestResult, self).addSubTest(test, subtest, err) + if err is not None: + self._add_helper(test, "E", "ERROR") + self.reportSubTestFailure(test, err) + + def printErrors(self): + pass + + def reportIgnored(self, test, reason): + test_id = test.id() + reason_str = str(reason) + print(reason_str) + self.stream.writeln(f"##teamcity[testIgnored name='{test_id}' message='{_tc_escape(str(reason))}']") + self.stream.flush() + + def reportSuccess(self, test): + duration = round((time.perf_counter_ns() - self.start_time) / 1e6) # [ms] + test_id = test.id() + self.stream.writeln(f"##teamcity[testStarted name='{test_id}']") + self.stream.writeln(f"##teamcity[testFinished name='{test_id}' duration='{duration}']") + self.stream.flush() + + def reportFailure(self, test, err): + test_id = test.id() + self.stream.writeln(f"##teamcity[testStarted name='{test_id}']") + self.stream.writeln( + f"##teamcity[testFailed name='{test_id}' message='{_tc_escape(str(err[1]))}' details='{_tc_escape(str(err[2]))}']" + ) + self.stream.writeln(f"##teamcity[testFinished name='{test_id}']") + self.stream.flush() + + def reportSubTestFailure(self, test, err): + test_id = test.id() + self.stream.writeln(f"##teamcity[testStarted name='{test_id}']") + self.stream.writeln( + f"##teamcity[testFailed name='{test_id}' message='{_tc_escape(str(err[1]))}' details='{_tc_escape(self._exc_info_to_string(err, test))}']" + ) + self.stream.writeln(f"##teamcity[testFinished name='{test_id}']") + self.stream.flush() + + +if __name__ == "__main__": # pragma: no cover + main() From e41700fe55699fbd65677a19561350e252bec422 Mon Sep 17 00:00:00 2001 From: Eric Shi Date: Tue, 19 Dec 2023 13:55:03 -0800 Subject: [PATCH 46/50] CI/CD Pipelines for Documentation --- .github/workflows/sphinx.yml | 30 + .gitignore | 4 +- .gitlab-ci.yml | 24 + build_docs.py | 41 +- build_lib.py | 7 + docs/_build/html/.buildinfo | 4 - .../_build/html/_images/compiler_pipeline.png | Bin 36891 -> 0 bytes docs/_build/html/_images/header.png | Bin 1646470 -> 0 bytes docs/_build/html/_images/joint_transforms.png | Bin 479613 -> 0 bytes docs/_build/html/_sources/basics.rst.txt | 214 - .../html/_sources/configuration.rst.txt | 138 - docs/_build/html/_sources/debugging.rst.txt | 86 - docs/_build/html/_sources/faq.rst.txt | 112 - docs/_build/html/_sources/index.rst.txt | 192 - .../_build/html/_sources/installation.rst.txt | 93 - docs/_build/html/_sources/limitations.rst.txt | 56 - .../html/_sources/modules/devices.rst.txt | 200 - docs/_build/html/_sources/modules/fem.rst.txt | 386 -- .../html/_sources/modules/functions.rst.txt | 1992 --------- .../_sources/modules/interoperability.rst.txt | 146 - .../html/_sources/modules/profiling.rst.txt | 44 - .../html/_sources/modules/runtime.rst.txt | 1491 ------- docs/_build/html/_sources/modules/sim.rst.txt | 157 - .../html/_sources/modules/sparse.rst.txt | 19 - docs/_build/html/_static/basic.css | 925 ----- docs/_build/html/_static/check-solid.svg | 4 - docs/_build/html/_static/clipboard.min.js | 7 - docs/_build/html/_static/copy-button.svg | 5 - docs/_build/html/_static/copybutton.css | 94 - docs/_build/html/_static/copybutton.js | 248 -- docs/_build/html/_static/copybutton_funcs.js | 73 - docs/_build/html/_static/custom.css | 37 - docs/_build/html/_static/debug.css | 69 - docs/_build/html/_static/doctools.js | 156 - .../html/_static/documentation_options.js | 13 - docs/_build/html/_static/file.png | Bin 286 -> 0 bytes docs/_build/html/_static/language_data.js | 199 - docs/_build/html/_static/logo-dark-mode.png | Bin 8504 -> 0 bytes docs/_build/html/_static/logo-light-mode.png | Bin 10324 -> 0 bytes docs/_build/html/_static/minus.png | Bin 90 -> 0 bytes docs/_build/html/_static/plus.png | Bin 90 -> 0 bytes docs/_build/html/_static/pygments.css | 258 -- .../html/_static/scripts/furo-extensions.js | 0 docs/_build/html/_static/scripts/furo.js | 3 - .../html/_static/scripts/furo.js.LICENSE.txt | 7 - docs/_build/html/_static/scripts/furo.js.map | 1 - docs/_build/html/_static/searchtools.js | 574 --- docs/_build/html/_static/skeleton.css | 296 -- docs/_build/html/_static/sphinx_highlight.js | 154 - .../html/_static/styles/furo-extensions.css | 2 - .../_static/styles/furo-extensions.css.map | 1 - docs/_build/html/_static/styles/furo.css | 2 - docs/_build/html/_static/styles/furo.css.map | 1 - docs/_build/html/basics.html | 525 --- docs/_build/html/configuration.html | 530 --- docs/_build/html/debugging.html | 406 -- docs/_build/html/faq.html | 422 -- docs/_build/html/genindex.html | 1980 --------- docs/_build/html/index.html | 566 --- docs/_build/html/installation.html | 396 -- docs/_build/html/limitations.html | 382 -- docs/_build/html/modules/devices.html | 511 --- docs/_build/html/modules/fem.html | 2063 ---------- docs/_build/html/modules/functions.html | 3001 -------------- .../_build/html/modules/interoperability.html | 659 --- docs/_build/html/modules/profiling.html | 388 -- docs/_build/html/modules/runtime.html | 2743 ------------ docs/_build/html/modules/sim.html | 3661 ----------------- docs/_build/html/modules/sparse.html | 758 ---- docs/_build/html/objects.inv | Bin 5391 -> 0 bytes docs/_build/html/py-modindex.html | 322 -- docs/_build/html/search.html | 291 -- docs/_build/html/searchindex.js | 1 - docs/conf.py | 7 +- docs/modules/functions.rst | 66 +- docs/requirements.txt | 2 + .../ci/building/build-linux-aarch64/build.sh | 1 - .../building/build-windows-x86_64/build.bat | 1 - warp/__init__.py | 1 - warp/context.py | 2 +- warp/stubs.py | 116 +- 81 files changed, 136 insertions(+), 28230 deletions(-) create mode 100644 .github/workflows/sphinx.yml create mode 100644 .gitlab-ci.yml delete mode 100644 docs/_build/html/.buildinfo delete mode 100644 docs/_build/html/_images/compiler_pipeline.png delete mode 100644 docs/_build/html/_images/header.png delete mode 100644 docs/_build/html/_images/joint_transforms.png delete mode 100644 docs/_build/html/_sources/basics.rst.txt delete mode 100644 docs/_build/html/_sources/configuration.rst.txt delete mode 100644 docs/_build/html/_sources/debugging.rst.txt delete mode 100644 docs/_build/html/_sources/faq.rst.txt delete mode 100644 docs/_build/html/_sources/index.rst.txt delete mode 100644 docs/_build/html/_sources/installation.rst.txt delete mode 100644 docs/_build/html/_sources/limitations.rst.txt delete mode 100644 docs/_build/html/_sources/modules/devices.rst.txt delete mode 100644 docs/_build/html/_sources/modules/fem.rst.txt delete mode 100644 docs/_build/html/_sources/modules/functions.rst.txt delete mode 100644 docs/_build/html/_sources/modules/interoperability.rst.txt delete mode 100644 docs/_build/html/_sources/modules/profiling.rst.txt delete mode 100644 docs/_build/html/_sources/modules/runtime.rst.txt delete mode 100644 docs/_build/html/_sources/modules/sim.rst.txt delete mode 100644 docs/_build/html/_sources/modules/sparse.rst.txt delete mode 100644 docs/_build/html/_static/basic.css delete mode 100644 docs/_build/html/_static/check-solid.svg delete mode 100644 docs/_build/html/_static/clipboard.min.js delete mode 100644 docs/_build/html/_static/copy-button.svg delete mode 100644 docs/_build/html/_static/copybutton.css delete mode 100644 docs/_build/html/_static/copybutton.js delete mode 100644 docs/_build/html/_static/copybutton_funcs.js delete mode 100644 docs/_build/html/_static/custom.css delete mode 100644 docs/_build/html/_static/debug.css delete mode 100644 docs/_build/html/_static/doctools.js delete mode 100644 docs/_build/html/_static/documentation_options.js delete mode 100644 docs/_build/html/_static/file.png delete mode 100644 docs/_build/html/_static/language_data.js delete mode 100644 docs/_build/html/_static/logo-dark-mode.png delete mode 100644 docs/_build/html/_static/logo-light-mode.png delete mode 100644 docs/_build/html/_static/minus.png delete mode 100644 docs/_build/html/_static/plus.png delete mode 100644 docs/_build/html/_static/pygments.css delete mode 100644 docs/_build/html/_static/scripts/furo-extensions.js delete mode 100644 docs/_build/html/_static/scripts/furo.js delete mode 100644 docs/_build/html/_static/scripts/furo.js.LICENSE.txt delete mode 100644 docs/_build/html/_static/scripts/furo.js.map delete mode 100644 docs/_build/html/_static/searchtools.js delete mode 100644 docs/_build/html/_static/skeleton.css delete mode 100644 docs/_build/html/_static/sphinx_highlight.js delete mode 100644 docs/_build/html/_static/styles/furo-extensions.css delete mode 100644 docs/_build/html/_static/styles/furo-extensions.css.map delete mode 100644 docs/_build/html/_static/styles/furo.css delete mode 100644 docs/_build/html/_static/styles/furo.css.map delete mode 100644 docs/_build/html/basics.html delete mode 100644 docs/_build/html/configuration.html delete mode 100644 docs/_build/html/debugging.html delete mode 100644 docs/_build/html/faq.html delete mode 100644 docs/_build/html/genindex.html delete mode 100644 docs/_build/html/index.html delete mode 100644 docs/_build/html/installation.html delete mode 100644 docs/_build/html/limitations.html delete mode 100644 docs/_build/html/modules/devices.html delete mode 100644 docs/_build/html/modules/fem.html delete mode 100644 docs/_build/html/modules/functions.html delete mode 100644 docs/_build/html/modules/interoperability.html delete mode 100644 docs/_build/html/modules/profiling.html delete mode 100644 docs/_build/html/modules/runtime.html delete mode 100644 docs/_build/html/modules/sim.html delete mode 100644 docs/_build/html/modules/sparse.html delete mode 100644 docs/_build/html/objects.inv delete mode 100644 docs/_build/html/py-modindex.html delete mode 100644 docs/_build/html/search.html delete mode 100644 docs/_build/html/searchindex.js diff --git a/.github/workflows/sphinx.yml b/.github/workflows/sphinx.yml new file mode 100644 index 000000000..7f80e9324 --- /dev/null +++ b/.github/workflows/sphinx.yml @@ -0,0 +1,30 @@ +name: Deploy Sphinx documentation to Pages + +# Runs on pushes targeting the default branch +on: + push: + branches: [github-pages] + +jobs: + build: + runs-on: ubuntu-latest + permissions: + contents: write + steps: + - uses: actions/checkout@v4 + - name: Build HTML + uses: ammaraskar/sphinx-action@master + with: + docs-folder: "docs/" + build-command: "python ../build_docs.py" + - name: Upload artifacts + uses: actions/upload-artifact@v3 + with: + name: html-docs + path: docs/_build/html/ + - name: Deploy + uses: peaceiris/actions-gh-pages@v3 + if: github.ref == 'refs/heads/github-pages' + with: + github_token: ${{ secrets.GITHUB_TOKEN }} + publish_dir: docs/_build/html diff --git a/.gitignore b/.gitignore index 32462e43d..4e9d2c85e 100644 --- a/.gitignore +++ b/.gitignore @@ -18,8 +18,7 @@ archive /_repo examples/assets/.thumbs /examples/tmp -/docs/_build/doctrees -/docs/_build/html/_static/fonts +/docs/_build /warp_lang.egg-info exts/omni.warp/omni/warp/ogn/tests/usd build/lib/ @@ -29,4 +28,5 @@ exts/omni.warp/config/extension.gen.toml /build /dist .coverage +.cache warp/tests/outputs diff --git a/.gitlab-ci.yml b/.gitlab-ci.yml new file mode 100644 index 000000000..9fe2f2c2c --- /dev/null +++ b/.gitlab-ci.yml @@ -0,0 +1,24 @@ +stages: + - deploy + +pages: + stage: deploy + image: python:3.11-slim + before_script: + - echo -e "\\e[0Ksection_start:`date +%s`:my_first_section[collapsed=true]\\r\\e[0KSet up docs environment" + - apt-get update && apt-get install make --no-install-recommends -y + - python -m pip install --upgrade pip + - python -m pip install -r docs/requirements.txt + - echo -e "\\e[0Ksection_end:`date +%s`:my_first_section\\r\\e[0K" + script: + - cd docs && make clean + - python ../build_docs.py --no-color + after_script: + - mv docs/_build/html/ ./public/ + artifacts: + paths: + - public + rules: + - if: $CI_COMMIT_BRANCH == "master" + tags: + - pages diff --git a/build_docs.py b/build_docs.py index 4bcdd57de..2f492dd39 100644 --- a/build_docs.py +++ b/build_docs.py @@ -1,38 +1,47 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + import os -import sys import subprocess +import sys -import warp as wp - - -wp.init() +from warp.context import export_functions_rst, export_stubs # docs # disable sphinx color output os.environ["NO_COLOR"] = "1" -with open("docs/modules/functions.rst", "w") as function_ref: - wp.print_builtins(function_ref) +base_path = os.path.dirname(os.path.realpath(__file__)) + +with open(os.path.join(base_path, "docs", "modules", "functions.rst"), "w") as function_ref: + export_functions_rst(function_ref) # run Sphinx build try: - if os.name == 'nt': - subprocess.check_output("make.bat html", cwd="docs", shell=True) + docs_folder = os.path.join(base_path, "docs") + make_html_cmd = ["make.bat" if os.name == "nt" else "make", "html"] + + if os.name == "nt" or len(sys.argv) == 1: + subprocess.check_output(make_html_cmd, cwd=docs_folder) else: - subprocess.run("make clean", cwd="docs", shell=True) - subprocess.check_output("make html", cwd="docs", shell=True) + # Sphinx options were passed via the argument list + make_html_cmd.append("-e") + sphinx_options = " ".join(sys.argv[1:]) + subprocess.check_output(make_html_cmd, cwd=docs_folder, env=dict(os.environ, SPHINXOPTS=sphinx_options)) except subprocess.CalledProcessError as e: print(e.output.decode()) raise e - # generate stubs for autocomplete -stub_file = open("warp/stubs.py", "w") -wp.export_stubs(stub_file) -stub_file.close() +with open(os.path.join(base_path, "warp", "stubs.py"), "w") as stub_file: + export_stubs(stub_file) # code formatting -subprocess.run([sys.executable, "-m", "black", "warp/stubs.py"]) +subprocess.run([sys.executable, "-m", "black", os.path.join(base_path, "warp", "stubs.py")]) print("Finished") diff --git a/build_lib.py b/build_lib.py index c78cc6698..ce8f7c1cb 100644 --- a/build_lib.py +++ b/build_lib.py @@ -1,3 +1,10 @@ +# Copyright (c) 2022 NVIDIA CORPORATION. All rights reserved. +# NVIDIA CORPORATION and its licensors retain all intellectual property +# and proprietary rights in and to this software, related documentation +# and any modifications thereto. Any use, reproduction, disclosure or +# distribution of this software and related documentation without an express +# license agreement from NVIDIA CORPORATION is strictly prohibited. + # This script is an 'offline' build of the core warp runtime libraries # designed to be executed as part of CI / developer workflows, not # as part of the user runtime (since it requires CUDA toolkit, etc) diff --git a/docs/_build/html/.buildinfo b/docs/_build/html/.buildinfo deleted file mode 100644 index 7e3e1db1b..000000000 --- a/docs/_build/html/.buildinfo +++ /dev/null @@ -1,4 +0,0 @@ -# Sphinx build info version 1 -# This file hashes the configuration used when building these files. When it is not found, a full rebuild will be done. -config: 3801b32913435da995d554ffb86411be -tags: 645f666f9bcd5a90fca523b33c5a78b7 diff --git a/docs/_build/html/_images/compiler_pipeline.png b/docs/_build/html/_images/compiler_pipeline.png deleted file mode 100644 index f3475577b971e46a42ee1bf622def4b3a05048d5..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 36891 zcmeFZbx>Sg)-Mbp!QCxDaDsK?4#5c$0)*hCfrb!h+%*aAAq2NT@ZjzQcL*+xySwW> z9y(oeR2spppG_)MlAkH*4cGjlmmQWf8R~sk|)WzHs0l{TDGv3^Zz6Q(p{+Lkg zkpiw>c6@JgypqPk{)lXWn<7GffvS!S1o;qce7A9+@#Z zJM}qtms{s%2b*{GhQ}8dZs#M{g&W(@mFIe^m*3ac$>-+0MGu^?lHXoIz6%*rhYnJg zpXeFia{Vr&;;f`~Z!kcrn2^9v#c8qlcxTzWuG!nk9(t>1I4BNTXey)5^)fiKZX!vq z`sPaC!Tv%-T*d$c_nK2hh!bDjrR-a zXpUa6Em+7o(K%LDaqdrJ^C^-$R;h2-vloTm-5&X^W>b3%{+6WIXUZs+#9`WTPllAX z5mtrxk$?x7&-((+r96oZv4$oZuK-R1=05$(eErwqHJdCnpIBRiKYb zB!_*VVp*Ic=RK-i_UsB($}wSC$x>j_W?{Kt$^D#Gn6B`qjJROB+^n0$VxY!^uH7Jm zKCoa#?InA`$#dQ}1vN1`7C#%>8NXyz&b<6tP%#%@#%;I0Ie^s=Az+e`X0`HK_9^TH z&BHW7=$Nf+fbTk3k@%+M==smW$}4ON=G}6~b$zE<*g4W@cy&~GibqdwcJf_H#akWk z>$?}@Evy!Yrae|{``XL1YIFXmvP>TY=^#Uy5*;C#2oiF=@kP%v-^Z6FT_WEG$r9(r zlo7ERn}Bw4PkpOqYA#Ghxy~bw)?QwHtGc*19njwLimRDFKGPqM>Hb|$=AQTa^OoP% zatame{qMZ_qPHC(g@!45;bQtD@?sV~lXW}G?3j6woUiPYZaa}xCvLvCsjW(7=kcGF_=Y@}Y&CU% zSC9wr6XMHi^WxUG`|~g-ejMIm7(1+bdtSx=0s2c|I$^~WF6JiW-u>R}2gvN{OCzhd z+uap~Ll7xJx?TN&xQr|%r$#rH6`O4P4rKW7Ewxp^jVmpdjXU}q0kguWgc3J~^#G=B z6Go?tsWE9ZLHG`0Gy1M03JoJNeT}u` z)e|L2w$1Wy&n=%)28a55zSEr>gTLpJjxC}0u`EL5Ok(l;j`{QJ z6!%O~^TZd`&cZSTny650H20J569^Pl6&M#j*s>d}zbisX83o@nB#F*6CbC#ix->96 zl@DMV#-++i>&PiU_J!s*BcJ&n!X?F!KXbht@|B?6m{s0>nuFcNBs;9^pKbZGjQiVA zOTflS7Sa()xKgJU1yoJTDgLY|@byT{6R-(zOVM*Miez&C2ac`5qeaGV^J znV%4HiuHUtnYE}w-YzOCGxk_?o)iq-(~=emlSpw@t0YpjLmG!(M{Wk5FGspQYlAHqEmqJPCTc0C$_V;wcRk>f|nQ*e9$Uq`b z!vdW$m{?0~)r6hGntt(SLV@<{b0+yFN$HQn&~n3{91@J=ErpLYC_8*DY}~sc%t`|C zxGG&Mt;}to6Rs!nESQ#bzW;cZ5~^F*RJQP1-mm)UkM6R~me8jb@p7%fpBY~UGp(hm z$`dRa#S9(wq2MS@269DO)+sqLh8GxXSBljYC_26xZg?w^N#Gx+YnzolIMazxIr$+; zH`BDZ#f>%tEnenri94K<_mQj^*sPjah7$DRoeKipXY|?6bRx}L7N!ve{esHYJ_mf$ zV9Ld+U(XIp(no`GkqK|tx%fPNLTz;7py-kK(PPiN9TLckMzB>G2NJ>swWc?3<9emV zzBlHZm#DXxRCrD9sy~T&1=bTNrdiZ6#I1;R3?aLu;vVuUf4_t*f+nT|jyIw?Uy$sx zbM3R%klJA`$8DpN9iQG@P}Ojn3r|>;UkkUfaMDm6dRe*K&mG@{>2&u6oiEGS?~1%| zxyAf8lCz6{JgN(~#`t|iG;@yGb5tZw)Tx{fOjS`449~};jEi5<3~e-UpcVlf3XdQJ z1k_;rOkDldyH*vtq?ZwqlYW9z+$kSk#L-@TRUs{8vj^+0yM2BeM*R6r@vT8gPc}ic zWx;RFjn3y{OJhpf@Hx}paU8;1d#wmn0`Iu!Ser#rwI9RD6eaqd6{%I-BPo@e2QoR_ z_}<8QqYkB)NvP3I`uQH04v>95@oBgyr)zkQE_#3yr?d0HOv(XKM8TvUG9I5>r+49p z$ny1llea07N8fj*3~L$cK4a{VRDl<1jg@tJnV(&Q;#k_X2;`X^mnoX}7R3!sG8u6Z@+N@3wsCR}|W>mC3H;D5UQ0C(m%l{G39+00wit3-G^>_1ee z{*-k3gQpKMDat(WV=1SpsO-jovk_NXD9bRH7%grC~F z+9eR({ArFBUi^x54r{NKOR~U##Wjn}#XwLsZGT%OWn$IWM#17e};H?0Awle`skx)|kj4$5!S`YWfksvxr8(l7-3m zSU?-kA?~$n-1coKvVqH`2+ZQOzy^AgiRX65Nv_aLyi@%XhSEj4bQ!rmcKwa9{gCM~ zYoE6?iacyooh_vr0czk$D>jnvDgACrm^T?E_F9L$2qcgvFO)u0XG(*5PW(rVJxH(? z5rs!|1C%j*g`Os_;iQB0^ql&z#<=bhQ%8IgmTWCS8`$R|B{i@W=Bl64_&dHd{9vvh zy6(!!!S1?`Ki9SvON#eun5KXJRG2&ULW&Qg2K`9B%C`t=d}m(X^p+v>54it$QskMq||wMD|%#M5mVn!!#Pig+K}6NjI69 zBx+z6yd-J+w%9U$?c`ml>Fm?;ALHxJ!rytcwY>Hs0vlYQT6D`KsQO^OMgx>nwEQqr zZf*AgRMpG!apzg_s0BRi1cbeWG@^7rQ*mP9}al#kfV8ug=@7!kRSkmpCfMTi@f;^ zU%9$$`KgX+hMz;RBir)iTcg64-(RfUEjTq&BQM4a)M}cS4UY|6Q_dDm2<)ujkFjd4 z&QrBDe%haV_x1|wn7lktX(2f6m1o*1(nc5uf)Do*Ob)?q6sh7fS$-pZpEV)9hw2Fd zzv5eKBC8Om!8~?fGUFirGZ(>~O`fp+h=#xjY5r~78rOGcPDrmV0#7O(&vzQw^KLt~ zaDRpwcVDyC7I`$H?8Li0dqodsVXdW*DI#f;F_b@LOX5xb0wowra==99@wE%<99s0) z5m0{71!b&flI>l4U51T?`^y)Hyk%a`TPj|C-hWE5_{%HMwHL1Uch12y4J5ts{5Qgb z_)ymzaCpM{L^w_p{B|!J=VsFjsII&k(=$|iQKN{{m}vvlWXq79t~lE7xb*G1)}-pV zxLBWOy--CT?OM)dcR~6Q|JqDAB}=&3{ApgJc9rZ1`j06=MOkwEf{b>9-3S!X1<=k7 zj8^jMAob~2pQvmK39Y_1I7ifdQ-zUUQ$+@FYlYQH@lMvczIvGAs%xY`Tre53oM%Q;Eq{@r*I<(Tx(WK0kI}BX6 z;c0#)T(VyR`*6tLbU99~@(;)aJV_w~b8WgVp_XXvysPoi?p6)T4*U_E_qy?mqxNEb zyLQ2-)^^H`Us`=-X`f?4tNc4WMfn%Lq2xU|za&F7!w3n?rz6}i0w}$M^|)$!-mPd! z5Iv{w#JNLhs^i6oBCt|p#(r#Qd2Rf7WBN&gBm7RRa(4}F!5g`-ys~K;!BkA4sH$QE z?{^)Ro?aEND^B$cB65mD_ZQ0USL)1!AJ4h3vM7H$W1QsIG*q0~ULly|{9M7Zu|W+b zW^tcgo}Eo@xOLAOo5!KzwezD;O^*aH7;yOTRqV01WB?p>cs(TGO{D+K)g@R*a9=FboZ3sG7vWmOs}Yda_n4+jqih+W3T z+=+`;44p>A&cswmORIoVhuy?aVmAf`WpaATCZWE_Pr9 zyS=NG1H^^h%AW3l#9uU|q4vgh<~9!I)>bqRG$BUTjt-)PA~_E69(h_=Na}6GEM-Izb)v0onfy5KvtY;P^sM*sr69%RDKVCPS&l6Qkh=VCGL6la>+{)4Af4?6^9g`?xVQyD zg4`fMF3?|W|DmS|wX+8-@qs27#KHX+-3PS@0n7k`g*@0PK;REqfEOVtJ1E4#+D^mT z+ESGEfdtLN%s=K$Bl4G0>IH-u8 z_%!ssxGk}`lK7~fB;J3L_^7JJ{0!HvC<~4qw`4Wr9u>l-t+@|3YZTXvVJCT6T;eyk zPWe=!j=QYPd2gW6etqC+YbA^VFOn)JE$ve<3=YPW@*6^$s#Ml_$u%{l{TvhTayaSv zBfQPr=RYgeDT3(4z<9iLCnAwHaUJZ5gefx8i`vpFy~VJ=S4sfrp|Dtkf*#PyGrF1Y z6UZzQ66leM(6B7$Hdjf4cbTU|^eOP+YAO47Zx1AZ>kp+wGUPZz+ag$k@H$v|!QLvz zOenqRFms~wW^0>{HvNE&mUdp=X0EZ|Yd5E;;;;Sd;p2SWhTwiE#d~Xu)i9Ejth7Sn z*6+t=0rK>HUoVf}=lr}@L!9P;EGB99CEd*z5mw7cKXA12Yd>E(Cy#l3ESs8+^kC7! z39G5D5`jXt{LLh2ATKwZ*IEo#LPfr*Kbu*$ zoGz{`dos<_ToN(vs>(x} z)X29!#5;_;62@YurxiwiY)Xz3`{yn=6Je7dK?yOE>{-kQv>*PgoP?z>ZOIhT5a{w8{r z(s_7u#P_aL}IkXneEIa5#Y6tX+vOJJghyNU!KB z&hkl1*P_8oH>0Ebqxt8WXYbv@=VaPNj*FTIFfYt4%$rN|-}l=6l5@Afpu?u_{Fv5y zSW)HZlv@l-3^m9N72lKg4;M*dwZ6gdygD;p%HURbsq%~v9Ut>C2-C;V(3^sP{ung& z2CmiQc1cBoq7x&txd73-k8L`>7N2cxso|c|ERi9>3;tuNl=z2avG6b^Mt|Qnt#F|` z`bw**z@mnyq53Gpfp*P5RKyVzBb0ryacVM{n__9mDtebvk_PeXiL7YCJqYGdw&&6Hn?`(L)Wpqw58S8kghDbr0aOB16i^nroIO>c| z{zdFcnpR@a?Qzg4JfnDF%5+T7@E&U-ZL`is$lLbAFHQ(ZJ2X*Wrv zj(+}mkFwww(r)Qn2|6u>?|XOCsFR*8oEs-#=ly)HU15pWnc_g6onkL$dw94)Oj!DE zAe)DukIQbyC0G$VhB$S6=z{=rg)CQdIm#9c@gx>*4CPD)==L%)t*IKS-f>PfR!V2Obep!<<} zOfoMm5!AMyRk2}sFFTY|9(uPaG8ty7sesym>p^?}-tDyu@x#b}|MoyTvZx<~T`+NPINr(AGC_a z+nNO#xoL|FloAfU&VLb+`Ua73*TuN6Js-3zV(SE*dw5NNrdPd<_XqdI?n%%tJa4Y8 zz0>lHShLW)422_ZmpK3n5n7+Wb+m+=u6}JFwVd}im;6P&U|n?|Io3S$4O*pq61OGIMdyU(#)+v_bUbD72Q!s&cse!^IPuIlh|WcR8XBGDex4+LS4)S@zR zo%O%Mc;kS|u4*ViLxJC>3T+YKkH2GTsgiAwsGBP**(i6rW16@47 z%qb|$YG}Y}{b2uRMP`r~KaP!$Rx%oXJ%Br9e_KY@0Ys$;+>Y zJrUf$VMo5bZJzV9wUUlh)*>uATk%?fu%GT*_)d>|JnMn~9~cj#%@@)P&tP z5@G_v&n?JhTsVio@wT=ZLZYkCa*(cx}A~9KCx$^IR1q58B9XCDfMP>o}S*#yQv)zX=*W(OB~k zii*gp?|Odi+JRrbhouZgJCrY-*zf#z^_cAIk>r z!9T)D_u=a;#AGQQt`4* zao<7Y;wsCTDGic2HuFIonfHzYqPUTf=(Qe7>qljZ@!=u|T=?^z+)1^8;U~uemVJ1Z zT2$*Ff+AMUOPwgHL9yEk^g=zR6 z12ERwE=lh_>TNJwyL+Yh2 zMOA0eC=RUx`e|H?wv~*m-?Y-7{Le1kVesk%S_q@m4+-jv( z{64HaRLQ`5QDItV+V!AN{I%9hYT}+(;18yhHmUO&ei;`RIwrn8`br(Sjz-DA%N9(N=usqR{4Sy=9Ba2*OYpY>7*JU3e_G=AmJ11`@ zn4cqsj*)VZX=D!SzUnkyV9-6(nL0Cd?rhCQ!I!V!KKUc!!9MOi&mDnGOyGD1BX_bs z^5c9!=knt0gu%OMc+t@4qy)^7$o3Ge+E|1>J1a6N0rew%88TXZc*4;GZHuGJDa^ZR zvBHW0K--gS5T;gx2by=oDtU^>hF1@NbctQ}qlZ@!;LP;`OqyH3po>Xlla=j<*-0;~ zy!bj(?U1)8^1o;12Klzp`-f91Lu|n{Pa4QTE1)aFbuODp8z4qamf9lq#2CPBrCcgb05G(T%XT>4 zWOeNmmU!(6`q4EZM25{0zIEhf)L={M|3Uz>J=3SFt8Xp&ZECjVEV;_{+!OQx+S2*l zRc&b#YhgKp7>*=h6};;PC-#8B4Z4b73KsPDv*`=q*q?((oP5XL8$j)+gs!kirBfRj zcz8#bEv)HCQGaJ!qg^&&xGpuj3*O`yA9l1q0`2bdyKG0V*XbP)Hyjj2UL|}u0-81f zOGfaIAd@py;jpR-fMTo@99)wDLh^_Fo*8|}TC;nDdRI+nx1vWai|7c^_w;Hw_D4*1 zgI7iF2Cso#Zp#iYjp$Qrgi!cowaZ@JF0v-OuIyAT77!yJ!7IDB_2p$v`JfhWBcmn~ z<0iH0ZEZ10?MP#w+}A&FCJnS(%d6(UoBYPb$Bz=4OPyty*=Lr3mv*slNEPMl0XD4Q zWPk`Z;Iu_UYwM^Dd?jz9IEDPYN^^L8Yn$!tsgcnvrTtQ_$oZrXJw4;=QR|OaLLpsV z>(!TQiPoCnK>1f1`s#|4(Lj=H8nKRvBo=>0MW#KaXVcBOF;c}T!;q=*Mgte!@1U*i zYkZVk_pfFI%PB4Y-d)p+I64rfy!^{WA7>`+?H~6`HbTHA^9`F^*2#;pfW4qE@etf} zF?$MBClJzup>NJ{XJ-~kE?3UBLi)*wjg_Xt0ME8JKqaBLF9VcQGhn7K2{8j}rKc+^ z=g)v`q{`4Wywve$_eOLWOokM26+J5)>xLV)UgCit_unBJRP$C6{KX{ufpxXho^VgQnh+DpuCWIMgb3AB2jU4hVsr03&;(JF}^V*jkU$;w`(`&QNFMm$KzYwA>GK+TIr~!DD9TD z%KCQs*fc8cTlvJub>kTyB{quH;DF6j)Qb{YJj~WMhq&t5p^#f3E2@Mo1_kY6&MSvu zJ-+c$8yPvQxVEX8eb=h^O04CIx3}hS55-m>DUR{xJei+Gw<=h%usW+(NSYS%$jjU8 z-1ptDh~C`}kkTVBYJYR11mx3-injK40s;ytU0vZIh3=0sQuwIGx-*b@FDv#-Q5Q;{aJ)@u-b(lY&l)2VuFp^)Esj*6p0~ zLmDE^o2t%BCr(S6mbiqoz)ugl%UMKD4{np}1}>9q_xud2Z-F5H0PL8E`>)^jSHhlG zSv`C9>{G_KWcK=@*F`^my_ z@h&?arM&RkpG*Fsv~wjuS%2VGEO~t=3i>p9;;=!=D=qy8J<^rB7Rl7x}x<56e zGW#Iyu)Xs~6($w4K{%FMgMlTyWBW7@KQPckX6u-ZcDR+)|C5SP@E=6w4`T3uZ#_U( zf6%Lk4-Y?-rNUk#ZKZ5PzJGo8h<`w=&~gwlD&mY#_zDlzfrBRsszUKli%SwVkt_}&YQU7*>*JcmDUyTZ7wvXe zW*P5t&vhb<$&nKi$b;jAdB4OOL?$W7xFBT;K_655-oGCZe zH?I}xCqqWd4Ycx5P-sNpK=%I)@i4$j6!)P_zihE~2=rwywLb#(iPlOD`fG8X7s{t@ zY}>y%X51E|ihzU84I=o0;e7_ur%XkqFHg2|IwG^|80RaKCbYTU!S%Nviy>{nk~dWrtd!*hLHL z&PAK0v+9x(bIbSiKxIslDv{4$*t_l5`t0*3nz`zYWdLPJOcu_l=)vWM;IhM!fNHZ)v>XEs}x9 zk|BVz;9~m;?5&Jk9&&nxjF^`?9-H3XRtZm)dtv#TgWP5wbKLe*+Xy^W^4!KUaJ_mB zgbk~R07dU(6xlFgeAe{c=MT1Q7s#!Q8qj*-i6{c5N>X8pw0Vq)8qo4lS;-PJ=1B|` zkq@X@S@EAS@*#r=YjGaIAFA1`lE&~K5#nT^xU+$6APE95`YMQA9^9IknA)#mIjidG z%V?@lZ8mVZdLQ*F30;dU;n(Num42-F855cO_SbQQXq)%EYcgwLU37kuM*{hlyu6Zs zIBfeIC0@|;dDMUyP5^<}wF9H`tOKuEiu*IUR8Uau)^2%K6(j-3zu0FyN5%kM9|geo zJ3*K&iy)QQD8W>ZF7f?(KkEA>{!mKc6#pwByJL4_-RZ19-W?#&`f)Xc}EgU=lq0B=gt!UsN#U`PMH%@p{rK z_>Yzw|0j=L@WHft0sJv1ciMks)u{VMaOISxW#1yZATz%Hv)Ib{rt*IJoECAY_?dA1 z;Z4*7?zs4)69gno{^0_Y0j-ALUIi;c<%0~MwGU?hy7UvNj?P?c1S#9RYc*kzv8(%+3f@>)S451@9%E942Vq;F9O17@fpdToZTC0xW&>P z4phIYeSM!}@qh>E9c|Aq+r&M-fs7X#N`Xi-05D=(lbwmF>0|!Pqn5?w-uEyV#D2;x zyl%%qX=KAgMS2A;|JE+h11>g-tyTMugO5+V{)Fo#3XbWGZD&+cOeho%oP(Gg96*xJ zW{;WK_6Ce+b-tQzzrydoPxFs!#>vE&p^;Ex^UaCI9Nx{4x_Aolp76 z2?xpKQ~bp#-`!{;7ZEDPWKWJ`Qx&tl&`qTz2V}IMZp+#F$e`?`j@^5Yq<5fS6;1Vl ze)eXIL5?H;7rA@45nqd?jBfjkImr?egYSRhE}}44F}SjoKn;MWO=k z7u$=43}n73_k&V5YfJkjD`iuYm0`WB9W%SMK)qDVj!`9N_WVzJRNEUc6>4w;MG!L- z2B0mDDzicL^~x~lCy2Dv8v(*Cm&rZLcn3$3Iaq5Mbf~C0?r^zt|9Cx+E}Ta28QwLn zTa-VdE?*%Nn8go`DXHaZjP=6uEL-VffF&dAJRJZ7D6vUJZa`L7+enyVmV`icLB#s# zM+cSP{KNnNICKJ406hb5JOI)l@L6k76i^^1Hz^a0=W7LzY-Uv7OXQ;h_<=(2Mte_Y z$S?nDUl)$1HAXk6DFNz5_rALH8yP`mtctks_mlkn;g@dEQq%U~fpdtH2-9CqOxfy7 zq)2?&!~N>_9MyM|U+)0eE$+Bm4#>ev&0F1c5~hJ88{kAsM|WDgc7gi=1_6$H5Z_zF zGBa!99e+*~16U<8HD8`?0Cg(}+~05yWMi8GkLQ!HD8>sIg_}NpZfP`GCk9Spq;0zq zfEu~f>lD3b-0IzOE!WnE5AR`CEd&HUFezD0J}LhQ)7ymT&{P-NN-ROwCl5iVle#*B zm-X$4>f6qf^Z87msz(5H{7g#jX*fRzG2A~+3x_H7(sRyrRWPgJmN*RS6ez6I3o4$# zOUWGDh6IvS0I-n+`|=Q#_8SiIxy5ciW_8FC4*}T)7}E!EbTT0B%#e-L98QS; z_yE@o7v6M`rMBe(bZxdeEOWED)eFS4j*n?{aV|Y%?kADaNUW5V=GHLCLNQ+TjLl4U z_6UGWDdk7q`S>3!x>LBGpORd<^a#5c8Otm0w@-;z3+SLI#T_K8Pc{~O{)*^R!e&!V zsdohzx4DOTuUz$df94mXitX)RotROwP^7?edh}+m-)Jk?8;j;{HUMbMlC^i^r?WG@f$Q!;pr~9~SzivaJ=|%cUMrj8zE~aO z|BMJ=Wwv#qC=GCbSnKDSeYHt(s#i*Vu_=Sp*y?Ynm+D%XcI*?@Dv48c5AlqTN{bsi zD0r28O2>3J#w;+WYAy}8KLW?-0Q?6aGkDvlOXt_cw8V4O0*}1J+4~=I7_~RA!(mcZ zFA(Q0E(U5zFp=L|S<*DT9p~6aK}?M(NaV-EMD8BwWfEkFwqaIMS4Zk*G1tEW$-N-# z^Zt7;K(1+|fpF(QC!09b=05WdaH z;(@fI1Jrk`hC@8y9x-=YpImf$iX(tE&O6EtYUGr1BeBS40gkP7Qe+yRSW+wz-~+q% zBtw0?$@*$!RO|$qn^J(!h415FMa5!ThqC}aWfXuZ^y|}B5GEGb={NRg%waArp{iUa zM&cjK)>TaYCk8`EfnG?+PAX;FFB0Lq&*->+_Ewg$+jO?6=?Ni(ZroR5VP{8`pM;85 z+Mjqw<=2ap9v}b8QuHillYgneAjr;pmDF%7IO3rCI~zB&MRZ*GPY}eeL1>V}Efw1L z`vh$^pRYrJR|feyqePygh!m*c*rElXbRkCQh1pqHewjh`ccDha4pc8ZH^>Z>#@fYf&?>ftC4 zxPY|&-@N@TU5>mD<0eEeaq=Wf3$$WCQ??^jRnznBTz(A{WPx3=#Hf$8>Ka1>t*lPN z>;#ow28Y;O-Fo$G!@GBdQF}E%-Z92yDL|*lk37Zxq~Dh>J;bP^`yqD0SH{{sR`c>s z+)6$C`QLx-N6e+bfkZgS_Q%nERtvX)KF2J!Hc&A)a>2vbP$T4~b`$%oumiZSs)Cnk z-gx|JyZ%&&@5>sf_`1e}T6)DfkeyAP4$E{Amvqo@+5K&{z&TV{4gq0EG| z_(2PHH6Z0EdHT|GtUU)O?Qp2J`xF|P0A;w;+O5Cjvqzs04iABPHBi=U8%N{)mep#W zo6Yy06Zr3`<_(dJm|N-;$Ei=uBE1Hew_d~?dR-esKWuCC5c2iwVj{%v;wmfokg+Md ziXp9WTu^kNUrB=Iqj^HL9*3H`dOVN0+B!=Cv^NH9Hb4m+AnczLJnYQyP*U*cp&xS8 zT>GxQG3A8QWhtAshno1R}v0)?fr^7I9O zP5}O4m;!^d=~jmB>{x0R=*T!Z@ujH-j*n{&kBoG8b!{Z^@$-}PmdYzC(s6S~&CJY* z#>9U6CJihQ3RBs3tC_B|T{s!<2SPwR#_hpGaarAgcy!F{?9kPo=+V*9-*a=}oy%z%8NS+O zroc`^ChEr1-roKoNnVTb1sefUek)4P>$5R`61+$xT2f4-1k+fKFj_-teuYiht?ljH zoSX#|@e4$Ne(U;imEPT$&8ZY9?B_kt)Nx_Gi zJ)!`CJY!0-dBn@h+n2x_Qe7=T%xTb934}Pj>f2LuR z7jRtT>MEFJZgdj#(#=f> zkjA&@=!gBir>6yI2Z)W8gF+c9Dk?1Dm0^H_AHw|9K5Zl_5(;)kadGkSy^TQVAkf(p z^iG=?V8%vZM(~vYB_n>&&f!J)`ZOGV9ybR7@LuA8WmQ;A9L>4!=5}*X*MHO9`%3&J^G56D$D@8|{ZXH> zuOwp9K%ty?a=~;RB@vmdLyd6EMDmdqV3t5YAtWIIc=#a~VY)e-$-~Dt{QI{A4ekbI z%AUmI{x?50!A5PUSEt(n6WhBY33Ef)Zd;?dm{cO9fY;48dYW5XXTM4n11vK#Dr$rw zaDUk^zP=;a;~1N6+{Yzfz8d$WD??9Jq~gTio@&MX?RFrmsezJ>MI}$ z0juzBg_sT`0jfh=PjTk}jG~=Kc|i1B4?w27zcOgWv;#}noNp3ePxTh_^Yg1e>R~M} zFF)A&S@bnFw(|*zo`jVZhjrs6WAnQ&SQLD!hK7Ti*{K77vp?wDxFdA&AxiV|R$TkZ zqOj?MBH)F$MEmt;kG$`D!}L5ip8&mRb`g}O2}9$XKr7GT9R(*Ofe-s(XzV#tlkd>s zePgNay7Af^_iVF+s(Y7ij0|vQ<9%`L3FN-3`_406#}VSvPF~hPatoaCB7QHePXgLM zZ{kxATD+-fxmjZYfTCqXeiArE9vPmIe%*8jKwe0{hiBRnh=#nBZc(tFfmwp4w>|)8 z-0aHAKnKsT^{;no!^5@hafue=`HMh2TI`~Wc)YPAR06~Z%_0LpZpvmk1HHZ5Nt|Ht zAqL6{zj72H7LGLc&SFR5hwUs^JzMR~8yR5BB}5+@9+tGTAq9qB9g*E0%g-F4+J(yyddcZO2RZ_wPw(aD3M=~<9m9;fsi<8=)Yv}Inr2~T_)6>%j z@KS*{#mC13fevK1BLARszzpG)u;u#W0Xi|Ulr*V;BS3S*9wuZ zv;4`-gpWPqeV|%D=i@Gw=i}v?3;Ec)OT)t8pLFx6XS`quXzwuF&f+SpTlTW-T}yMf zGX7m0X{pl`1GH8txgHZO5k%PtP=2$1z8n;=N4Iefz!Wu?DFL=Z$q&7)zMo%M{@OjW znSFZBef-0`{tWof26iS=VYN^zldd37?+r>7c&?)PMAZr*Tn_GjRDTo z-9PHi9Ot6V$*X6v@xOA(4|dTLq8}|qMf|SIp$7UHNJhsejwcem2L(xPz5$(g5B(zQ z^B#WrNg}{Wt|Cd_YE38AJ9p?4;0!{~`TEvUugU+~sv+fDxdZvO#U{{_*;KnmY~XeE zT9ZRt9%w+Im?(g(Odjfa?XtUL`oN7_$`An^AB-zfGFkrudOmsLjY&9=&4`@+L`RU~(mdKY6o$PwOv+VB?5DGMKh*H6M zclHW&+xA9wLRuFmjW30*GD^1xj3?BU>X2QtM`}6;nwJm1Bq!h2^q#ngm_VV9u6^65 zPX0&w>p@{*v&LR{K#qi$bWRlGJmX9wC>ZaDLGm>vMdif{M00cVeC;xSz*kBwr?~9w z>;gkV;KqVLYNzq`?Z_l>qP*R{eCSYT$A#&$1%ta>=5{_{9t;?3cCE?x84V55Z&SR! z0jMt;Yb;wRwg?D98?DP91@O#UH5<|k1v;5PGPf^l&MMt=f99?w80vNTSNwE24Dx=h zq1H22HPfGkWl?ihO3i(^!VR2KcW0x zaEvwPOG;$-V9^y_XNt>nmDrG*Ihnq@6)7MZ)HGoH!SC9~-#0;9e{JN<04>cKS=q~B zA#@D9$yxqx<3$F|ADdg{U#k2nO#@O3-JbENiR{3YQHLdbe1t@xFKt>^x1tlMHa9;3 z`7e-Fw=UZJu5-2q%*h`Dh*%kjOSrJ4>7hJI?0|S7#}8&m!`f!aGLn*y%#t06)w7f! zhfD1Ol-L9Rr?Iz=iu(KB#Z?eg8UzO^2}PwtIz$jeN(H4s7`nSdrCUV03_@xEk%ple zkQllK7`g@+x`y~2-kr+0m{ zkj6;)o@}j`A^F|b$0U0@+!D7YM@E{%?-RXHM9#$c9~1s;XHWt74^r~rUe}$TOZ@f{ z%4;>TUzQNpU9$Z$I1m~UgQ(y#t~apCuXqj5i`?a|xt)l*SNx5v^HJVc`{_`lB)}PK z-Qeq3p|*7(BEajX8Owlx;Qj%CXgKWa0zNfMy$>*bE}qN;2rG5xr*T!1jBw|P@v6!G z65HpT#DncF>w5Bg9Y25GCJ6vjp`)wYctzZ}e{$@peDQjEu7R7f{fDS_o!ek`!lFf& zARytHb#OQsH=lQ_1puF7+yhs)kM#T|FU%dHqoNis&q-ERycopbI2XUPbS4o`9XTjh z+t}DF&)0Gj{xE-y6kVo2_4BW^aSgVpjFa+Js+xuQQ{G`BLB!t3%F5>3*<$rv9KYy$ zrP){4wLP=#8Ax$ z<3j9#*pC8RsBV9ArTDeIj?($O;vzGpaWDC3$?zBWfM)=D0p_Mg4b4_R-PfY9Mw(t# zVDje&USqx}(Qt0qJTnVGr_mCdt&(aj4~0SIzNf{V2pB72Mi6kc^^Ux*L`~6pxo@OE z=;%Rsj8>!z)4jr0mnGG`St_`2J+M;UA&^U4frE2-)d}LsfiaYWkl&Lb^duw zi^o@q;Jx9BtL-fwGpggGf3t zt(4e=!sIkpEyIG~hD1_OX4;qbPII4_szBJC_3@`V#V#lDq^(r**_!W!VtMygQ85vI zj`sy})uN*N99sK9ML=HR`4fontOo#<`Fy%5PWQsmyPbdB`BVrs^$ytyNEw2Q>x;_X z)ar3ZiyssJ{=M55^b)K*z%UN_VDq z2Ip&h24t}}A|+2mgkXj(Ay}36MYnzsd>D(vY@Mp7zyKc9^Ow;|_^<_AZcPIU-RG~} zPb#Nn<;@6M5cG% z(t0bpJBH`t$^u>{fW5DJaZV<(n6@h(Ly9|K>J!DTqA!e=(d=nn1c-DOFGRWxF((lq znSs&(!U#2U&rWyr`s@5^Px8p zz=Uj;qax;W8%_X4$CZ??jy1wlg70+8ydiS>wD$wpiC?j2Ta?NQe_~wNuCb@N(Tw%e zCjs7PjQ@5jth$svXjxy@CGoH2Q(u)QSop!U+%#WCRzx(GpEB6A6y?C{ZJ0nkE;z7 zJ&tl;KgYnTeoC$4blmhb#;Mjmsi*47W#O*pRE)giCaG0?SwX3FVhMVy?p| z#h#AP=?9|(UEw9wHmtx^2|gK7*Q{q~5dfNq7ecP9JP_lXAu#sp}c)RUFZj zlXmQ=N?Yjs$rBNJRj)fVaT&?kB#t+R0%}sMK>JbeuTq6lw?%#cA3tK`{Se-xJNB+L zXcij1J}}HjzEuX;?mM`>Dd_Fci^Y8uY66f|v%aYrM)G(fDv?A7|J0mc`1Ws3uvB|@ zWgE#CXC=sHS~iEb5gpCccb*=^R8q|E4~$Iy)fYaG&OF_DY~Xt!efyB9QLXrhA(&(_ zRmgELKGCU-$!>9*aMK7i!qv+DU|?jR87w$m_)CJVLzMkJ@*A&8O<8X$b^@l_=QwnT zwcQzqvvfLw^>9iCSh_8Wm`Na7$=`cQrd|>zg`9C|Zg(v>9x(PiZjVrljgRa4 z@EuR<_j_)@qN8k)k8bPlXIXJ*obxO@@|dXAa~({_6$0JKeFp^8TRfEy^V70WuO`$` z-@D6T)NvFouG5M_=_K#2x?EOq16y0UeGS~x4a|iB1EXeBLj!+@#J^u?X!wn8eR^P) z37}~Mg7YW`_ z9{R9+S@iHnW?a&3qWDmFhS-j$7Y~d2ZF2i#-)r-Njx1V18+^OUpIvQ0T8yoGglkc**@(YvH*~)pu&92G zy-~e4!_Ll=sb#Nc{);4t1<)ob6c}*~^rQz`2C}}Ape^vAf~N5vyEIc`SKHtF5gseW zm9d{c%WZ#BwQ%-NVzlOGOT_O_y;p`*y}GsBS(7ij30z-H$d+*}zaNVLAc zvOuO*uI~pJue*77oo&yG3nseWOBfvt*d@fOE@iVbHEnFqxYQgiV(pFFL)32&;GLf4 zTU*-MEb;i)eaX~!Bnb#6!ye?SleB!Rs0fat6W%Q6rVW;HwkA6N(13y~bX9Z$o-QDR zs*8C%JR=}BL-Y`~t0Z+q#7K7o$}>dDiykok+pBIOs4|lRqf~74IP+GwLDdBcApl|0 z!q9C1260!?+3QI>vQ)fMchRooA;FjCc^=f-=6z^!e|?h^wYHLDyz%5n2e;CA{2aM) zqX#om)Pg+}@YtH+DKEa@Z}M#W^89p{M;Mw!&=VDfAMlYU@^$dlVTQ`5=jSmzZ4+Jj zb*Fn!khPcs;8t{Ys7w@iWslR3-pSG!DCpeUz8Q9Ua-u7~Mq)Ew6?-yqH#m~MOhH<6 z@G6hgHZM3BKNyUQf}F{Guj*&@Lb!F3I8;m*u&M#C-f_a+|EWPH3u85w6jr@&H=(0@ z$=RQ| z7WC^Fa%CEnAxAZ5gKii1HdiJaq^tB`XElBonDj)q$xpsU&Z4=h5_O2tCxd}psX{v) zXa2Jai3Ux8UaqPR#mlp#6%>9#dFwh~=(JrqydwBL?@^IO7q4O z8s@{-mEEbWh>;3TCn7KBlSBX3II<}u_2^k1R2jE2e?~|KUD~tEGB;B%HKmfq^_2G$ zU1^~JtPAPx)2)U=19+eS633_5ndfbQZxLYHvJ{2s?BoIT)?;0F=Fcs&@B8bJNf&4} z0O5I)GFn!b|8(n7-a0>2)B4jD5aU1PEuJk)3eK{c zl$acN4`>_M3L^QFgGYnRR55eo9v40KcIm$rBHMlBaElee*ha=vf2~BD*PLK*+Am6X z^X!i3@%71_+AfccYWAwrL*e&HTjT3$fUka^OVT%{#^_293CZ4u^oIhwnmE8Nu0H;o zDXzI5;dw{}Kf`nGJm1}9%4{D3;~Mg1>v zU(R#4d>#^R>W}vD5(5D75xw7SEAuxVn|wC+xTP|nF_H;c(PY(U*A@O|R{lJ%ONc>w z`xzSEy6D80)x73L$1QSFT0 zOJnmM?Z0ib5eb&D)?r_hp7NRVeZYTljrd+{f7GV@vfga4`^7JLswg>@+pkC@GMyc+ zxV)|R#ndk%3()#!jn+Jph_|EDfpmNd%B7+5KYdOTFUZc1YyE?; z-ah-94V^gqhUd7`AWr@26s>NfGgHl-2_>Ex95Wody=2X^JI-^K3MCZ5b0vw=(8$rQ zK6tjoW6&IJYd<(S5{(gK`|{{V=?$8rwPL@3;)@;IZvCnxr2is1L*s&N-VuJ(#sgY* zoSM&Ux_the^lgZX?9>%`>+LpEXCRCB(q2B$swxRfNm&~&8#g_FEa`$Ht<$DIo~=ty z)Rq_vpP8%TmLVq(^eYv&;kzvw9Y7*WPZ$YB7L{G+VxzptpWIzac61{wsiV;UM>O4H zZ?S*e#c5P=>HL|ygI*%{#Ay!v%)e=FTfKh2240 zhdb{%k9V#*KMoIIxY};CmNhaJC}iSMl8HBkORjz2f0IylUPQy>aWt+*I#CYi+%f)L zK&p2x^}xn?r4HkCIxo^2;@^F&I}we?BYAk+e+z~FhJ7mCrCH2M8RayJKC`c|^-axX z^i1llXZTZrG)JNAw?}e>J)Bws_FP=&R>a@O;+Os}Ep#f#^(D3N4^~LOksj4rl z5OFEZ+8U;M>kG$?fDaMHbzWYZzshI4ulCsX_-t$XMb%!++K<&*AMSmOFK2?w1YOlT zAR2wGi*CF)vA;;x%=G`5%QV%9J|Ab|6O(XJ^)c03i-Q@Ljy+O|b*A^Q$I$s;gd2LN z(`zj(Q7JFqJeiG7<}?n#g;)o9S1(63n4V{-PWct zD2c2&5gjbph>W2|x`JCegWyT~pC|?g6KIznu$+*(l&v+Z_0=~7m^1nYjv9`4IIBrC zXJ^($zrZ)}I#7HEs}BwT8@_r#KzMT0fwDZU)?>74 zoJcg$9^%yMm}^SM{thF(dFC7J+^HvKS4Z@HXfHM^{W6u?h6W4?V6}^bU|Xi3!dcs4 z7^m5`M0NC-@=VKqrC)G5wgFL5i8kK+bX_F6C1pRcZ)ikSggVO_vvyQ}v8{PJBktei ze!fQ*${wfZx}nlab#o(BV9)D7BBno<*$2t0A3G=Pk8RkE@!wrO-MBcx4hai6_GfDX zc(`gK5#D|7>pk{+^({Ai?k=qEK;FP_Q!$}PM*)Jb=R9w#K<^P175y1l{HIMfzw>Tr z>-^2l({g|0Nf&I+8hsjLbJQt$l!166Jl$)XdBIX$s3v%K{x8NZZQGB6;ObA-mfKFE zylqz#r^Kh1vFE2T4{zV{nXhbU`$An%LIXeIxQNa?+f!Jd-oC1&2{T%p*gu_PFwFUk z+&%O^miDyoqSN!+FZYuEvg4y29UVQPIX&J|XIkJI^i81E@jW`)w$M1?ON_=dXkyJoQpF&`ac=ViJ2J^w9aY*Acy8`_ehMD`i8B3L(&r)oxw$ zj6inmdMxe>D^?aI`RQkLzz^!1hvvKYFx9WNLfPlEtR1Irw12>QY7zBoedQ(ImWa_3 zlqbipqDX8}v)QV<2E)vWaF6IXjdQ{<mHAsGS+;tOr@PLv2b4=$Bj4u{8>QoPo>`1eZbIHU02o zn{|u@r(Y{Zls2mOXmfgE4oP;7f`p6>%}+v!+2nqf(l)Rst5WA;1DVcY9uilV`XZ8& zpq0Y=a446?=uqrmlNS%>@tbB{p)a!D2rM%yt2`H}d+_{kRC8H}=fW@6pc5Sp)oi~7 z&dtvPV@o&BVZ4Dnz8j-_?GD{R=^AQIQX$I$qj{A^tJ8X2i%#h^HopK;pioelKd`(g zx^A=ly{uZU!C6emucRU7u)@wLE706fEmDnFOv2|~qSEfI>nGmcv~;xn1@ZvV5$Rp1 z^AIibL7RUoj*0#Lz3fZZtz-I@fB+`U38ewEbbXW&`3x?oj4mSz4<~-GQ-<^JhU<%a z?42_S@M{qF5nlLsER$XMub`ROZSL^k)dVo1_a&XG*IzTaJM7`K6yy;nm7=|3$suTe z6OYiu4Bs@|MFZ2T4r|}%0G@c{-_AR)*H25k%*H>ya0H?AKPQ$xX+jGKi8<{ln?})8`qzXQX_vL)Z55q9k<3_I4ul zeA?KnHxi}PHqyKffHW#WJEA=a!jx$s=;Gv)wq44%Q_UGiMde|Tk#UwzytjXCR)MkJ zpv2}rb^I`XhJqV^*GfmnkoN2q=CgXjm5IujXHvpbVQ{Q~82>ZK$?aRB1ScoqcOq_F zd%*snWBIp>t4sITc3W9Ik&C-qA8Ig)Bw)3eU`bHWY1iB@S^4?!P5pGWOZ3d%Xa})RX`6O9}P19*I=zB}^{h2R)141VcGE+dUx@Qn9#B&z<| zM|cJ!smliYR=sg>$^-$LXWHG#$H&Y28k${PREAqzaTM+w857mpVPdp0h??s8xXE4j zEQ6QW($YHDcKX?ac7@fol{CgGNeKyipKWb^YHGRp*g3_*a#vz9lC36h`^;Kt(dQwhbmKAzMjwG6N$4j z!cGm1H?QA5mrBeo&5kmxIv=4`Vr96W3yo|#BsyKmY*652Ts|;7xfMS=EP*>BAn+n1 zk6;JWrsv+3YiVI;oMrz3!B~};pQ5vKOrN3ozUO&jpO8KCq0fbQ>zw1-8Xbg*ZgGvy z?x*d!MDPir=UObGgWer9$LG9X3+k1AX6?znD`J#@#PVjTd#L6@`g|G7=iX!tt3P&Y z=3Q9LoI)W>RHxAuJVHp5tAa*!2+Iv(Ls`@ zV7TCGgL!Xwt~YrnS32-zR-MMxm2Tg6!+K=$oTnN>eQdt^pXFk|z8mK?Q00y6Z_fEemdVK*uMtYAbMHfZOK)V!|Src>|L8DT< z#xELcimRwR-Wm1t_1aH*(OTlNcvq<5#Q9xO?aF$fIbE>aPrieVX+`oQJ;xrBs%Rya z)!!bgx8AH0ry6+1^4_?NXr7x=gIH{K9KmSZKd`9hIz@7O=Q`tQKiPP#wRl7Vr{ogl zi}t77iHqAI{(mQrBdT`Pg=1B7$7+sU#SYi!+SSl9f;98#!ou6l>M=Xj#izP!badL) zc9JpDr&RD0f8T)igm>V~j#UOX{QfxKRqv#;V64uOm8q^azM5zWv=zj>di}QTd7^)R|Z^Dl$D@Bl0}` zj?;pBG2AgcR&*MtCp%v;Tv?k`!qpwK*KuagL*Bvkk*{>6WoCB4==jIb3QD>}AnG+O zX&^%c?I-HDfly&fB4$F=`Guy&@AH8IEnHZH$70Z(vF-EPKYxVFOn2qy!tjOt4~QU$ ztu-Q~Di72`wks%6uW3=!u&37EcJ|DD+W7p(^TA|C6AyCqZeBhtJ;U3cOR)UU?kQEw zs}Ao$3@WpKE0Rx(?#)~MmV?9T9A~WEJD4sRO^Oa`{NNyUk7Rwm;>k{`tK+Y_{p+Dzm$}Rd3gK0oF)9VzPrcd<$MPPb|)2X%Bj zsP_KjlRNs&bwPLf{J(|hO5wWL)GdFCorXy{yk<;dk&IA~av`_%fl% zN^TdYy{%iL;nXg@i*T*pnV{osH!`tsSmSFeVDvP&iay+~yT&K&H$-#`;P9be@vOfC z<0UzqYWeGWCpJCJpOR{4?(r=X)=SD=w~)V@M~al(e)yAB zcJg$UN7;~`{l+yPbZW0GoQXWDdfnqf|85EjxJnd+k=_V_!_MKPXhP+FEI5l62H{Oj z(XUL9jnO6(i^q57d^t%A2Cd#(QoA%`utM0Q zj7bqbdDl8p>n1*4!9FEdTZVqEy)4ZD(d>ogn&9V3np*>9YNhAD3vRT0^SJ*buYWQp z!7YK)@HyLEQyY^&<(yBve}Kt@IP`K$I?#u76~i-vbC&WrSekT;8=7l%g`CfdGVjyy z1TTa5KLqPN)NA>Eu_nUfXu9^MPp0b~Lsfr!GO|;QKAZX@5Z{5=`TO_0WCqmqV$Y~S z^R5KJiI?_o<0l0p`Y+Tpg{RVSWBX0sfBqnUg56Xjb^s2}`C)>T4?o%Nha@Om#6M)w|UT`PPoEmO_^XKe(m$T3bckn(i`MH};`N zA1dYy;LAKk)dhhBhOzzvAqVA?I?hYY%PUCLvFiK1x_D=0b#389S6Ycp=k(xwiYs+| zds-YMt2^sZvcaK&_W04Mj=G=-&x37})4dFT=ENT3me02K4T{bvy%f~a&IqR10j+-_ zCzXjuEUBNK^~Mt1!0+8N_q+o8_x=dRV1kq6q>eJTvuug|4!lVm51O4ui5y=l@uE2w zvVy(5W6HeSMb67*y8(w|mFDbt_4VDB7D*{aub!h$gVs-HBth=;_|vzsJJ^P@cxr2& zW=AP6!85Jym6cz!S|(`y6ie6m8VFxQ4C0-)+z2!+yFQX0r3=&nl$l;JeH_6Pi-5 z={bQN2?NhFl>u9hoQBu&g9yiOwLb&eT)9C5-}31$!`-`PgT0JP+y)1wXy@?c?&~&u zEmagg=;c|ai_dg^+huI(wDgGg^ycl$+928@$IlX=9+c)-*!3{Dif}CX-sZ?K7seJ1 zO-f68@8j}S+4O#?7BTWrk?jivZ+x8%%F3$ocJw_xA(WUv_WNgqD=Ua>K(qs>rYH`x z-&YHR@>A{_mp;r8j-RJb)RItT&SWRXGv039`;ar=n30YeKbmv)IWK7VgsCAWA>G=l zci%lOKE1W7yc8&(!9aLmhx%*Ev7C8AO~8OK-8hNRu05a2<2{?T4N}Gb{45`nWKK9$z$IRx`OY&^VdQPXrKS&`_a#e&LZ{q z;mku>VEvhx_SyB31{Yvl4q0w3{Y7 z6P;!fPXj^Vsc z6|o!nwdJ423JTNT68EG@|D^-fAldWD7cP4OGHqK2K5nxvv9la{Rw53 z)5-0``?t)S-113Z>JzqcL?>&XOK@grHbT@7h=gb#!Vaw?G(T{-N6*jTuHVbM6A1|Z zU$N}Wt#jO|hB)o*H~VX`gXp&J_cKbW>})+pWmuZ&iltxfaShAlJu~NIqzoJCUR!>x z9&3yc=b2C1xfmFw+*xZM1xk|!$KH559B(n=Y}sOYJo-^7du^t!I3T8wYBU}0;!sW0^4UW0B_|E5 zSQnYjrDWjWO<4w)PQ}*@p`==Jy<|GJvS79TX_WadFPAcx;PrpI^a>w*ZXmm;li6Wb!{;@vQuXOQI@d1KMd>W<3jdA#99T`1^ z=Mj`AL>OVa>C+I=tdTmE&br{d$!xnMW#epK+Ov+|Cd5usuMc%u-$Zc8jql5lwFF#m z4~{_o99trvVraRYGeOTp0$D?rdgu4}isM!=$w}j8hawEM;kKLS-$G_TUW2kSRg9No zEo_&@&t%j}d-MfR-Kyo)_L_G_CU%MgUT3D8+hn>XZb)G;jOJ)&TT+q*TBe)fwo7_7 z2PA{#*v~==*MbR1t;@XA*0UZ}h+g%bqFSG-Zdk`W1?ynu;xYu^0UnS`R|S$U+uK1A zfroRmfu8+%U}cp*%=|w-JM8Ob8WU_{R2*7t6REFy!OUOYs3(Q$1?V#1t#z>Mu~P|RCG zR*m5ls{DX?I2qml91q6zmW+N+A;FW*NJ+p0kB;Zi%$NP!-PgyP>UO~EzRho1DUdYv zua~u6&|X;3{*rgQ)PsK1^=7~oXgJg6N2Zw?0BaSNgEN#IUnDw!FZkZWX-3t0Of^ht zhH$Xy9CDw3W4(;ZcF=EKY~?}Ht!Wk(^CvF~h~!ia*zSU9+_QCB%^G+V`DhpD0XgUm%UELW zsf^$Gbm@~iwjsfUAxZR^edb+dQh|mtzRYbbWl8V^vhi_iPwE<8S_B;AAl03UjglbQ94h@&#}Azy2Mk z9T`loG=k{aD5`?#j-W(@#N^$a-nhOR5VPRGh>^$cD&RMYv`Lq7DKed=rPu~YM&q4? zN(ztl8UG=$T|F6X9_xU-Eq`kYPpA3G|1hsK_I1A1}1|=rIusIFpQzzseFl z&)bh~K@~@L*SM~b?Hy1?wf!o}Fzu?Rl}(~U=nwp`N*iwKeWR@(WcXqgb26~cf9%7k z+iuNAjrm3?T`cx+QAUF~Q#$+p_2<3!VHn=A`o#Y4S6y;;lErl#PdTH@KEL2kUP$5K zNj7kI5%N6UCe7#gqIVKTUA88Rnfa}}>Y~#oQV{cu7hvcg2-Us*kmAP z;x{bdxUt!5SLkSp^K-=>zGi@c z|1|NX%z)=hAX&=9CZb}ZW4o4ysP9WWb7YO>zt9=rl@e0rP8~jf%q%>&hOxY~gXEq+ zy}QY)^KiWS#roc|@}Xg5zZi1ali@#IWcbi`-Ds%RO0J2>p0iT0oIK?Lr*BDdLt$b*UZ@;vRcxr6Rv6|U=kBFh1Wa!{S3SX-`qG_s zlrv8vc^^t1lFqcQU4PfW@@(EK?DXjmTuL zeRFZWf;)7jJQ6c{b$ND}aY2cJr64&hT1x|c_0VG<)Y~x70eR0654@bxnm_tl%NXK}~l`sH?eddBh31gDfIOo+Ogircn8oQGojpl7Fj zsII&ih2Y?ue?8)_TXU7WmTP?N|3d;LwqxU;kD0Hj+UzEZ5`l^P?#n}oH-~&DW&I2o zeTi9RTLM46Ly^apsTJ6UragN~yMjURz0z0Le0OyM(z2^2rN~J$|GS_#!(gok(jpKe z^^!k6WqUWE67W$=W~aT67jmVZJA31_4Ox02vP#}`Fzc=wQUV+yFHOER(vJZG1?lSI zexgA$$L;W0DkYFJeZ-d9?BBJrvMwFjX)h>#qy4t+N48ROTAImV7f+e{GU)(yd||^n z|HLwqC!$6u*qA|1Fjr5mS1L*(B25tB=PZmdiHjq)Q-8t$*33L7pQAv}wY6kjygi-3 z1?i6Lm!B6|_^qAced-8M)4#^}6FMS&!}?1YoX(d#wo*CIp^x(->(iwH*o%F`vekIa zvEQBo_Vw_vjNY@lok=2zy`N08BBZqy_RBD=U*f0b*dDXvX~R=dfDhvK4i9$0&#a%! z1Q=U!g)mBK5#9wlO8nmd+^?E zGQrT<^YTfx4^VT2vB#MTH;BY4fAwc*{egeI(q`=*@wF5k-J>Y<1&_u%O$q|$XiSMS zN(jE2>)+g_Y0wGyTL^Yo-51k>cYv2dwmpJLJyP@ELvZTU+(sWpd@qkA)uHTUTk%o; zXM45faCfbz+<4*|_M51$9b({rYzjbkEG)h5cugLDuG_Fby8-d@LP~fNeE=S)`OX9m8ro}k#r7m>(?$JuX@MU1(p zK2iYtcc0VgtgS7Rd&HZ1Hh&|L9np7sgg%-=FK!4=&v^SEFB6jxD~Bjr%K|hSzY9n!*Cs!+d&q=K?OP>MUVqy`R z&7nD4Ln=cH%ahb69AZ=dX{)kIL}Po0M(f{&*2e-+@y7*^!`SCEMn~Su0yW$8 zTSx*Zz0_G7kMpQ|Ls#Z$B6>br{6dX}OZT0d@8qQ0+{Z`6crY!0zJ{uu9cV~bDIeqH z#mOUVWq|AZ00?#b;%h=7VoMvl*^BdZboP&YtD1{z=;gND%pcW7=~2@D9}DbjVwIoY z4>S2v+TTyB*&tPyU1!WuDJhEh|gSj!BG?1FJ!h!Ch3++4rc}xfb%mwLd!n)n*1s%l3dG7Nx5saW))h~ zKlnS{h}_uLGril4K17aR=5ah5O$4AgVC#+_U~R{n?aveKV_%vBScZuzN?sf8#g%I4 znf!6ufTjQ8h|Ys{MAzDJng$r*WtKr^&Gq)l+bsUovIdFd`9AlVE9jFb^a22rTO1kI zV?8OM^g0tL&$H~rqnUJfQ2!=igdZwI5|dFzv?*o_fQ_*`hDXLL#{Y(Z!%oX-+(tXS z%I%NXufjZ*c-2Jhsxkr6Bv2)(y2$XZI!&?Gf(JDj7hJhQzH|AE0JA5V7i*fHi`C1X z?p?Y*YZa)__PNtl|1+AyY1cdG<2X>uM&od+RD@l#_Z}zqQ0f#_FteCv;x_F4ai}ua z`AU1VDt|I)KhXDnW9Ct5&Xb&_loiMhp+)pf^#>%n102X)SOQOm9MrzLzr=G`T39s) zCnOxWrJ!_5M<~_Us^7OcE%CrVJY!bN`SD3Ztfitzx0FU|H=C!-q4WBm-gLx!e`z8b z!>3|#qP55_$N)7TrK0n*I~!Y|l4H{mzI2SJQ=8@}DYqvpil0r*XiSp2lurCsgDz}mvPJ`E2D|NBzPvn2`? z!4ulP1hqdEqXNft?nagjlsKT8bH7yQZh`fFj_22a=1R0*YEI6ByLaynF|&lg{l~OV zCC7qE=zitp&4zQp`ZB)KZu-uPrda)CW64e(u_q=zh%q{|GTy%ZiojXF=sJ`)#HOcd z1)6(dTcTB1F47Lro5q5@*~WG^PrR|ao5+2KytHcYYjSW z?qVESi}p-Vnn<~!Hfy`}o*~fh$+lBoK+Az|DNlqnufm?=wkQP16+~chRTOtd9sioK zP3f$R;kY9-1u4Woiit2HAQfaJzgfychj(c(D!aT!5GSPMVTs+8*gKeB9w~)rpep3H zD1%Jf*XL#_6mDc>ic6olga!}GnW7gMh+mE*^xv-`c{@A|5g;;4(vIN!+V;kE3BsH? ze>$mZd(mXN_7@YL{OYZK6jX5V6*#2oslw8p$$?_$eevYsa=Mq0lpm!J+xg0VkY>63 zZ6N(8@r>@8m^*>Tzm3gV66O4jbCgl)2atl-Ak2p0Nxw3`^o$)grjbS_4oP9# z+x#g@4x9Uqn8}LY2Ix^pOGh8?JQM`gqcU=sfAr%z3YX;d=oOe&vW>Zj56BYs-?(0Z z(KWg5yXmZn-H_#a%MOhA@;t3x%w*NM6=RrE42tMeTHQ^akTrzpEv9qHH_W zbU2L1k%^3qnDXoPW103o}yh&r-9g;#@iwv@AU7K-4~=IRW;sDTKl%(TNpq^@rVpW1EPxU5P(l6L+BLH zBZ>Jj0O86n)I`0{Cv8_iXb|2n3<%GEdFfYffmk`2gv)i``PZ+3Fys3es5K~>a$@3X zNJnH$%h$erb?uufHT-vpZOkG8*8E9ND3_`YWKAkXTve)`nY<#R-^CvKG6*K_$3OT- zh*B!J@v!UEq+;CO$(T~fGiK!kUK}^x`vUmiG+z*nF0g4^=j9hYc$hUz3w{y+h>gLk zAhTFYxqJFdUc4~Nl~)n6R{r3h;Uzc{3y&w;igT9tPwm8y*%==K{N9hW}Vh{m|9x!_hBU(e#*b;t?sqy(<^d=XI; zFt9Gra_OQZSdcttEpwslzSKXJ3Sc85mJigcfX+9+_ix)27&rd@8rpooI|=`2_-m0d(fyMn&yeSKZ&q)2x`bz( zP5t>($uA}W?)4RV^2I3JI5qk*md$mwqq|JaqLo~yLTqVvJmnSSEiLUOfA>_pYnNB( zT;2s`*;0Q)_9x{}L|{t(_Dn_2D9FkNLL@k)MyKY$^$mJ5RC5aqE!j>W`DJWx*6K9+ zxw9_E{Lh~Y&YpL5Q&uKM72n#D*tKR~G-{;!ozKl#=vm2_^w*2@Y-4nigt*iT{Up#K@#$4R}Vp#18a?))8gS z4D+BM(EcdnsTrUbi3AF@zLL25n3yXXT2e6Ad}W+|C!AhAm*dJW}xA`(sj z-0V;LuOF`Qui_=h<1fMM|Nio?_RoKF`R~8<-*^5uU;4k4I+wN2@#z=+!PtG_;c2w7 z*FnHqRu5FR`%h*SrUM<=hPGcp{<8#S(e{;WJvocC$Ig3Z$fpCuSk?V0Z?K01Y?bcvv;RzzXq=14qyN&J{xy#O zmpM5}5qqXaM;i>)o{ZKn3nco)P`7G1<$4eC% z_HwS``h&Zv!uBJ*)D)t~=R?<7oN7EX6x`i~uhhC@moAlLFoqXm(drTghrXFUQfd;6 z?37{37u}BZJI4}0%Manm+pc^eeK)GtqT$s;W$9@hCGJFVt9!j>Wv5#q(kA1-O?_6C z44ZY7Ai)sm72ucyjb2DFW=_LpEBR<5D5B)IB|rj^u}pz~HB8R<1a1WR(zWQIp9m)U z+CShTg(zP;q`ke}<7hUd`s@IeS6oc^t)L)+J;UP@n5QqDY{FA6R6tTh;%Fv7Lqnr) zc(`pb(Xcl|(i>EuqoYYb-J2=PJmZXtigIyt+gXTH`_f~knEhtbXSc_MKN)I=*qj2u zJ?$*eZFms>vZu-xbpA{152<@(ASSDws}~b=Up$CgpQ=qX&+rTeznGt&Uj@byCdUGl zB$DB9sS_No`e4FZyWZ;w(Cm>o+ZzNwbnViUmH=&#RR?b1erQwxCi4ZbOb|@|Xjz&W!Qyes-qS(ykP ziWHZSKy!daBge)dva+(bZ(Rq|rB&<3MNLgTs4hmssrB?hoY8D^5Kx?s-`unVvNg|i zb?F!w7$T#i`9(xLCbxVf`YpazPJ2bf#!`T(1xxcCEVmp>6WF(*ZN^}Uue9aSDkX4! z&&e_KdfB6<0dX2oLf9__ zx)zrkYH(13bjLRnhi%9N1a4UUfsPLvFf%|N6fFQf-z}w2gVwuk=q&Z7N0cXYao0uy zX`KJe+n|u#!k@Acejw{&Wo@ku_YnmmEvG=>Iv0o?DL-hLnYs7&?OOo;v&1&KPQ~b* zu@K7w`5|Dc#AIY@(o)IFAYm>UahhrT$jT@T)*YM%Y7*P{V4C+14t`q>g1j67Bu$Kf zI7#cgBXAO6CV+SfznIux-~hS+J6BRta>1#ZRlcIA9CR%J5uYYt8831N!5=KKp{jRp zQ;3FCqt6d28;b16V+S84cJT=bweKu;g~|UEeDb8!6$756r`tZ)76GJa%*TG45&qIo4RdZ>Xm=L=XATd(}i>xMnwzoHrLZR|tum>~| zrC`Jf-1?xjmpYxG#d-Oy<8___Jat>wbSv%d$90yNbW#qi3WDs89(Rb%&B+P25$XaW zM!Eh7lzl_bbiKEB$@{CvJ{czbib_gEAVufpZ5+r}(gwOrOg>vzc^Xdn!Cq!fR~?+3 zECj-Dq6)OS`9Ye`7wV{kFUibW1~A~Wcw{sm-p)zj|c*e;!gh$jJpt#Das&h5mc^Xz;k2}DIiJt%bf-PrRhe?kG z+lQXTNj2^bc)+o0_QhD7Ntre|xi@qPqE>(k;?8DBU0pgOr4HHz*~N(mgZ?(%ndR!w?hS+}_Xg zzQ=bQ-@otg^8=X81=n1&_uA*V&ULOGrKO>Wk3)%rf`WpttR%04f`ZYBf`VFug@OEy zEfbm`^2ZYo9YtA`sxj&V^`04m*+b6TGN^FaZ7coVWy$sV~Fh6A6hS;F=xU*RTI~yZ_DI z|A6xUnt}iAivLBF{~zHKZRTT#>A!%wmD&fNk{+{>{2kV6Vx!S^N_=cPULv{VlKD^M zUDW(<_#P6BG*3WxJyv`9Tz~`*gN2$PJ6JkSGB>W?h+A;fdK&K-1>G`?TJ7Z>g?vpA=vr_JkDeorcfO?JB<-*gPl$E|z1C)kMGV{7`TjDs>jIlF1Nd;9bIJ^U-Ve0Z;k z=6K0N^$a@9(v2#uZ($civbQ45xaU9q%~FryH|t(abpOd<^!6zCngmh-wxd<~3VYSY8*e#_PEvA28GE=2r<&t~N(NnA?+ zvFt7Be-T(0q@eSn{0@lS8s5K<c zvE;04H=7@UKRtW+J_WMf^^h)EF7(jI3fR0PV*23SmD<`MiTZCU){OtN25Q3m??hE? zpm7k%KB1NjPC=0OaDX>(FmA_2>BgLL-7cEB!vr*lw&G|)(EvP-02l}cZ{*AyB~Kai z!y`FUxNu4dY6jwN9g;rf1@qw9Sr@1pOKJbHfV-(4I59IVl7g zg)Wp`W6qK_j;(>;tV%LuWD87EuwhY^aD^pwZ{TddkpBzBTU<#<8uZPAChOm~c6c56 zGtW(yLo}5h?XB}sm@ePK`b!>^;0Oe{@q)O_5Ixv=9elGzxU~-veYpbaHK)_WWs5aU;22igXUZ_N{z&)R$80WkkiKdYtMP}!RO&)&jqyC)s__fri$8RRW+efr~{ z&x5%IwKyW&6NTZ`dUTCqJJRYm{~_GEHO(P7mh3hTqC8#L0apLv9aK2(Z%6g!5#fv& z0W|VCOUSd~^^*4Ri8?XH<(kV5$+;F^{P=eUAH)Bw`TU>tx@90b6+@Ll4bum8zlb40 z>0Z6}7@+H1#~&a>BN*c$dYwbqmXPo!;|tvJ4c`T`Y)ouVE3`Kru-+B!aTJrAInMvrL*y~S zp9Ham9g>*=k05*AS5(d7-g|U+=(sSk?k7DEL8b2-*qx5mP2stFE}XKFl{j1vBU^(l z_+w{ey-wRf&F439(y6Vghw%SeUrTOC`b6Wl8@a$ zi?dtsel=jM0K0R8U<>LGY+W5=%2f?Bi1y;1Z5jY7$WG)SylLp35lm3}papY4 z=jiJknAI}J(d;DXE5gKCQ5@>V*a?4cLb4#cfsX3UhUGEPB15!$j3ut*@d*|nkLZLa(xT(I zn?AM?@3FAD{M=AHj{HvZ01fj93%-pCe~|DiGV9k6FD(j_)}yxjt&7L*P7la!hrrP( z>Va?|te=<6seX@H{-?&_9!^1+gV?)Qu&gD0*-d#eF>0)jT zZV0bhJXSDyj5!eo5<&_?W<9Hu|7Ms)LdO%Q>t7cCKJz1iXyge-?UP$r$jgl|y+oxC z>XAEWdN2%Nj^z2^7REe3(HdZa0C0rg35md5@V=EKNSZ9_xQ5wnF4SFx0rM2q-eI*v zeRqsT+FHNbhaAqFSmN_nkF_7*x8=S5eYHpu5Ny^u22_H2hQ*?v`3=%`V9nw*67@;T zFF$#j`C*J@#X~=cFx;r)s=RG%tk~{p{93D(S!>7n`N3hY>ur|{Sk!H287Dr?d+#Fu z@dV>y^Fe`f45bMfoE^VX>njLtnQnU~VJZz8pnJa9mN+Ght;zBX-rwxg;ea4w=d`4NTeK#&CW=&#-+H z72|I6h=o9dvzoz{a8+JCRkXdi@Posaqmxzv`%h+Re#U2A#ak=w@6+|hb%X>~-z~5G zT<$sR6{1_ERcrTKG&J#FjvQT~fkXYAHYT?~8*AnYCT$uUJ9F4q4w2$A6#Im#LmHua zzx5RV6RLYVemN2T%S}EEx`vJrF#^}Y;h%7pZG~DJ&q|(ughK~h2vvjqhEM+|}uqN9=_+ zOP`v~gl5|7849L|4ol1&9SoRHyRN3{u2WY`I&ud;uu^W*UpNHRU29Q_VoUIVB zF0UzIZd7I7EDTlBrT;^J1n{B>K^7Bp4_mGwd|goeu~<~r$Mw+Uy(C0+#)XNeN4C&2Xh|7vy}G#)V(8vx)K-L^EAv8 z1Vx>NyE?BI*F6iJT6RQf2mIzcaQxhV@a-gi>=;<)8D|Rfw6i=)iZIqPN*XWTt`s#- zbP3uszMLAV9-4C3hF<{SY?t{U2&DarB2KxDCdIF?rSUeM)PX%JSok*!xK|VF zz3hxnrhFF&2swJwTvo3n(BgBd*|yy-m+49XfY3_}fSK`i;{;0R2JQfMw?&SY<3hl* zS_<1(NACQ0yD+@bOM=oZb!$rmuAb|A*a&!TL5@4^jr~;YF)?l%!x|RjM-|oM3S-+J11b( zgc`MC5FMXaZaO02_ndYQ|I|D_UhQXc*{?MNgx`{LW(&je)ZJf>FKGMf~g;WrD9O_QhD=3fRUrk zgK?!xP%BSG-4TE`Y@PS^=Nqc9?#^tUN#5rkN0Hj}3bdH@VvUr4p;K#afN-*Z{1-an z78b8*F?!gW)?N5s;-UgzPkH{yFg!6-GvQPVO5eA79xez^E!X=oG49u6VllqZvAv1_ ztg%I5`aI2u-SU|d66x(n@V!VOq|~B4H4#HaoKvN=nuvL;!MoQH;9>tWFw;SR4EOXQ z@s&xr)jb3OU;hPw2EjFTc=TC_qwU3b%}6i}pVmw+aB1+qQSWa|i(8Z%!3n93t2cJS z{@eijTp#OcG<71xLLIFnl$PLE$Z)c@^ga^(C;?rLane@lq>YmFr~UG*S1e=Gk|+Lp z5|I?TtcVpOnz4*D0eY{4EDzR3!W)z)Z(eR=*BNndKc6Q->&TPzF(4)cFVmZJJWzZb zgMlzw&X{5M{*?5DZSPJ`emIbM6+VR0fdMuXb2;ZDl~kVt!3mCqKELYljh-80{w1V~ zyvJkNd6<7m#SrZPZ@W8c=@`MI#@#klj3JH0RvZB5K9A_{T&EqtAC~aApTkJkTVL4!{trpbFpCM3|70rE{5-uO>N) zF!7pz%rwgLjYUs~%%MA)#X4mwT$FVJeVa0wSsY4V`B=;QYggJqsvNVeyMxmP9~W9J z(*TLC%r7Gd!VOGq>S0O_z>#$v;hPXCWXkkykfeBOj3;&`+L?y!U6_`hFyOn2|8l3#Hs{MzV_ko@do8ZTr)dhdPwt_4V`CI-^&u$b<|HF6_b1e1UR|J$ zCnlm6I0zVsXe`{+g=l`UrN(*Lh0w$V^ssddnLa}(?`t|3h>UmumJ@B#2b@#sc$9Eu zS;zAm*;g$oyEWRl6Kj;XC{qGhd3ZZ~%+>-S+~QuFHAP8w;sM+B%vTXYcxdJ{2le(M zufetL96?ZXggpEn@VLIcTiHe&-6!;_Xln-@!_LpxbD~n+^Lvof%>ut?Wn=x4dXxf_ zfP@62OXo#2^pZD_i`S%+ixas`D%T(MFD1cOXI9Q$8pxGmK5M^Xxt|jSv!wHYUjh*K zyxaNk=^&nLu}z=*-zqYGoNPVCi{Nh+nJ|bFns`Kk=P0p7W+@(= zD*4&`)B7NUCc-T`^8O2JF+}g(Dh~W^r4!&1FK7^uU{DPWJ+zk=k+6w322=H8li?+0 zd%b(TY)$|2L{E`&^z*6r_U~VE?(k!N@sB#07He)#nK2Jlc3YKz{eh&dx3CqjA z)El*CPr;ghYnrDc;6ZmmLv)CXd{sW`c`2WhwsN}`?p@YC-7sLiH>@rg=7sB@G|sYf zchT#<*~c&LdD(2z8KBK$D#6>rkF})ZzV$G^jktvdHcfm@noJQpLgGrEZwMs`;V>3;cV7Qi>I8P zUfT9R<>Ms`0Ds#Ogs94qdd1?>4$lg>o)q2Q&fIIbl)E%WZ07$$90kG6KLCGz_nkO; zeiYLnoafqCWzIRhBz{?CtlN>Q@AUh61z9M>x2=g5BA{*Oj}+TM83K530r4YVvkYU% z{nx&H^Tk228h|hY63I$d^0VQEGGG##&^$hBy#7nJ@>sl1PfowoYigAUPktN{1Q8l76Jda?~0_S^Bkxh>ke za69tm4t%^pRp)Ft!;i!)2rOo;I1x%79h&)yeSg?yp5(m-ddJGD!1DaF-djb>sEkuZ z7Rp#v=Cql+pH+I(J)gf}$BHrvLY$GwBLa~Oz0XHzZ4HksEQB>6REjN)i<+A2KTJOp zp;RxMr}U#i|L}pCH#|TuPtsqf^S;t$=u0}UD(Hj!^uAK1kuHEgidC^l+c-5J0kv^I z+VvEd5@#jj%}dt>s!VIB)S0D$;gk6zXRx)i;mKabott^HR3=4MVXpdL^2EO?`liJ@ zYJR@ToKrF84t-`PoPD_mxC@5vD+aNX@#duMjpwFcM9C#7#s2`;Lr*jjy6_V)46r?x zi&JWYEGHP6?rux}x35wQ@VRVS z|MNG!4+Zz*zkF=cu-ysMS%_CC^g0fEH-z|lNP&|X_3 zSAvO*x1(TQTRvW&g*IN5nKF?MwqHF1ZCL3H)U@6s{SZ(=PX~epwwy!7#f8Kfm}K_gRzp6&GnoFaQa774yICtQ3#6c;Nwu|?hrQW>=Z^101YHd3yxiWd zFF_8t1M1#|I%@PJHZ#99g;zZGAmgKJM9Sy!RFiitHd@iofjm4NEzzc zQ+~u89oypLM$DDt-pGkt3JGpo_I7)+ zN7x)JOEwlradr&zqIwdh~ zt)CQc>Qsn&Vuo7r%_jD*;i-z1R?p=yxx)7(#CU_uCD_bK>>e(94y?9wbcUuG={haU zH-6J$=IXJCaMisJj*jv@7a8^CMD^%GPWV*&O67(PwP?cQ!nW_ewpAb)I$ph>{Eqf5 z3o~luaMP*9cZcO`!LtasuJc^ z>o?Osl*@GI{1r{6TH4WM?GC)M?2QgZ*^PV*P4m+A3fVn8RCOxtKp{_j`L149fk1C| z_sDkEU=%HWCndjskEuvyrhJref-r{3te9S$zME+7rMS>Y&f{GG>dW}jLHzvEs(WEW zevl}cy=PuW_uhBC;$S%67|l2zR!>f_0(m1*H1KGin8}|6Asza!8r?BA;3BY$`Lrio7g8&v9O0c)ya^H)(K!_t62?~NY zTZnwIS@%LrD?~8C1Sic!tp@%AI62+sd!e;M( zH$tpg!dw9P>|Dn>f;-Kcg6q&XY4E##s&+AlIf){wc#zp5gm<(s?WZ=cs+;HJX4ivh z3pBD%m>b(~T1>WFjpW_iX9oo)S%#J6&TZT~DvMzjqY8?rYb`9`D@laLE7&#J<>d(P zuOpXs)_qYbrTRADpB4W=c)7p)YpmxV2Abg1k6lu8vOb7H-AH5)TtC}I_8o9B2AwCy zoPw_;BjGaAh@ZGuVxgY!>xb#{Ey&)~#d2l(S!j=fXPy4yn8zja&U#rR@FxZzch;_^ z1Z&a3cV(9Mm#b$1FACfp`MjMmxtct$ZeeW$W!|45xFvh2AugSJk5+m!QjPcY|K zKA{Go_b1V>kIJ>H?OTanM)hs7M-6PUUfcf&6rxSnV&-X3QQ!O(aw=!>F4@{iW@$97 z_{t_jVoDR;}sc&;~%N$IUUsU9;D6tfnrQMabM(whM?SwgWDl2}l zt1!}Px0Upf7?G7}V=D+|nfGD;A*(t{Vr$1$sC3rOmr*)?N_6|CXxT8eJRf0Fa<-l< z7s0x7o%xnhvHS9(8a@k74Z74sgmZC|-I$fUadHSSg2=2~2?@oax=w@wji*8Fr+Fg& zWn(K1fR~yu2>Kr8Eewu~j;op?oNZqQ=`izb_%u+E@)=Z?pY3Jut3?{u&mym~!>C^~ zCVp?fT`Ir45Pg;QC7nmPOebv|@Tdm5{Ix!O<1qih+D}hUFa2gLyxQd-MpPSNfZ(?J zw|E|Ey~ZuJSeXgYU@Bjyi$PX=Ptxizd1#SB13Xy75f6u-)>%n73mmaD}I}rdXM$q6@T7dIF^$+d{T}$&PpgQ>9^*3;;iLl3Epq3 ztE91bmDgK5FVc&eTR9ewzZc6}>(wxY_Q7UZxzFZ|wf=zOrfnoI0(O6CR zd)i@DOQVFHLmI<^iV|PaY`rj#(zXzQ=#`8G3xjR+z^M7l?^Xosoz%E{j@o3BFGhAxS4;;#V5zNYRCTaT+Bdbk@80%*34 zJzh1!?qvdaG>UdK2~S9tBS24A*Mt|Hm6^FNH*wi^%FjBvA_!wughJhutrVPo^g5UFcuYe+fIu3=7a1{e>M9a%Yl59^)n&@L5{H$A@?K!e zV4?rfdsi3cudYRTlZ9OvXT^1l4q88s8LZw z?FaHxPv7x{7wT1ELxpH7!bx%LJ6MVgtBs)}sw0=BLAR*)>!3#jTRsRRCmUR2JGyXy zYr9sN+f@Lw4eWL%`c5}rBGO7QM7B8guvB&Ar| z+U7-b2WC&vwB0Z3x}@>F(QWq@Pj%L0elQ>Tf;uxXslE`U@YdYMC1LG71cqv`a3}OesKhslXQHePZA0GbT;^j47NLiDk4-M%~2@QU&logwnqRP_7789qrBor3w z*IVCM0DBQv>a^73Rmai&$?VaK@KgH_rz5A#1f?x(GzsE;AxB(%VOwiYN$!rpa29g) zY|?jF?#vBu0|k6A>*~5`-{bgob6#ig z`ndCkW)tE*u8~mGaZ*%f{Rxctnr(tk27qdO%|D^&7Kl4veKDvif+5^*#5hjP-;vpV zl?vHL+)@Q;u00-NCPlKT9pRFpN}#8@8=kJTa08$tbi)wD24p803@hW};aboa{|6_& zKaO{^|1!eMlnX-ICrxMdKUU`O>BYG#K%$~UXp%PT@c^0)j8u#GK*Zb$VJN^X%+0O& zeZ=~@!X4~pu!GEimkzc=we7MX;X`S)`qIU}_%#2Gh=br-Cbkk5{2GM`u(luXy+%aq z%x!D%v6UF_<97d-(w$0CvxL2TNvk8nRFyBpIE^gX>Z($Sd|#(7-6zou-)|)gNW5Yh zwN^~ZY^SA5(&A#9vK!i5i7A;(O1!|v4%3-(PEoHxKVil0Lzc;jehpl|bX8=v)jY_% zO@b*){@C%Ohxi$!y1OY0E~hm=;G!{3;fJwAAE5gindIKq)*rqgdF9F1P>{w%{ly_m z*=~L$OT*C8t>OY5|78c^K>KxZtQ~$w8JbhHoH|qLFBSTn7k0BnX2z)sg^a0}(e+uL zQMR|c)~6#j`EXeUMTMQdvgxEzP5TuJstgxfT0I85nRfkheD)aH#GX6tMEXmLsk<*a zyssuIm81kqtZ;^>Hc_!ZW+$nX&_A1SFEh^;;ire3naw&WDk!jSFQpz`@*;M?iR(!5 zCwW%qO^?i(SzP^bK$U5z*y;YywNn3Td{ZpE`R;(OMY~uaoty8d)!V%7SGPio+DASyu`;NRvUHnnWiy95a}k^kU?jsxD8&&*nqxlXhsw~A zv!z@*yuSwr4Cs$f)P{JaE=MTL4Gl$R%6_#Nu(Ru?>r7HGD2)nlwpbyXRvN+Xd58tL zWM=|l5f$X<=`y zdOzR|T?lau0xgutFG~KJEjLm{;8~iy+P11oCo^5pR-o@qgFaGz5+t5~91K0cq-5M! z&EHg3W|>YJA!ANdQ*JP-d$O;_%FXb${!pcDdder%k4`14k?gaDact}EljK{wLm4$U zy{1QPp(iqgCGe~IdU~NFSqD`K9iGZz=y4!>6_@Q@mO3t0Wrdbli5u{+xACKq71dt! zfN-F#oo9z<_lACJRvK+Y55x2Zj)IUH3Ww!)EZYd+utH_NmJ*|OA1*hqtxZFbu1Q+z zj@6?UwUGspP?^5!diEwiYp%xYtkK3|^K!l7s+$D0V&TPvzV}4Wt?Sh?)`%dhRiC@B zqk$yD=popZ;{~(eH!(T3Mh1#%w}3+C$9dXo(^GbFz5{XlN@al5l~CvFAKL%#~~8z?~P)JgQo!F4vQt03TU)XZ87l)K1|QH);q3uZ=%Gu`CN!`l zD4%s?GB=U3&f4aBW`q5df2t8p^nW~69|)%aueUJl_+D?(<+#1Y zkTnQ@k5x5C@_`{HJ8l9X3PA8 zG}2u)`jp?>jxcW9x5D->&X9a^wkylbDT+lWE4FBWQul4TGcKJ;lbX^CEJdf-Y8AI% zc=dIbKO^y-BWgtSQF?0Q(!L$6diO?hGUR%_F{;cOARJ|D2r*_ZSr#J@Qc~Ueq5687 z&{jI^+k}{E<~go!$VTO~o$+FA%d=mk3Js3@o>yqTnK5hSilx_P(j{dPYFM8e#=rM#I7m`E`hjXt!S~S8pT)oy&a)Qbrs?o z{X7@7i#^Tq&AIe!wT_*TKh;uBeF4q$iJi9uYr$2c5_XT2^dEbh9?g2P(O|*&0@A#R zil+6e>Pe|Oyw*6{h}cbE9~zg@W2-#o{OoYI(}hhxMFhq?*@GM(Qs~R(d4}PS zV@NFT(GB@P3|W%5TXq;eZy)bgR|*nPPsf^rnG_Kh&cPq&Rom7_X&}p?H^gu z@CH;-lcUg2l4y(>_XK7?t!E7wSm@dxTLbP@c}EuCMp!ZDPx+J0ovW%8P9_zHzbVt@ zApRonWG@$~OCNx9*nuNk2g--sYAwq`QR z?5roGB@~W_9r&S>k(~4=3fg+cK6lI)bD7**Bjiza2zkk2&&Y08e3JY3wUd1PaU(%7I7v zo7Or!z_Q(BzSiU)AKBAK+>hp*?)!OPrK&WP@H!Z>?~fQ#doUdJ>bZ~|mOCt&PvB(d zCS21| zkrV^cYs<{@Q|vUtFlvCfL_C~fp#U2sRGslqjSHMfLbjfxma@$K%xA@w=gQpMts@g!&#nS}|VW3bSS-Pa*g% zW6|M`XWV&G6|ovQ?h+AbBhqs(Lx=a2XCC5VbPaz+-B_b&PJjUu3tP6&ci=@Dg?)Fs zQJZwwM>_l=AB~fvekrr>tD5S%pm_n0q|pdpOC`8@4DI96?kbxZWHj*x)il%p(0*olYpCU2ZTNO`e0v^Io$R9@m!_e@#H?RzAvSf-;_`j(|F|j(&5w1wV{eZdT^T^ zbm76k8dG%qR9i}Pc{=t!yn7;!lFJD=y-?O)wv~K&iOgs{S8O{oQF4AKB39N9!Cc(j zN^K^s1*rtQMp=){1>W^hTL~}kS zL(a5oa7};NGnIEEOLp_KLPg&m4P5X-cpXQIzoqfp%1RfZkJj>)sKr>czDcz1;JWdf z^>=>luev3IDb*$vWS~k%=_UgE7FO@fG4&}3udzH|gKB5+!Af2Cb4l@zu0L-zFi<3R z*ke35q3l*?$7Z2#JF-yQ;%li40KIHUa0 zC+pWG+5gsa(>yK1^ixV!3S)0{61t(eoa*2)Cgn6Y5( zUZ?oS{(Fq$eBMnVs`aNSwEJ~vP{Gpy?82N5K*h3m^Onq0_B+V(eXqnLoDVh#uW!sA zox(UO29w+y@s3q)J4l;Q!(Br+(R=R}HSvt~mrds?^9p68?D86!2r-`pb?lp#>5td+ z&ds)fPo+emKsrjKJ=++ogU`u~ej=^915pxiH_Q90PhJM+K4!+=Dzh_4f7iOy>hPQa ziHJIXPTj(+lScJ;ix|a%v8dv#)xHI!2wD!3M>7)X*Mn3K7c zbf-sl2bi;l{X;68-wkutA$y|CxuZ&AuYO#73%GNoo_=GAD?>iKTz4cSoEujfHQS>b zd1d6ypj@Iu+*cph9l0c0T+B+{&!ujNAJGl5Doahfp&(7Qtt}YDF4IffAp{`+!XN#kVOx4CTsl7hUe8v5gZLROl6<%V~ng_cZ_P6>O%Bcsu!S3(%J?VhNuqJ1ot zn#R(5YkBj#v=~dn(!jPeyA9NBW|*DF)<`Jii5QCmCNiEw|S+w9Sj zHT}cJe*R;iYrB4mycSNQrEI`+WUUE)#6-OAyoin8UikSw#5Y$?TS|?eN?_*OO)$8X zalXnt{VWJU_&Wf8uy?yd@HhD7u=$5BQ~u*`q{S6=Md^Ot7<%lAw}ob)kv!ZY3FbTB zqpRuScLkxW%u~&{I`i?E+5oWj2G3li!SSJAAjI{hjl&WuHKs^`aC+PFcS3|#*q@n_=rR*5m`ndi zQg+%3k~Rp(skj*uM-{!Yv7E9MQg`4;n`#$1nsS~|n^xf#?ntYs;xSsIp9vnInv>;B z)mMMSDKX(tZqY$Hol0+X`M%B%-SK0~UuIR6tQe)t78_zmFcQbJAvG_%HGy5$5aB-h z3DtvFYU-%Z8}^N=h~g3>UKnPylzEz@YD)v6ey1$S@s;{k@@D31;aSDl!hd1}z3F*| zMGnOLV`|J%Y$)wro}|(5*!s(_k^w)UehnL`Wmh2Ax>ToHw0P}s_zZd)l$a0S-Xm_h z8F+fw@1T0LN(j4s5P~e_z#)&Pga~HHd}+UeFYRp};AI@Jw`venF|vwwGi^RtHHI3V9msLLrul*l58ulPx4Qmx&y z8J`~rLh~xrTh~v>@Pk5f7 z#t>R?@^UMj{+6NHozftKU;w+8j~pck*29H)`-n+pLTMo_Dmt;T>Fw1;2kyleyW8@* z+oIU+G!1dTwVp{yB4Q`qWQr6bi7r5y;Eyf)WH7k)neYrAtq^CVSuoC`sAY#*dzj#{S3`SYHh2uRy>Oj~8ybZhBAj;8EVDyp77!x}u# zsZ{L{;8ex+C^1YQi?_Q^&a#%vN_{bEqqzAi2AlNANJK4@JWd8x?PzEi|B1djNu7e_ zQJCj4jk?@&M3#t<4w9c(YiVlVBjCwFj0k8xOx4iP>_&hbPYHL+Kg)aOr?JcE7yNfi zoMDv5-3DUNt(Z;Pj$<0Pgtts{W0fa2L{8&`Kv_ z;h)n^In%z0{nXlHDL5@oh<0 zADK4!!s}9Uqx0rszo-0XyEqfR6|*(APH%>1qrF5%bSmd6wj%FK$kIt0rj?vzkox~q zLjN^MLb^j_199a`YY-hq&r7^4iSCs3t~KliM~m6L_3*(?^BOeNIsZ&W@(F;&2Kjbe zV0xP5tqbxz!_l7}$K80T;euAL8XgGmvfHVMJ(c9BMq|e+*Sz1(ClNAtphJKisD_jT zL-nUM*(T1pswVHbZVIrWW0lcjK7Q*?HCyvgZL!!mY@z2+skOL7gs3g{VHo-*?hK zfUGAoi}q03JYSk7)g#x=AT%+?hivUdI`BNep9pg_c{- zA_Y@_Df4BeI+t@5r=oKPO$_iAyqFXDN-H1UV6U7;M&|f1petcD0)hxEgTk19Rbn%SfE&1xIPk0Rl~-Z|(G-5Y!k!3VRM&e zJ3kvAEy;`jmgXxn?l~P6c2Y9%wwx)WBzwQ|8EK+CM>UY)?kSO6|!St=vU z(X>XEBHK(9%!aR;er z^p)LO^(`Z2&y+@iJhDAFs@O{rZAluiO(+||s>BfN>e}wBQb1A+zrANOZ@d1uj z1Ma60topCozU86>4kZU-4iE}tRy?l{jXoeiO6m<)dNocUX5JRZwcT_A2*&FP?Pz<< z=iWLW{aoe3MaUkc=D6pnUUdqTJ77LD4*|k$KZ;$j=ygo;bss=ia(?sj46htl{2m=e zdN)!n}rb~ku*uKQ=STdR3jh3-ld)RY z3?kCUP&9M6>k)rUK3n&WN9pt;L8D}R)iGw`$@lV7L%`!#Y3IJ=nOx3Cz0HNQn;p#l z#?7w%P6TZ@VT^j*Q{0BL#;+&LB9#_A`E?ED!#lN|=DbSf@6wTlNz(kfk233k;!P)A z5(!(}$i^kSFoXJu(KOg8XtLb`n)3+sw{+Bi z&{?>fa?v1*ZI%vEz`Oc{38O=$(su$f$-k7Y$z_|V=BrgI^^$rc2pt}L1M}WAXh@Xg zqMv+UJn*kI;u^u_4Kj?Q0dN8X+bb)$GKknx$5aFolavJ5O>J}EMeCTD@&oY(#9vp& zc~(h?-26ElPO=;On)ekpV{iGHN$uTSl1j1T9#&8H2aZxJWfcy=ZzUE-S;|CKt{CH8 zSs#};DP7+7{ER^hA#!b~9}F^giAxpjao;zf+pF>I?(2#);VLKA<5-w2ZSPmJ_1EuZDB6X0gcMXU zt>%#(>Donyv!{SVG<=~CrSs$GwN`G912vFHwhjPZ_LxioxS}o4Wwol6Hsx%PovP

ogT*U>v6bzCn91!Js)v0?)X)+7SL57&y$|aq!>SZ zFkQNX_dB!B-PT@3U@^w)~hi?;rg)j(R2e7&M=; zeF{NpD8|==&;jIm%%gGuN3*+|1s$*keQfQISr3f&5hRJ2>+oswp&45prk=grD{i)VD1zbAG^SO+-QNPyob(fViU%e!3aBy(#H;2!-^HHD~b5YZ301pe& zo0>Rp9we71329#edz-^|z<1of=NrM$!)lOm=gq}DORn;Pr049Cs}uo#&G*0|lk)i@ zT@K~))r6Y0-k)ibLJi*Qqu?qSezBEnUl~_M$6AA+#`gbyd06 zckJBbSS8|pOx9Lb%A|XHo^6)z(cf=v8PU3kWFgy1{M_@y!{4NugN$q1dnQT9KDZxd zw7!=vw=2`55_t8h*a}yvp_T(Us>qcm#6W?O%5TMRNKrS5rpAdQIKwq^d6|?FJt9I* zLlDkFjK4e+ard3fmyRksrDy2-Og4?N9A`G?(Ec3*wgP`Recoios=~-j|MNKV(5WsxlsJEYUB@h&?~`7b{TftB2^)i&+)vDzV4Q>t6q83whOUM?8?G?-}1AvB&sdm z(UiP(bO>x(qN#kWANZ<`*=rx)(3U_a#8v;PafWk(*+G?2_$x?Y>Ibjg!w9Lq)>fsy zeJvl@*6oGY9?Iz*5=}`P8zhIZTnRS)fIUPY89jU zr~rl`R%ZM%EKqYlLgEv}E=V$l?z{-H1Dv8@jg`4L)?ND?>%AbcqAKMqeH%d~@;f=N z@aFXjk0uX3bsMOS7Hsz5u zuB~h~m-&bAlSFpElYD<$n#)?BZ29x$moHyxYd*!TBzbAvWAg8XJ%;v+tOHppdPeyCy!KS7c+0 zsOf78Vqmz~XJmtvkYm}D@HFT6jnCMxI=r>Y6UqtI=OKh02I_5?M*0UIk-V~EQkWxx zP+jR&enRqK>Gn>#d0OG1=J0i>;r+=v{Qu$TEZCy#wlJ*pNJ{sBAm~Ro(gRA)kV*{Q z4Bbdeqm&@sAdUm2k2-OmKW3=WM|)l$^>;p$9EGqx zCShK`{-HS3u+1UQ7(ae}{eh@Ekgru56{Y6Wy#=K|Hx{g%mN;*-i}>ped2QkGU-Ie^ zk{9sOpJ$w=*IPqTvXWO07c6N0Jvr@L&~WSP7^oIU-Lir7Q1}1 ziqN5Hgi_b8`}nYho^f(QIVeKe_U07LhmGyL`Xh@1;hYmqCvl_)EnTQpEuC|KeTlJE zIV1qrZNR$Lpi|sSC;UA8hRY|Q5Ua`WJE&U{;&nh6ZNXi<3mL+ppD4AbjlU#tr<`C5 zOa>n0Mba!pHu%h|vsCA3X4kgM@%sXH1Nsj=`U7qEX@BYBEYZ6D`gI$*WsP1^-*Y+Q(Lj3Yw=J%??#(rEb3_X51%xf!As?sgd zI4+lIO+CGLvTX-7*y9HQ@fJl+i~w)*DCM!yBqkG!U$FKjkx>yhz1GX2)##|UTi84I zz3QKY4#ypVm|A2pJMk`9boKSFm){;X^`C;g{^CC=mwH_#xg__my!uHqpCc35Ut!$0 zIh-_g_Ha(N@zAghTgRr<+bLPVG<_y8C! z4>yolH%JS!`O6(3wAkk@`W3cMw-$GP9KPDNx?27jNFyl$czM^IgF_>-D=4Jpyh$q+ zk8G~|sYCt2R@ztVibz-szpGo+dfCQYEF+M4q|e8K<;}W}?bOo0x6EPD_Q;vVZX%hI z#1}nsvnqxBKaK}C^zNHI3XZ#kyh(Tp{0Tqo%h@1^WDHe7!g%=xqjfHV=?zE3+l?wh zrS8KP;mk3TZi*LZrmn8)TiaVRO0z3}i)Sjo>gVM}%KA8~4#pMzYH*rDqtsNgGINzC zBxHG0>=JKIWjsoh>fXLTpNR(eWAVq0{L040SH6G2 z58g?ssnu&(!y@y$Xf_YeZvBHN2G6o_AB_HMt3hl0c#o! zgvx(73z@X^1{E5WgPgfKuEv!pk!Mly!}-nBhB-Hx?g z%kT%8Fp}1A8+gb*PVk4^$y$h245QBq?GH|O7o>`M!p}wM!@`Ens`PcDZ+kx3tgeL2 zu28yA-Y&kbtgXT*jY8^$t-O0M()n^dCiAZUazej0%}Wm_ppC7m*#NsK;w<U540X7c}P5;QhtEQ;w3Z=~FPer2l+rW2G z+uPf@nyl_m{poZGV?zoYEpLw7{(idM!vy!=AGdInH9r)&rZdBahDZfx@EArppt5$2 zwwCBsbKY1z<=@#3tOwCAjl&KW*{=*&u~82tY`}V-m-~K4_T<}OIABVVCe(qaM|CuX z(^W97?}(hL@XthXN_|{DDqJg%K!P)zGx4k1rswwq8%ZdVZ?H-^ zM|kq^J4yEw83{phmVZefiOegtO2XjfL5EzXyy1VzkCLEfBXl^k5)hG4{L?Nv(L^75 zay`9A>x);vqQslUe{nio+-n_^FI^6MSZ}S2sXx#(*_C!# zzl^@G{)*2%Zjy+j;%XFjjNG4hg#1~+yM@mXBhX~PWEhRpPeS9**F;3v8cnla*#dC@ zfe0iK4VkA%m5jo6xvC17cQ_a$Jk%&*C2yxc=KQ1XzPQaaiFYD>$Ax1
xjD;qr?HA2{m#$T)Yd3_K6ZjyS>8o+E`Z)7q zW2BL+;ty+4hXJNuqd0y#^a(L@dJT;Fk9!)`X{~Sb6*H#2EU6;U{_%e?cE0;k?#GXA zn`hVwC5pDc>T@=C5kD=STZdzjnDgs*>oOd9P|W@tgFbF)nJcG>L;?}cnui;QN1t-7 z75g;7^}b&C%x_VYeW;jj!{u;=L*mtYi+!!;@o5n^44Jmu;E1??8kM zvMV3#^#mull~*?YcYU-nqX?o6+CcmmA=|Lh2MCa3&($B-E1vqJY2J!VOiYZ0X{uhi z0gB{Xd$lP{82V6&Tzm{3g3r4VAL|5X1XpLpRm*p4Fi`L9&xQ8Wm9gVjTFuQdB)LST zna6%jw<(C@_>tSrF3R;}HvmKwqHi}G){`jDR5BH^ivlekb{msf3?y)D&-xwq9cItr zyYu7E<`^i6uHUhf6)P*10Nej9R*?Z+y(0>1n;#7td_F{+x!ut!tCLRjCm=Yq@=g~+ zz0-#abOkNpw6!4vDNLvV>(jQm=smM()B19u*Aa$N^7W&#>&65{$m-}ZfB%YIdf??B zDwAV@rd{*=k*UD|1CcHR4!4P_eXo7=Mn$$N_=mbq9Og-zLPv z3}z5>u<;*q`5WVF43u+$P#6t2tPH@rA#BEigma&3yfmBS_d)ym5POX`;o9z#Z$)y} z@2qEU0#x|u3qKWCa*F4hjyD3R0_q*Aa(yLV1t(u-JiZ#L5e^#4yJ2WRA#q=|wI(W! zG0}Lo{Oc(~IkVT~k%js=Y+VM>pY%wNnTLXa2rUb~B}(lMPN*hQ)P^04nJdUhFz;#) zk6ulx%P2f27Xw9(ygMKlEWcUw(FzxrDpr;iF%(mfGuu#0gj6VD@rc%0jshWMh?AJMm6At zu#vTW=@mJ++*D^HDul)5H)nU&OW!iI7B&a_dunFg!{Hu#SR$Mr!trPEOmQY6ECD!V ztkkgQhM&UrteBflK84T3~jSVQ0Y#7iUMp^7o0C zyISkbU5bAXhOem0D-=`VaAM15o~Ywe`|#>=R5uIH-BMR#UCQL1MVr59qZ^>YnSO#O6`&iE1}cq8B+hVj zJ7S>Pj{-&n{qI2?qHX-7Xj<$v3AJ^CVyg14Jv}*@9970;ES=M_)>_;){?4dFqr~7x%?soUTlJZN9GVswJGk zF1o7!*F2>Zi2LHcnSRbfpEe&Fe(g$hJSJQ?+FpWPUx*FtdlO0hPJ}6OlHhm@$g=1( zona^W*e_K(FCz0m<_G&v%I&;ObT(h#bB!2kP~u`K3t5uHn5kV~n$oE4=5pVqvW6#{ zk@EJ6-9PX&xF05OoKXNCfC4f6sruU`o|h=q9#u9>v|&~&oj~j!%1|<6E4OTB;`f`8 zwJ$PbeA{v*J%hj=-Cy@@T)e3}LVd5MvO9a+F_=_CMSUyZ6tUJCtFdkBVhUM3*5GX; zDU2QB|3DuooH$G1UpTo}1dB@?f7m)>NIq^BD_&PEjvtm7M}3aJ@n(ocfk_z@LjNGY zc;Pwj)9Ae&?>&rth_n`CzH=5Zgp0)U`sqZ|` zD>bEnaky^PnzN}Wo39%u-IBd6x4$~dgCS+`KKZg};X^ioWFCPZ z2(#tVgZHH~(S?X~4%gRYWxUJi$>xn}9WJ75LmiB%R7egh@rae{8QhL5f{gO>ov>(60$@%5EVWU z#-SHG#T+HaOZYu(du&iZ{HaK%*~W~y~-RoYu%xX>&@!{`+`Dk z(MsZvLA;#iuYU$mI{bAx#IavOo(LK~+?;dv;|yh%3)|EV{s>+Tf4aFJ;lv@b{hr}- zUhV#?`KIf(>l%FjuWb1J2Ho!redZT6veivBuLd1>O0qgzpW6KytvN4EqcsjJ>`U~(R zi&HsI;yE)?R~Axo>aNev7k~^VqI;{c;<&dmuUd&;1%5}xL)SN1UB9CNyiZff{um?} z$8@3o5`!F>owEqzOYF+jXG1WSP{CAw(m!s9cgByjho~Jl=hOHHza%Gp#OE8!+Z*1k zlf~XXK5uI?9C77@iabgpA-i_OW1NU*WXIBZ89q%T5A~0brz@&AQoaiq3%F8k;=Vfj zNrv`McU^c^)B%9stlz@w_%L%h%wSLw>L4JN9Dm(<7Vq_FWw-CdMvr}dp7#?l278qnxm-h;G{{v z{VKBov}9`|$-Y>|&pe(ngz5PCbj7_b~36 zAxVLkuZ)Xm45^mQ9KMU-tD*bV;P6*5UL=5SXJAvBF(+?fr+?6L zV$kRBlPFAqF?w{#!$7m?KjKJWkQM_|!SYj5IIqv%U1@SsuuQJAR=)@3sKxY?FcMp6 zr(-h!?|>5(7()LLap5X$YMOeTyqh7#n<#;Zh2K+C~qv+=Jx!c9(v95>Ud>gWJ zjR8*KR4{Pn2*9-`xrNz%jHECN8LWMRpN!(F->bIA2CzAF;-y0HmJB4J;BG5_oR-9K zSZ5a|4Qqk)ddIggoG`1=k)37*chzwp^C9jgubSeis8?{i`jTP4QNH)z5909T} zH5uG5zi(8r+=B?|S^Yi2U0O2_`LYik9la#af|^}3;j>942=inDNjyQI42lMMRyg|8 zTH8D;VIJ;m{|cCBK;^)FQ;nhFZ46yEa1>46(UW#I)zlJX5LtB4vHjc?coMmd^1Br9 zSc3FMVFL=ti;(9552CpIL-%z2=X2nEo>7~!@r=5bU~%6rN?*Z{)s?noEV7VQ>)`V# z@Tgs?@Pg0Xe)6T)_(?j0Ao4SI-~Qc>th`?RXLTSZr7n$4;fYxqs{z{y+BRg@FE=;i zPKu9v8+vIYTk3zzGIEp zyLW+ej(}(HI^imbouxY6IAU%;;kt2}#Nb>L#%!N*e$8C#&tiCC{|FUO;c(x%9)vP?``I(+jy>W8Ix!GN z*1j11Hi&zV?1lmo)^p}RnL{;s#lG@2 z^rBh08jc_fw%+L{##SdQe_SuqFm-WP9NaV=F`ue#v42IUGq^2X6Hbp1u;f3~FRU&y zFU&PmM?z&+0~IKl(X=}3B_2ayUl^Z5JFxatr|MNgG_@6)7}f3k=)%+OFX$!7?=9qX z&m-||R2Q!SYeKB0_&2pS^8JZK!hz}1z!MuuI-PG~=4+mr(Po&ji zND~x8mcef?nag}H%kB7gTDRMnh1UCMuJ0*&sXyX5E~E$c6($&V9(?q^?rYK$D!(kH zlT3FwF%b6#@E2jXl~!dx`)&-%NjZuM#li0GSb;ZO+)NGD(!#HmRq*zt#;Bm}sEb>4 z(wOq#pEoENmOFKJx(VWc&%yoRrwQ;-#D1MeVf3D2D=S>E#*5)pdLZ_4qXH5`>|Bvqi z4`lrT{l}T8&5nR~`@=+%{m;?edY1hKrp&1?PC3W_1S-r6`TZbzV~9;pcC~gC?u2#ob@m!1s~Wp27co^?_9p;8^CI<3x%Vox`s@7%5mc=t(C z))qclhbn zjYH7Xj`>nZ-hNVtSwxS7%ZgC`nAvpK(o6mUN3z~vkuJ)QxB8D`s&R>Zw%2&NV)lLA zprbP??yCYec}b;#6_UerAUB00@ z+ofQ0va!pNiXeuKm383j5A%(Ug(1SP+dtLela;U~K@I8imtz~qBeMMC{=G@mw{fID z)$Imvrd94g3&#C7@2-{H#u4Up{WHrYhg;d?=A~cYJVql}MCcO`d6TG#6 z@cU{(n{YG$_zjR5!L!DSl|gb}Usw7s*zmq2^5U~1K_&!yd(rkzhfKzw4f+QolE;ZI zZL2N|e6>?VOAtYH)}1$s+He<(Z-t+T)tHQ$(Iv|ZY-g0}-fqrl9frBQF1=)4{_bp} zTVFa)X-Zj_V7@_SY9U`-`STE&?Jk!XOoOID5QEXEsaE<5V7<365pFi{0TV*F@v9F= za|GbbCc)<52s;z9zQeC>*>R!SV zIc7nHY8vwV$toZG_maQgTeI29(RY>1E#S$iLue_r51G@47@NL%H71fMc{IGhbGCAS zJTxbM2Lx#j>o)%YJ@mCs^oEPh*YAAS08yo{UL;tw6yFJ}`41@urR3et45q=j2?LE+ zQkEzQ7Go;GFmKyM7Re+gPo9Vu=VSZF-ht5{V2T8{RZk^AS9RPU#?fk_A7I#O^Xtvr z?4BbktbTj(QO&J!$6yDQR$bIDA7-l!Lzo@5R&b3eOFHA!<%K z8~)42I?GviH9PmdOIbkasC9J&Z3^? zkzFY9g!S>opqY31Iezf2{-91s(nmLanH22NYxMkfa;a=U2JG`ekv64z;WOb| z5hs~T8sF(z?asu(hhHV2Qlrz*ZsV8U?B*8>R4PqHpbqY&YOy-(80c=5rwMe~NVQmf z8fljNiG1m6AK{(IRUq#8A4zsPV(bsuF+)*S9z>K%qh_D9^tAZc%7cUTb#*JAq?l0s zWasm0iis1fbxQ)bFuAd@<_QbKp)_J|bBOw06T)PhW@_xoL*B&6pBdbx112I_RFn(} zJ0vTTg2;c(ShGY8BO*)F=;IKVh9YSO)J+uzH4~cSDi7GHA`s|WL5?s@|=V7}vSrW&FBSs+e7Zat^tT>X$ z&O2K@hqY$#Tbw|!2UfOMqEJOq+YYLGvT}KVFDf%OMrVPdHVXX80Lv=Kkn#i6L2Dmj z3Q^YJg+cD^-^O!^_mfrE2_chtdCSJ1y6SPN`$~+O2*O>U=Qzp6<=6(^oDogxdNECP zwu`aBnqAgrck#SbAF!t;Yo9@A?)>_Nl3nw)csg{7wI=RfBr{R;64Q$Wavq(tWLVw9 zYh&Pxw$xaZ2ui=zi>mZxk0&=OUp=I9|J2^X&d z>$|58{C*cB)0i#3Kt44Xr{I#qrFQv|!2iHqC8gY4tI(`Ql6=hK0BpkI*A? zQMi(4rV04uQpFw3N+VegX#$o1{^DKr(O4hPy@`~%SH}hOkx2L~P|YLeP-LAW6uD5? zRExhP^Tw_Z#Y4dH5Sry=?7A`=Xk>|rtWN(0gOtD(y>@?YcEU|}zWfQRJw0`x3hk;6 zxfvWv8A}CDA2HylM-5J@ze)xOTVvxOKXi`zu{9Q_B_7@pUL+ZP7m9sEp9jjkwcXbz^BHy?1CukcG_vHZn z3_uk&G=CGzs7B#Ub3BM#s@sqef5`gPU2!%S)nTe&A zG`>}M-Fqnz_l~-+QTg*!AM1Y+9=hwch{Z*_eoJ3N6X-oU`XRmq%Ueb_U?6xujxw~( zOUr@ti<8Yz8+;BBu#Wq8+m72;xc?FtK&L!!?C+NiY=#)1R$Z%% zr)b!R$L0l}@8K*O8p5bL3k)*9PRc6-|EDTNn=vJpX;~R4u$tzBH`eo8d2vZS9bbmk_n(Ia;l;W$DGR6qE0xaUL)5F@YHjuASlegfoy1=F4O%)G*32vmtU&6zZg3GTC)K~&! zTV|$;%TigPCN;Dwc;Sx**z}s3OJ{@f6J{3`t)}f%=M|NRpm#O`GJjpFX}j*UqYOKR z#RG<=kEj}MNB-p;`MFKZfyECZ=hVUuI!`OB_qgttGjr8Ha%iZ$$FmsxIn+Sy=9ZcMeq)#gG9ZF|GdM7goq_ArPYFHGi{?fa9OcDj*n3H`@g3> z|L=HvO#ge7*pp`K*{Ftzm$ip#WrP=>om_Iy?`f=$I<1Oa$gNS`*K|eX9VUUCL1XFl^#~NwH3ypvfKE|1wIl7 z@jHx_Xp}y@F$=b6)VQcJViiK|6qVD$Hq4Qz53ECyP(E>a2FbwgWMuC5|1tooG&u2c zl6;F*2()e5T>M$LxW{r1s&Z8@iVs59d54Yx_Zzb9E5|v8WTJ{ z;D%xIgfFmR}id zF?-Z0%r>juxd`of6(3ViUuU~AeZ3r-D(KqD+djCN4TweNd3_0>E{inUV?(^(FSNq8 zIqt|N60cr!yC0%<=T2B8pA@Q>EzIMJIYPj%O0~VZo12^80L{urM3Y z883PKmf90H>6}A}f2PA;)*s+mXNquuY;BuwRw?zE6@c9YURElDVYo|{tO_-iZ;DyM8ds;w4M8$L_9$Z% zi;a@C07DJXV$~a>jkXptcE@riATvYm%In;Vk#iKP%kzt&+c06xTGk}T7MmV|Kg{S$ z4B`42!!pwXTL}Y$3(ArjFqtkoiGA}%Xz}FuGvYe?6G3Dz^*K?Vf1KmZ;1o5^pW?P* zNnL<4S#`37>t{x;1@Ge1ms|1g^9TEt1*(`~O_o<<%|1%D(1{W~6;SzP@ded%LuK=} z$^GA0RLSKVCVzTnm5466a;K9OdZ$(wIcuXmCX=gL>qG`gm(pB?Ek&d!n6;;WnbB zaBrhLTJ5XsASa^uDf7|A7#7(-9Rc@?qg)ZM%wDu(Uca;>01b3q*k5;y46ENIk8*T2 zAbB49w7K@V`t8~%W>@K|R>?mGFZ2EzBy*Y(0Bwm#3XFfE0^HWjhJv&NeDQ}yYEh42 zq4$TjOCM{NJa8d5K^$Ty?I1(8H!i*w9%LzxyE$Zi1Rl>tI5X2rv{Rmx!InF`)j~Fh zoFkUzCP|&4H1u@9oH$PZ?y7FH<$5KKp)Ydb*K$2gcI}+)cR>xa;@*YbXqOz1d)Fi9 zzRrcRy8O{}swWQ=_PV2ltnI~L4nVV|kFu@@U7Rw+rrG%`LI%QzQP{`^&Ew%GoYGJ?;*o+1YP>RfGyA zj3tj4$Lkxl?`y^g!ajH!KVPY$STrW6gkXdGf2IhOC1vi^%<0XEK?nczR@9Z&*)AnA zm9aFi-n}MRajtHQ;RE9d9P{3EOuv_ZU%Q-NW@u%Q?GN`=fs_HxSW zR=hB}peMjR(f(O=-ATyK*qx}O!%&;#3 zcU`=Z(Xzj4HHn7MwBdSKHRWDt@sD2)n0~NnisQOq(r39=p^cFWvj9yx68u_W_JS-}V zD?Z?ya8eo_`7V4Z3-;lSCXMmC4oU=UL~3X-v}~)QRYypGiRcIO#?2|FM}E#|SZ7K7*msZXn}m_nXDYnD zXP#IOEJzyTHS{J=AIF;-;%IwiY`pIAVF$I5dD#BHz7>u3tQu@fSdS*I^+6r8?5Xwd zpZMhG+5DC#^&pF1p>-1lO9=|a#jnp5YNM=eKdyM(51lErU9h=7-EO}o43Teh!?R9f zUCtgu4f06YQy!ygln}Ja6E&3(*>oYWr?lah?0!!6SRpE?%}i#4E+)!y&leS%mD41u zy__gs4`8Eu&E@Y?7YE8k1qD&9majUsL>hImXRu!=IR7GeyZE2b54l5}?b9AOcPY&v zdXk2*J6+)SM|^bsCamTSzj>pQ~3j$t4kH689dfsliaJGTT$$x;f1^~-3M=L`olTr;VAzshm z|HUD}e!Dkx)t#6lX?U|fXR{gdOf?)tpcDzrsrxks3#e&>6FD;Q}_=ING-Nea6t&rBy%0*%<{pB!Iagb@WWD29-W1M zu(DcILPEmk-Y00%XPLodyI2yJ=mDe0%EaMeXtB2`><11CtCCbn)@|U`N40Yl!xwid zTqAC}-!?1XSL?^kh-u_geQ#L61gKV_k|eHn3$&kBv&4t|5xUi8ObI0~leKtv`BAp% z(~J`j3;snava}@e1oM=%H=mK3W1bbNXEolMA1_>TiV?5~4)319RU@&?tHuwaNTeeU zC?7!6BH$1D&XgzJ&HI&LLxk819R-F9{$apq>_T|J&qs|GZNnmPXFBm&5{N0}QA|`? zcv{r)0TMELEi4L^Rb7@cM1a<>MH$?DMscD47Gi6kLwgEt``kyjdl}LF^hL^Scvx%X zNB)HOOu@~*X9r=^t8-$Qj~gs_tvWYIob6e1%;W%DNXo08|-3x z75y(#PZP+1mdleI)R!_~xT-f(hsL$J+ zzs*8b+6QKE?c6rS2X~kI`9||P(Wz-(Vch{TZosxcwz&Zs9!C|w^C?}DuVG~w!v3d+ z`ZJmB^>j;;l%~ar%+8TfN~Fty|7VrK$iiT}&IAno)T{KO9UUNMc|ebGubD>bCP2%F z(}lkB*>n5@5u5VRU@KYfxJj|G`YU%}OyJo8M$;#loQE4^C4wBp{vOzwdffR1D-?R` zao;+~?bX5yWf7(WD`QTUn7D(lmAf6Vv&U|1;0{PfLj8FPii6O_joj7W}9|=OL@`L2sao5j%&YKA+TrQ zoJXC#B+72ljX-ku7B|G75YIJNT{|u*={~OoGon)S71Cj&CjA8*-vNnfp$}Oq%)v!n zr&C!r7=$E-CP$`&k)9D%QDSp$J~jwF7N>$u3NWIC7VO$ zK!K(!q^1&+vP(^_7X@{fJIDBChO?v|BPHIft)z1XtpplTH6pm2m~jx(poM-LQ7PB| zUp+^L%39c0@8k5N$@D&VkS11lkdy!VJiWZ^brPoC2BI{Ws}f+NdK6eK=Vrd??gH42 zH8c{7FZRlxLOgu(m*TTs$IZ;mkZK=lpCecQ3D;5vyzvaj1do?f3t+X}Q+FvNhSo`DzG< zE^;vdg%THCAGQ6w9aR1=GB?%l&p8OHOx=njvVhnJ@iCPL(G4{SKaUr948MNO^T!Es z6G3GCE`ZF&n#MKOF}3A@~?9; zj-j3T`sx2Pw*fyWs~JQt$xOXahl?Im-Ce5JV6^WxLp6S3X*ur?3N5$&gjA1zm4|gu zi#|0K)TMHWj}RZcdk;cPYpWK{PP65C7nYa+y_iuFI`5c2dokV*$pE{}FTm8$SZ3G;`)o8!UG8Bie0k5{aOf6^(A|8EhWnprNWVtD*3^03t7UbV(sMLP`Uu*6YsiHXoUDaRNBCv7;^mDha`O&NhmjxBlJ}J1BDoJ32id}L)r4}`wNDSc7@5UCM zKcxFJC|u&6$|-F4faB<^Gc`sh-jxWk-oO+7_lN|wZoPZ_<#d*I?4u-hw?oCv$7hQA z-lK3wbY-9Vx*M;>9F-OY>ucBm^`T+rGMi}d=|QS~S1V~ph3mX?7$!Gu^GVnTp@|NO zd}RF#64zshBrOqg`UkVp5T^cpa`R&XZg@2Q6 z%Ma^X!L^lzDmr`rXM@PF%{<~j2Y^B?GoWjB%+n{rUVDk3jyo!781K!t#KZ1w{xDya zZ%%DB)=c}@*M55)a$c1#dIGErrEqK37Ey#ZCABe|3ZFHS4L0ezONc}n(p|}*E^rHYU+2cs`u{_ zr4=t)>TJ*Jesa4{ZTYu@{3)98*Ox`o6ahwy`?b%+Cua@)$}QDpQH!rJEdOg^PRu}rJY({7HBrn6iHV7| z{JOnTesH;(s$S25F_AMNFq|Aob4MqiirM$SZghSITIG^%Rk0JBA-oDK7LpQGOeW z^{H6h6!8*npU#Q9S$7%;1ie4$BxY0~u<5(~nc&>$hAQs?6wv1VK7&oNts$G*r>@b_ zUq3wE?BrW2EjI(7z1&|hzU#59$=c0UWO|MC)*`Y+FlI@Nk7^fxij7Cw&Cb?7drpTT zA?e{g$LsrA6ffoXOG-TgQL6D-N1?|JBkser4RuJA433;R@N^w^} zB8|n;_;Zc?z#!SoO$D*M%=&xnz+jCx2R*yF0j}$yb)mx;VlwlRNIH{hmr+SX1P{~5 z-nU`sYW!x9@MHlSg2qC8DbH%!E08O~SoJ))7C}JeQf)38H4({c^@+$sx52T8%6L*+ ztEmuCM}N|-Nt8@?x9x#+b~siG@T84YVO$PiL36k=6lYxn_UqAz`@{gle!jgF|PJ}Z8C1O+E&tOg_H8rzTHn;?HsBBrb0RHJA=m??bR6kwx_IA z5%G;{?owZRl~p<>h4zopqu@)IJ1^o6;V($fxiQ5TlGvizfZ6lVx!uF5My zB9jYT@lKT6f3+pLC9BbjQG7L#7kfC7x?P-WW$KHh;h|?z49s`f1_d7E%{84itgd7U zn+hU4R%RrGX(V4CzBTZ8R_|%9gY>iwUZTUnyI2)^J?{rTFHU5hwMx=5XypdvYdIpd+01X6`Xv;Bz%cK4&h9(1qKPWqz0% zEwJrZ;9mVC=$=O}mfoV1m(Nxnf|Zl0wTT8N`1md>ZmM&S%!odmN09*=;}mal@C>_3 zNADLlr0q))*i-TH0cCsDu8!m&Nsw;j@@yg_l8V>GjKJp_nK;sEyCv3t04Sy!R!%+4 z$i)E?mV(%|X;^(1|GfTG1hka4@#V`8I^hGs5s}qs1+Nwv^4_WflSdLfrHNedMJ%ho}oXtxRVTEhPSpk zJ(cQvo#kDwSXFq-GBnxQJUlkCfcfEvS_r`WeD5Ygutm*Xf0Lvm0mngw-d0%1_V!Bu zTXWIdm(SW-4*JCFWLe(PXpor4MHysJXltba!NOXDH|X%PWoZtd{}{>R(>?r)0CSez z2GN+j8X8J>)lt7s+`+D0Wb?}-4YWTI78hr^6ynW)H97m9>j-^KUvZx+_qIfx1ptir z*2vIIB7|n^{DDXm-nZGQnAxdsptV=EwVIMcVNYffq@;P9c29R9X9?mrYKXc$$DMIQ zr7DGe6u5KFIuSRw(CgdIg7lQwndpclL@)i%qF4>yL(`Ptm;SWjHIQ<1@LwYjNK-Jq z*IAwzFa-K&#TN!1il4_EtKX`?r;pnry9}kUw`UI+f0*=gU9urcHcW~eprtq7X#FR(TZD~gLt#lNr;$~_&WlN-^Z_cA z7Hm?@CT*-)jCcKJg9z?SS(lEANZ{j0ROiY*d~JSN0SuR!6@gt@ytex*hC zS!1w#xi$Cc?^QXPsHaO`R~PNhXRLiNDM**iND(k9TERC?6O)BlSD!}RHbw+iVq;w` zmZesN*jrL)N56%*g{y^BS#0;=c?8(IJ{e@S%?HJaUR0E6JJrUIpNH97%?ff05XHke zy-cUW@G%e!c4mGz%_nBYA%fD@>1o?#a}FJm@3dZ+9sgR}3Q}#eRCW#Yqd7Ce?zHq6 zDrVu%r*Rza1K9Zc*nIYzv-DjE)%!2sK>^f?H)zjE166!rtmIh8J9JIOQ1mve?Ld93 zwsbn|-771T26LJdaTx$=i1c|t2#P(e>S8!R6ZWyVCL$Du!XFGuLOiJK9^N!aCujBX56U?A1D3f5HVZ#uK7lD?2azZ zKNT!wM6itg6<=j!fT#BK!It^)7Bk?$)qh#uoLSQ|YKA+L{Kz_m?)|EjVZht9lQny! z`j5>x)1>tD=#N4S+Zo~<3tppvN-UZ@#h>P`&*G8BE&wiTMcd#7k-WLl{7YBTe)nk? zs-B`OW4qj#x0MHaZCO)vRbf=SMVxo4z@%2IPJ{-Dkp5t1ew4i2y}|X>oT=Ko2P#~o z`Cm%Ba#c_vYD-NAon|MwQgIN1T+~pTE_V9b5&D59+S&G_V~*P5_7FUoT-0Bp_@mDE zyu6@?kMhN;g_6(aRK@kgIVmHwXgT@l^JH0xdl_@RWx@?1pFfeOaKd;?%+U{7ElMI_ zP`GI9HjY8{McV?fMqc7bS(#rq20GZ8%M@d1I@JH*tf% z)8^Ti6s84(n5)x%ry1%fX1rr4Yq`p6zS>i8yt`0$#af9vNH=gezj6lL4)fL(TaiF136d|{t{vSY|7 zc+$o8$a0mE{lRs48`uLMfU(z;bl43({?Yv?c>2#}EXV1_lh-Zmc9hDfDyNpw`_LC* zHq=U}m8u`x(}SK;M}hCwl6?W8_gD{+Z@yx(mKbO`6VNURiHu+-KI3h{QF;|b zBMeTLkRN+KN)Wl$;-+YW>Xz!Xq$yFw?MCE5U*g%f2Wn)kpW{C$tLyo@7_o4UaGgC> z7T$P%dwRgfUQH$1OD0cW?>=j|jk7sI% zTR_;Z59qz&FYt9}@TWYEKq$55B@H&wv^WWjZkO+2ZNSDL%E3oT)6KuK83;)L5+}8b&^O9=6of5?1U-gVA_80bW_Ez-J>V2|$awf`@={iwfO$-6yQS4Xv7) zwQMiZwJq8F`?kXUg5}3|@1Jdd^nINa4j658#(m}rYA{PeTrPHAf`U-s7}|H(^8;hdeDgke1D<#&PcTCJvW0P zEMKo|Xm}X)Ekf`7eAO|!T^EM-HnXy z7^6qWyYKHkj{OBYw)?rB`}%y&Q>Z3eZ757XMxO-ln^fNzQj}5CO!I12kaFO~m3ou$ z3OARya|rjiG*ThvVp#|ynK(w>QYEA5Q8NYOVemOul_#Nce@V43Tiv8$aa+-iR$NQP z-n{$2RvDc%VjC;PIhQQ!tg^U>E3j>Wnlib>lRQjR4p~|N?Qell1n``Ti2j&8Wl|{+ z-rUQzDo)-VByvXTj#za&XtB;jxnr zO)ctUYSLxqrVR&fMV@4BLdG+Bx{j7cFCDD^GNa5S{CIcd z4hvsDd%alL9GtJf9^DM4UCz8c1OZ(uet}CCEP;^&`KUT&FW;M4RMRKx_Z63GeIk1D z&xZH_NmBRM6p=x%if(RBgk=)XfkAy?OjOmypdRZ3gwuq(2BYVhM;f$S( zH>u)B1iOxff-Gqf0$z^Wla;6U&XPoLNG%nbsdHW<4|*U9o?teDG+8>hb@DvNAF_k{ zzqHt0106S?_@_eGB_v+m6b!^yU6)V92_tYLsH6pB=A;rmIq=rJLxm}Y>?hM4KNXL} ztt32RQq2*`SI3>%0Xy6Ng2q998DsJU*8tDu4?_(E_SQiw!*QjW&7PH{f9 zM1-ttKfEtzkE1F3Br#F%d%k^NbN)ORk*2r0J|)6dtp)sKv}PVxDf!Vf>uXh&GMrnX zIt=`yKkwfJ%qLs8y-Nf7{zmP=FBR|q9+{Db4@qKU9naWAh8UYg_x^bZ=0wl>$~>-w zr~a8W_=qsu9X48aDG+o;r#QIXye@W3No}zs{h2|Nu{yXLCnWo;+X8RXo2G^jGl^+@ zMF%Cd_Z-S4MN8Tm(64qiOR>(4@Dw>4W$S{yr=7!EaemI|rVO`wAGX)@$K&Js8rxjy z6x;)(w=G(10;8f_Zl7oAA{of37kE27>uAbDOvl*uFG?A%2O*p{GrSND))F_Xrdq_b zA$ef+mTd2rY6pr2_kzo@)+Z5_E(&-KbXkVt<*xsC z$Ngfq`{g_{;4@K-+~0?LqWk5kAX@LU^`y+dzHq5z#M5<(`tA)>r1Wb-ypD_rYpd(I zCq8dawFL@oICv{~E5IoNfpx7dTS)lgSOEm?>v_3&1APvM^~~Gz0W}*db8C_9GF{`a zWEfLY1dM}Z#GejjgaWt20^~xkAe}gUI?N6SQd9X$-h<*;UT)g;J7P_4VU#C;_Vr-O zs^VME7%#c+)Y1%?Hjiit&dwY->X%l~VjBymw`AwDe3*?xwIG)x+#4uF?x}AQntgE@ zH_xhcVm<`UcAlW@t&hBK;59VR^mZr)a~bOD{z9GO0W03@mokPW1`O7scg9nS++?do zg+G?BJjCS(J_dS6Zh$r%E#ctd<~)LKgX>@D20o0h)TyQk}Rmxzs5zkNHd zj~pvbUMW&XXTO%Qy7FJ@6CB>d6-;Z(h_9Xbu#=V$2@uGV-$DZpu1MkjIB7QS#rbjF zY{J+a^yHYKej8tX_VEU19^l<4g0-l{FQQux0xeZM&%n=-$#jzxfejxywS4i~vruLO zeo3*>fdlms5f^w|_vI3D33KV-*mzo0fG6dJDzq!zZ+l|r8`N-lr8-*Zp68w_q@GNR zJ8%p(&K0iY8i`ak!*6x#-2Uk*iV`PdPUWZFc3oD!7yFj@U6?kqY>**c9rDP=8>ByL z%YPEOV~HV6XZuEuFC@|QSj;85zs-)vs!=Gr7iVV4o&nn=eJ1G(8Aa}VGk%(14I^w_ zUmG4d0AA3lghwW%F)4KkcR0_ptJyw&AP{H2mW(c^BqJzl%(6pgV~`U0++vIt&NU*tu`* z*r8c-mY7tuI)<32l*9oG;1m8xL^m!F7d!v6%2;){{EK$leu*J#*3IH)1h4}F!K|Km zpK*q}ublIG2ct)0qhDCUQ1Nk{#T=(OSi!c-sLM|aex0hq;&3@_He#tTZ!*fuo}@Ex z1h=pH&@D!)(Gzg#7=Wqt6cSE z!Gn;{7LwVlji*UxPw5aJicp;zp0gc@P{V0!UlE>XV!LIAPB72VG|uTs&)fQeQPLqZ z5p#|UrP$B;Z3g2XHkkdFzHTbG2iXZ)Bt>!Cr_f){5zAyRS;f=jiB?DBe~o6l zrt+CzqSh+%&EnkKe%`1pv{TtTXEKMmJ%&uOxl2Z#^+#)b(g|zc0{5>(X&i+FX_sz>7^w#kQ>9r@_Cg-JdD&Tlp`Lr%mP5Xs?f-G}>#;^R_Aj$hK7}Nz(Ax z>A(N-bdW|4c+(7(+N{6>WQjd!d~0Fs#P~8dGl?$z)-yn|&$MgC`E!MSQn-~$o$lg+ zb@zVYU|-+2)UG>68hwFuW1lbLcbka5_a!i2&9c_!JH)53&)yF#Q6W!*)g5+^cGB_e2ZS3jD~Lev{&3|udErbYN!sf|xNJ|-G8 z`nAfrkeN`x-e!t%m%aYG?cHwCQDTYJ8O#F$rC2h3aWXcmj9oI$AurFUUU2pJW2_N@ zKc%?;oq$mp*&ur7kCg|vm#0UHOsQ%(kmEI8>NIqlj5z3D;1207f2wAy{8>Y{m#s2qsRqqvoaHkJ@Oc80omRvpwo&BRo-} z%}=cJ-&2K)2OgXKVWGEsaRM8&-nTn%*)l7B;@={7UccpEakG`iTdSql2EzFNJrqUw4 zS!&ZA(klz&mAM%OABYEjEsB|`Hda7MZp?a`!V2+57dd+{N;UdtN$_5L^!4Skzv4lu zm<U&l@;Osbm`+?bbQhrycnmA3836x{*;*Ci%RdLvB71qb4^Wv6TL^9816L7K01X zm)Z=mBd8*(>9QTJO)}(n82eF>V++gJLbLm}@Y=f?yV?#|;T<~hTi~V%n!^iYWvkeT zAdH#T4so@CC$l;pg1ea=tuiw^ncy>i+IL|Ng@n9B%TH#W0>b>vbj6zdS{9~+Cti%8V^`ige}hBhcrG2fE}eW~sU!@U z)Tuu1hJzS-bEX{uD-NiX4FT* zH11&Ijs0q=L1o*N#Q(i+4JE-Lb!&AUEK?Fe>r@?wglnAv%5W`n74B+Oj<~0Mat1u$ z8#^{O#vSn5DUNphV2Y*K@GbdorXKSVaiG(r>2qjwa~b36Or(^;F<7tM7PYuMH`>b9 zosDC7b-SZx2dHnH`nSZ_ms5g`$D@(E>PES0?CT<`W#dZnH-3g4O#*H=pRdV(W5vJ0 zXe+0>!@T^8(ES(QTJ5bbQJS2jNbtbp0+*@Y8!7*l+eE$&oy0JLO2E{eZ~qunytID$ zv$Gx?AXbjL4kgahNOzqN@R&P|Ik3GUR+*}T8XO=Q@a^wE_e_MD3UYTf$I!W;j%0*0 z5z2@IsQgarkM>4NYA6Hx?T*TG53CW!PicK!Cne((QBf2~rk1O!7d)^&bqEw;v<*o_ zn)@iN5pE7AQfIy?*Jjo?!O@qS&ahupW=vEDKh!Z3)JyhN{)BbwPpehg-qrr*wwv1z z#zU5FwEVI)xGKmKJ8E|tB$3PSt2_W!O6^HaTEeT zHD@I^PpP@O%uONBS%MNq@{zG!{ds_E5I-0tXa~6t<(x@`Sg7k5v*TGvwd8% zhb&dzmc6Lo?(7?(t);sYDv1%&YN@}X|FLFkhny!B3Dqo_jCp+M2~BK)1^=5qXBi;M z%*;;(c+9y6-E^*Y0N|UBF1Fk6L0)Fs&Z{7{C3rD@r44koS&QCVppUa~HuICqAjkc9 z*i13OlA(mMd{tM9F4UhRef`fw|m))vg*+j9K^L3tlwwd1R zMGg}f`}Qih82hX=P9`4IK7tXX6v#{}X`94e%<51mg=JS}sQ=MH*CV<23A%`jogE)k zL{RXI#RwyMx?mpT=tEg~$Y-AXC9_#W|&{|-5 z@_KQ!AVBi*!z$U+k#>;iTwhDo<|aPo)f)-pr9UL;$d}_;x!%8DI(n#eeU1P_xX)Wt z;Wt?4k7WJDH!stH#a*2~i#*R+qU<@1-b3wHof&y!`EUu&Kfggt3$KJbBaeXAy6i~) z)2YAWyyu4{5*-ZSJT~-nZ_>@FPJEI3Dn}K)FB-{fEV5+ zaQZVO0TB5ms5GwltUJZR_kP{Gi}`hJ;}!dU5kBA7bzM|;)~T15)zYVMDVChG=cOr= zLKKn{! zah&!_m>S-DLcUr!p%@Ifg|i^`nLiG2izmkGzmUgOuC@orz*l?Da6+<*_T@4@&;_2n z{bT1O6@$(JvGpd^lx`oq{@Kb;a|hfnImJ6&fE<_BUFlX~YF@4V^%%2u4K~Fj*Y;?f zJl>^Lxi#b^ zvs7#Rm=NM5m5tG>`cDS!CoQ4>IgTppDy{~x`lHgBlM(h@dFJLjhaxjVxRutfQ-MBf zJX>Stg9eRCW42^j#l@kR5`_8v)KTESMcPo#MFY&qY(IQyziJAS=z>+eEW1K1Lk4Vu zQhtZ3tjJOz!CZ&?91Tk1S=)S*DA4}Pl*8w%lzGNlXFPJRm3Q-3@6iU}^5@Z?7MkuS zyKrU#{98BpPT@(!9lRNq_o_@XH3F%F-yyVe`vJou=5QSi6wt3u}uB-{=YJ&2QT^h)0hvbNf-PCJ?wf(dV(bc(l6B- zb3to;q4eV%<12jxxjFUXyXRJ@^9!_xZN89ruPhselqov}dleBybh~B5I%nLY)XU0M zc=eXbb_h|Er1qEg@87sN$>M0V@2eaXtV>#1F~Q5s_GMM2TPmDIxOVElXOf!5J7_o2 z>>@uI43F&2|B5|EWGs86YZLo^5*4ea_Su@AcqW`sA;8xH9wb0zC1+ADM>t^XhK`f)!g9M_&TCQJxeqlfQK8d zkK#7BzwNLos9yMa;7h&G|2B30K~F1oROwP~LNZh(UB*wIe8YG5MItBTJu3=K!#4nw zAlG^X+NnB%SYKP0kp~UeP|63z^_MIXcEbC9RJXv82ol#BJ{Od@{Lg`+!66t>Rw?eGm@f&}h*U{D}6*WIvFB8Z&H){UCk=b(4sfDhR* z7!xrjZ-MdpVNr}KFVt9+c&wP~ehoEqXeb=k9A)2lM-6VT*n&~_nm26$J09aANd|9D zNDXdZc2u)*u(9s0V($;3cUPuoa{p$oowDkj;o#Z)Lyf0MA$YReNRbowQu*2y~ zs%BhFqgbjPHi6T%kK6r>)`QN*E?G97(*|QadyRoR0>%Mf-1P#=biC1M&XYbYa{qBh z1(6wdkk86qu!sLC!mb7Kx!lAltc2>^1pX(EcS=7(J#b5Wrg?gKaucsOLiO6xkYr?X zzZ_&a*t;z8`1;XO#bb;YcY3b}nyRM4G5n^5MQW>Rzz~bH8q(7SilAHzZ{n zZii=a@q3@i3`#+6kYV+?j%4OXvtSkBT3DCtNP-i0GR9f5Y z>Hp7&c>$jE();WAm}dy`(iDFl(7GQeTiTs8LhBQDKb|KO^15zCe?2C$#YU#jlogZQ zVKaB?sD&BSnUVLU+0~cu2<4E0#K9r3LHGNdU9JVoT2lx2k^-Z&(SJkm1Xy@q#s}`Y z7tRR2$|d{0(KlQ4VY+zDw9aVgs-JVOc{gS=Lo6HV+9+qfd%TOch6&>=`x&+_gz;7{ zSzbROaiI{-d6eh~AuZ~c;YFbI>5{O1gxQZEW#X?zqEMH1H$B8i_pw-nP@|E#QHRiA zhUBS{gh&dgeyFUfI%0xTKEq^fDRdu@JW+Z`n{|1xA(mU>czr_``f26Om z1)Gft$;0bZC2ENvuwtWRfJ`r=y=u=+@iVz!XL?PIDaMz13i0=nl>O%T6V9`}p5SS! zIpLU1-LZ1dbc&H9kr^%__v>fZ2Xbx^I=1A^28p@_jh`Xr~iPkVr2Y#?vxSh8UnFKL6#U6?> zdh8?sebe;^tU|9}wR7>GvhBC0eNCI9y~*THdW2>X7`b!OLkNuL?m;-bW3 z%|Xv$UJo>3%B4KX)Raj{Kiw2b{(yUQ+Et|cd}4rLUax;boSO*isYwm!_xmlK40WKF zw$3M0F71GkAKBud8V_3m4-TX-1qT7If5qZ{L)I>^o#k6EP{38O$Q?JDGz;b-LU8Iq zrI(mla-qSAFGq+NVm7cKuN@QeyoIdTa;#JQr*#4`(65)31h*O#O#F*Pd>-2v8&;S$ zImtV-*<%^hVLZ2S6PicG*3l=Pnt-3xr;iL&QgmoY&~xL% zAa1+(0rH0W3M#A}cacQeB-CX(O$i$kr#MYqZ};S5cfi0GSs*eW*bM-6y;E+-Nnr5) zV(6X|XF3RL9LE5{0T{yZcJy-aJm;;?xgIyAYNP4W9|E}-e8-gmI9nGF^em!$6wA(& z$_KMlHMRuwFIC0#4Emms^-SY7{2TwCa>-k#x(vJKXZ-JE zbTSH-;obSx_d?ti)=KgU3Qml~SXjj%bNyE0CTq?;UF8ioUTQp9+4>hX`q~5W!sV!= zM}5`6%apDpIF56yF7PaUFK)>sxzR>#v;uylUmp= zl245)r*o>Vb1C*)@I%R)fSjLkX)y*>IM--P-w@7e=%>MT)r-V%(YuiQU6h@kUdT4VW<;2Fvj=}AgvLB=>7Nf~sw9L(1?1j;6xWq%552o3{z z`h@udHS5nK9Ula2qkGhaQ)WDBoNRoxiTBGE*k~2va})go4Odh@e@d;a;Xr}P+8Rnl z!NU{uCet^$VXn1RXU8$%PKRVAK<~#`RmlRBEj%Q6k*l$JkvPmA&fhZn4+YjFqdBBv zJL~Alms?7xOr%=I{L}IqeDT1}(HV6Uv^ZO78z5~PcC%s+RN2%53W5^4Kna6|e8>ni zc}}zh{tSF3r1-U2KSLc(0-pr(cbfYpnqfxlrjq|F3eqw#`*q zBM{qXgDC-UO5BDmB{<*{;Sy)wBF*AO?;XV`Ihy=JT{DXlVtGPh+SsWR?S%3hO|&9a zUdJb<-v@BGo8dg3qZ!87ckrB-OdcncZnoF=C?kU8G$C)F`1tJ{r8yhF!O&zWx@=G% zfxKMNvBDS`+6U}d6MkOxasyQZRmnbc!?G_NihrAIJwpQ(+iUJ;{acx-+mBoHzuclM z_7gbSSixUq&UxpXa?L44nsm@QHBb@QD4ITH1G6F)NI$erHN&wcc2r+bjn|lVXfs7c znVHn`(=>-lPdXnKZZ}eOi~|+Pfu*Y;Z*}{H%I2Q(1%zWXPp2u&`Owp1!_f0pD!$z# z?!z3%0Y|3LZEDM>&5Zx0R_j9d51Q!ya2|MC`xhXF3`ndzNGjX#+~7r&5($5MU`-m4 zfluB2ZqVIbE2Ue4qYOLGwKjl(_5S|v*=f{d@eX}FucH)}YIQPO*CS1t7NeqIwelO&Ju6d!;iRu;;a_@0Q6yH#`GB+ zV>OH&WJO3IJ^rGN`xuqDk>yi2UZSQ=UW&AyjN`&<|IGzvO#5y-ohbFJP^C)lHl-GwOo67>kTz+g^{fH;@(+9oe9~2)Db=`gH zDmgx*Y!$&&HYmpT$?^LaUQPEQicri zl&n!(@cGg^m6B;z9|*kstozu=iUkh_`UQD85{pr|;QC0Ty*G2M_jU}TdI2#ZZsqz8 z(^-+vV)c>q35hu7y1DrV)&uF*Zn5+wM6-ZS4GzuX4t2rT>uy+>C7b^MA{WzMbxR10 zh_WfSDBnQ{CLC&>1}nFXJ^7HnN|yFNJ4M?p+KE)-6w){G1G2qY zJuxJcV|5H#QfPA>*#`>f9-4s?{_e&05(R{k_`+CaIpC%`Jwd)x52W>tU| zHLb2Y05zmuAH;qX+g#H(M4wK*&|LYlgU)7QFvcDN`@4OSv5yK#WvB*9-Zj??a%5m| z)!0eLd@4G%V@+HF5Xv*LyLquW&ZLr8#^hGN`~8 z|9hYL16(99I-oo?26w+%IhwByW>jV=_>;zS)!SQXMGsin@!2<1>3qnX(Zo;IKI_w) zQ<@W%ZVlxwnbm85$&M@irA(BK((t8983mF&Kr0*KT4wi_+5bAu-G=txtRTF07*`?4 zd+}9hE*YZ=K!db}5ytA*QtyUo8v%s%Z0AOsr|A6CEmPM_CPZn>}6tk%+qqpRD*wpUD!PAqPh5+fx*li3`^zG}jY+m_UpM~&9DiEFk=5~9%Ly^H)->)M+p3>#@h z|A0Y^+RDiQk2JzbNxkMPT%p|DKeoDB4TMB2>e+eDl**nQd!jfknHH2l-#E-@UF$yb zo4I__IMNpDp}8cCauE4E+R&Hce%MbYGWNL24>S*hucBZ3!Iyyb4aRgcwSF3qEM9WcRzddfi5>TyL}~PLK>|EF3VP znf@94p_&cquT}YgCrZ;>=N~A&?*FKKx#zv!P{9bQcsws(((l)tU&95qwhC-dw=4Le zuCv=4PDMG1opbN`UK{V%A2?Chw7g0HUVA9LlXLES5el$I3o+K;(Ht&EK-L>G5tr>_3vT(S^@>h@kt4>`m!QMEaHUxgtN z=6%G&&CUIRZg!kto!S4LJHs|QE&?j;i8qE^CY}#)!sK6)%~;vICOh-U;#H| zWX0_^^Xz5r(IQAx>Q<6dh@UrweOg7V#%G<9Ejh|{KQcPvdrqhqhF@8}evpZ%$Gx;+ zn=2zD(@^pHzi42b9|nzZ+^-aQW%KhsTg}T6At`@9sm|4GXBCb+r@vnRnnhlqdCD;7 z4eHwpV}HNt9q%W}~f*Qcom0E5IOY9M$$n*C6 zpZQU->G4;8sOe!g7}LG2`^P%5mAQ<2ff#X7eNE(Yfqt8~}Wk2GQ}OC&FZJL5S zb-}*R%&b|cQ^q+z^PiV-*{;c{D(%Fu45DA?Bx*oWi36gp1aVuv zs2|!1#DBF-@1=>AYJ>+bGc&Tt6H-&dbxll~)3j!3l(tMq5p`@C3omqPux0;#%8(xZ zdem|+nGghXV@zq$#y?Q|5(@*S{?j!fFoX^)dhuwdX;)YLY5wyr2J`Bnv$APxZ5n82 z!J@C4L2GDa6uVa5?97}H1zi(!z$^*~Wz=~`sD;QAnQ_K)qgAYMj_yxa zF!X?X@RPP1p|b%e3=aqQjg@=&$F#~|AxR%a$KUHZ0b2xSqO?rz8iN6lU#ZZc5{}m17pQX7Ek; z+j}?((X$B5Zu>}Ax->r`^0|@Ag+_QI9*ic#s7=ssVSfj{~+YPn#)4toXAJf zN)v?FzZ{Zs94kqv$~lWXMWewJCuxLlPw6}a2CwP10#@F>I>7|A5b|)sc7A1zrt;2| zzwCphS=rZP??nUxI(6jEjVj_ESh;+nf1$h|@OAnm=V;%-OAd)3_~bzA_?Kg}B>I8A zM^8TK&oVpgIf8F^x~*nO$HKy5AcTW|>j3|4QE;SYrV*|{fqmV1#_KoQ@E8v+-hT%# z1){b*wJwfm^2yfkp#y^Er-kuv(jI?E{D=h@|8pB?Ip+?7`Xp>o39M2#I|K)5J0lN?-L&s z1wV+88d$u8vWnttll8`CM(rW?ci|2-*`O+XaK(!@!@^Gu@Vc$%2~iBr_0R)B?TJ5O1b_=N^s!S_pVv77uBKf6Drw*O5&Wt|sZ81h&*hNnXocHoRU1-~O(f z3rM=|I^}+*{hI(snY_`rc z7eGp|Bg4h30Yhnm=0*&E%rJlC;x&x(UiTGy*`9i3?R*4z?~JA%a2?}iXT!ZwU@RgP zL0ivDXCCv3Z{9eILfm!==pYC1H5r2@n(=X-RY-2tQ93iFM5!N8K)_AWx17pvkQ$n! zJ%1w-R3_S~esnan&RmLH@jibCd~tyrKZV*Q5wC2fDeQ#u57b&y#olo#(82;M!3Ot^ z5n^GapO!(*xU(H9s8{J9z-E>GSLk=3xYH5 zy=!<|eVmeV=9c(?eGQ($>n&-F5np zRb9y(n%KMu>GpNW@oC3}UijHhb6N`D)Vf8J#(`LC0tg%0L~@1CqOBqiL&=`^rL)~L zb!NXyKyeNA{@2$s8Yf-b$GTB5IBlqO4d=FXE5DzT1NAP^O*MaVGIn5$!zjMzr4m^a zO$P-v5{bojrGN}roao3qIS_v?5D>*I{Xq7VgOt5uz3*YXFnOAGfpoxJm>F)@9pGu& zuxjH2=MihY^1}khdbM1AE53cpLX4Q$+uO^?Znr2E&(eiGShKRRJ?7NL0qHHfuRmme z!s9npN_@gIEtEp}_=a)5p~BbF`P9p?5-WpK7Jy-f34g6f4-*GeQfF%cuJ+0oIEOMc zMVow@S*smB8X5#sFKyoGdNR~SU1YCSVN3D>mv4~}EYs?si ztE_nf@|c_y9S=RcbIvZVgm-D2X!D#znOd1b#nEx#1^b}+2&N*J^Kakg6~rT*aP!g! z)$&xq=OFGyTN#m*+asgJfThq1B_t{F>}dI~CY2I#%GZ<=AExhVePk^b!A2qJ&(Mg$ z+bp2;Rtz&Oux7C2cqwl1oBF$q9?Tv8>fZ>J*D#kj4J5}%v`&L3`Y;tG#Lu!aaXfQ` zDpRPd67mh847S*NTbFzad+Kjbd8^kZ8%Q;N@jLaV1>OIoNlf*I_ z&0TE&3_HjuAS_8^XeLnTzY~iu^~vJ{=E4M0)(hl*-Puz{zYO&Be%{{;^?V?YBUk_X zM*tpEtZL9Rxe|kknmXDUg8LbyWoFbi2SzF`TE8C^jp{Tko_J(2u}gT2Sa<{ktnJyb z9-25wJ(e`6EARLwIP4(xzROZLUAfz)4_eK=e#RYF}00R=wpT>1WxTx{dF?PRaj*+i5mLGB1GXM zav}B?7v3|i%2L4&JYfQll^0%?M5=HLl0+!Xe(<(8e#DrdhNLaaUy6aTjgNqU#QZ0^ zw+<%udZz9S_1QAp?R8si>t(O-1`F1u)*g#Vk^9k_fm5* z+e&@CPu_n2_mRrAVgf8e?6!7nP*z2aW`&uv`&mp5&c{ioqxXg%JWdGu(u1EQj_{g@ zHW!?B6Sdrfa#a(fcq4G4Q5aZV)2v?cQuT(!*PDqV`_clE3|3R`@9|1o7 z!atp`QwjoqRW-F2SZF`b%UD~=?9+!Av(qmdozPRa(ZCMuPWxB6Rg$<{xL6qS@OX~P z0-s@b;w3h2*T3WPlJc7Pxsa>#5={Lht8p#LRy7#8z!_AHVw4c$!IyY!q#lCQfe2+n zpRMtVg54jkWjh{5JuZr=I|!yseA(rP)Q5%-eR3ou2rT*#ts`g!`#Kh>_G8C+BRfNr zP~ytG303o44B29PvO|YN-fE!wSE-4%9A~W`rnd$vtO9zAu7Lq{l0!M+t}lZG63kCC z19keiOs&P-O}+1f#80W8ZZ@wJ&ysh<7nnc}K}^;8r;nxNM|oa5B2%37fTlskgW2<7 zn~a5~FsWX(rXcl}&YpsK65wA=N2^_l5-F<0DW`)DgIlMic<2s5bIaB4rD`8b)E4HS$R|snY3Yf+^Jg>;uedJmEI{kZDyA^SO4T*8H10~ui`}#wn zvxBDT*9Izws;WhIQ=X5EC%VeF*V;||XN`^!(-yN}MfNd0;ZbFXXU6agX@(}&R;YW& z`S#VtcnPN4)!;-%c2`xy8e9IcvN6?(bI-gNJ0}S^ZmIP;Gd=K3rzQax;}`X{e~@9u z-G|fPqSV(LzdVd99kh*HPseo)MFs5keSr+FQuSfPL>+{iWGn)<%6t^6m~!~BE{g)@ zW`UC`e!LlYN~WW6suR~_JBW-D^+{)J%THAG!QCi@i`|=17Xc->Y^6oW;&Fa+=VAMk z)0?K(w;q!|>a43E2hAv3SUp0fN3~L_5}_YpqH9@0Z~t^P_93D-vE3B8uur@A6nnu| z7CQk;0T`rVGMA~}?Mob(6u=){BA!}ea)BGbNJ6d@i_Pn_xU@KL8~Npv4r}!X_H4l) z>C!GUZ~2g12R@Ly1`z)!Jo0*6^z3<6`&NY*j4pTgDMvYc^S5qo1*;f}!zk9vHEA-_ zTGI^qKO18PH7@SUnFUBAOlhEF)G%Jjlk;*QxfD!^>G)Y$mKi zJ_y27$zQ@POA_(|`F9UPmB(yfsrQscGG&aCBHBZ!85WQHTMJ6?@;v_#SzQ?!{Ov!DKAiJz%@j#@G&p2vZy zHPdrm<&0uwm>XB3xDRrh+f>e5DccP^vp>n+{an;)FpTd!*0_dYx0yIKYeF?ytEOgz zMOI__o_}wpjWr|1*&9p(l&^};+ov{__D~12VFSAQtrhOhWK-NIi`waHIF5gYLI|(k zTv4?KtmwOnMG(bn^>E{bOavER43j*tV#(`9;|bB-SyfNVhaD}D_K4DXBFGD+JDd9O zPUdIFr5pQ+uiu{aq=Ar~g1`Zun>$H6z#fR9te-!rORy>tx@+ zqCP{28m5cUmBUon@pn~Kv$U5Yhf#u3QWJ%xIlKaCkV4DH8f0W+92n`oJ)#fG4!rFS z!BuTmd4tDv65((byRr_R?e8eQRSeJT@M@M*aVlGTubvNyx2ZGy+0uEH#<)eRnqi0E zU6igkgM*$7rsuPH)FCK!xnIl^y_ar3O5JDLR*P z_1g!iZK2I5&65Ov9XYwqAYQFO4VnR_^6xo{JuKhiEL5g+q`BE+t~HJBxkPUo)zxq} zsm9(Jd;Talz3_!Tz*+-g^79bSA?SZ&c02%MRp8T|{o49Lca6zl(AsJC@D9Wkw^?)O zHOc4UWtgcAdib|WM2tFoNxA(-b@teNiPI9tlE%!G(VV*mtP^eCp!5Br7T6RGS|+7B zB{5ocLRiXw8o}MEds*Yy9*yA`Og+ep^RQ7Hf>U1cTtF~+(XxYv2Clg~aa##N_0o5Z zjXdiUqO~s5MHvc_nFH~GO$J|c-|>td#8|c!e`P+-Yz(9bKH^t$8C0*5p7uS`!)5%0 zzgf_OJD1G>s3hH}Ns_@>WeJ)U{6qidSwS$!+dNR+|8jH0Zq``z{1R!&8Pe?1{ypeq z0Fiy5eWPWgWegm6BbHzo?=M1CHw4YD0NP_5CAy|Ph%)Og<7qSXrZoU+Ekh7IlZ z`}`V11}TH7#3jhEL-+~4j!5x8=1Gu7ingruLS+M)@w%K^RpS0dvwGKc-1z&T|rl?~0iX61nD+qTG;viJy!RFknDQmXR7lOs(o4?lS*Dq_B; z)LN|8tke%>#}?n)V7~l8`Ny5hy{ijw6~{pPSqE8N*Ngsj0+xg0x28!sT~T6=P9KKA z^U$*ac+Me@PnmO1of>pGs_b?=|BGzoU@CXE_0c#s7UvW6o7d=YTUzDZY`5DxnwCLH z+;LdPQV(asvS74Oonz?&fODo02S!{%to5nDV(II^S-Z7YS`jcu%29NulDK`U@hx5N2Y%KcHra8i3ErNS zuH1s1hp@Ywn>G^#mQN~ zi`mfJw$IZbgi9f=Bz0e(DU=S;>hd<2&g1n#a_BB~1x8z%5go84F&%{Q@e8nJRQ!6( z2{O)WkP=hMqNoH$Z(FmvN=k;wYqO_+X;b_h*^K`j-;IpmqQ*HwX0zMS`d#N}X+hjp z)jeKoEUXNS!N$isH@cVHx%Z8|r>j#l4<4}XU(H>~YA3Z(%8pxkd|V{2{AM2v$6A08 z9mJEUdZR!fv8!@zo%B5&(Xv0w6{$bud%DIrFv_VM6QIY^&LZ;wW@10#73jOdjwI z&v1SSlu9Ic8gXq6iP}S%iRLUmw{D(Gy8h|>4apmlFk?HMwYgI3Rv469ohGq+a;Kv8 z``h~Sx&2-OL{dEfg~y-DsQ+l0M^PwOh{8fE>SJfQjdcc&HN zn*h_sD0>p{r*ve2kc2C73pN8*2tfS=TCgR*Y%4;fbyxSdp~!2Ecs!LgCuAv{JGz)}22#StlaUaX;=~axl!_o2Q4=!}Q05)M_=w9Qzay~VRT+6jIPX)abJ(&d;d($EzVYo5E{ zF!3bnQS`fwq6*Lu-jxIY9{?CZ=f3QaN#PvDamk0UymDH6P7f&!Jsh7rAP|n81q7|2 z_tKU3#S11~{iA>9kwQ8y@kF>{a+CMK6Q3#1K4s;P;CTHsv?%!a<4@z0Pd@doo{sCd zj_bIm#C>Ceuc@i2Z?(qP!~Ah~()VwxZFNFUH0O%{KI$R_19mDmtMZ2 z>nk?%)062obG242d-r{tFj zZN93$M;xP8OPI7%{3NL1i7@wn!|}u|QPWqadK3lM?w{0G+@-k5@s5|Rz;f+AJ?5-SGbqPZ-_UwO-1>jD-33&YLgAfB5%5i=Y4er|RRk)K~P+PWdrsx&nRN7*#ubljkP|%W3Ilt1pb|g+!5i@({==Wg&wugrc=!9? zjj@q_Yb}bE#kn*%MeZe)ScB;kF;$kc=+%*#yZ!=+Ps~xSoflmv( zJeE@*wfoY{Z_+(VKRNCbleeAcy>G`I-;c-pLv_>;eu)}WeOfn6^$+w}AjG*^oAs4w zY_8d~AZ9F+>B3|(ui8H>_#28ssVHBG!J(0;l=?Ius1MXHm`DV#E-lPkQw!lxUhyzt zxxBa_*xQMm(nF|0KmYf?`5*CL{_B5Jo|`dq`g9Bpk2>80;b99ba=pUm!Z9i{M=9f21nn~56>T!kdsiTPiowHyFL1U&nqhY9VqdE2Ppuyl*pCi<2X?&?g z4`W+#5jw6%R`7tvX41w)c(t!MyVhjFR4Qk!(TAjC6M_~>?D;=wKWSgft8Jo z)wp&0y5V(t`kb}Sx-)3(vN4D9D8Fvz)_n_h5tK2mD90|F?r9H|9qUM3eRf-@tn}&O zPTW!2%YvJt#&x-zH|$VOHtDm0-}9~K6kw0}0S!rTb8CK+`(wa^kK@{N!q@3fa>w64 z82;PpJA$u{>$uNznxLv<{c-l03vuT1g*Y`k6Scv9O?sMWh0OPv0GWt25uswg*+AHJ z=zAs-gj`TV5Wlu7t_d2#0Ro1rZJ+B3!H+P7$pa#(xuy8K>Ah_bQxxUFBns{3$w%)X zoY)L==-1G6`%P&WNf6bGi`@r>M zXCjLY77uC}^&2kj8cCI<4Pc5`Xw`bBo>SW~G1HoIil3S@AxSd}^evtDC9gDypLPLh zGHyllSNg*5lTR*9`t9WPL76J;Llv-<7vB^^9|=VHc$wZDMRa-6t&`Th5A61h>MZZN z60iMUDe#VZyUcv{+w`tcZ^VsjH{$BmYq7GjsxKYaaUIujPlfAfe6`$3X+P+{33pPy z%u6S|$Lr@a@7n%J9HHC(t8nDsWKvvei;AZKm0{}?}tB(x8HulnlGGl!Fe(; zk1)*yvnP`|jPdco_{A^&G=BbzpT^Aew3$(u*GgsLjFQwAiLOh89rtJ)umhW&)=HF@ zDkHwthVnep)+xMd0IlpaT4^cWHvIcaJjd}TUCEp8t>95anaii+%JY|F=FDmJ|Eaiq z>3qC!#w^#Y3sICjl^4nCRQJ)-~HGsQ!=wh8>9tAT3@hQ$Ruh#&pn zjd)&dRT-FyN@YZ_J034Qe<_}Q_HvAjjz+%F>)rYYbl-jF)%e*@e-N*|@t~SF*z}u%)lu=S}F*g zV8FVbYGa=%GAQpZ)p2j9X^kJ? zn(;uNAxP?J{E`{oXc)m%2d;dSf!y&i>ovQ)`;2$G(3jls{m6OkM_65sy>5p&y7H&{ zG-lKLHuL+QZ@+)EcWSzR-u(Avol;Rc2x9L~_jvkLn|9({xJo%Eczq^beBrt1ua$h> z8tqG;lMdQm@MM;jmxNC@VqkF80w{Pe;2*U85VnAqYqkCu9vafKaP<0G+`e_&S}q6y zY-+Ht;yB>$8`p2d&6_vl-~RR2@#|mzR`W`~@XadKk?81{4eHdu%Wsx_}SgYd~RzKv*xB1 z;r?Qw5F^T$4b%u~mzEY(-^FNd?Rf5*yK^VDHXAmVSFBVlbhGeP86(I+D{Ecx2)m7T zqhPgA$SX{j+u_EI>v8w)yoH6QXJ>8ZF>RRTy!fm&dXi~L#$~t1OIcwDD0i)@cIdTm zrD$Oan>fP48qOPo-+;N(-~8%d)t)z$W_R@FF>{C|BF5QPY&F&l4?TGVVF*bQ9HcY3 zG$!|xAZm~Cs6RBH5MCqrE~qcd^e=s(ez9ht(q$~yh36@=j~h|guGZ!i#^}~o>x@p} z3(h8-pPN&>yy7G9Yw_BIpDbuosX6w<8r|woC9g0CM|{3w1;J$jiohCG2=0AENssEN z@-QzWOe6jtT7GDO?d}U_q%+Sj`-tg4gswI{sJwv_@Cl|nfg#KY8mAmKY_b!f9{rFu zC}2jBdw7m%b50yI)NaJZ`jl{@#u8yM3ySuaQfk#PdHQ2ua44$6*PJ=GCb;My7>kL? zS@k(ubI9;^T|eLxGm~p8f~T!5mjk!}p5TLV)|!Q53j*i6Y`ij!(ilO15=u^8kZM|yC?d*9HJV8P&T!G{E_ z{gb+r()cpIPVQ5Y=6g)5ii*%zLV!O>w86-?#`ys(FkV}fM{ z*=%eYK@0tAGD*7=AQ+e^Y+6DS0c!FVcVYN?Pdb{>5m;dgamNQ=ve;&qVwaFT z#J?tbO^_@GC>!q+QJ4-Ig&1OSfVmY>8EIFH%7n(3)7svT-KL0ubxZ@OjLbz(o704T z>6y#%g8HIT>C;4-?5nf;C=s}5g=xXmBKmQ(vlkk)xh7zQgL@EjA|fE^QZwjEa316x zmuDx@ddcK%J_6}zF{GxTgLgh}-#0QVGM@m#dD$mf9QWf3hmZr+Nyxw|CNaUIuj9rrZ2 zj>cEZKaM*o-dF8Ua*rzABfp)H{^xo9eCFL3@$LK{=~8z0`ShAUt}S$nIoOMLxrKN%RkC z<W~(ycDyuXX4VO3vpR~c&J}xU9`5o3T(QL#_17p*-iPi7QtlQ*yxbzc4(%lXE{NB=jLHyW(N`A&8(}rXk6vorb=7bD5lb37WIzO#doSd#85W zIb7>i8e2yX_N;%}Oe>y`#-Ebr-p_}-*62EaZYrMRY^cj;XEiMD(^#GYA?c&7B0a%@Azrmw9+{|NZ)857>i^H zZGSIc-#CgLQPU-TS6?_s<>hmU`pfa=YtO}Z-gr@MGHf&axn4CKOk}}Dbzs0k+0!%A zap}VOc=gqn;^mj0i!0BakLl@A3k>L9+SZyGFjcoVkblXe5zy0B^0@Z(^Ib~o(e81=Jj~rI zv!DD9m)5)YTssf?p}$&)7oWc@e0av1oC zYt2Fmw1Y?yrhis2(Zt-W#sen(`Z(XJ(&uxqN~MD4mfcuhT#ogPhWZb)nu%{SJv|xE zJ@-s-RvqhgOx7YC#RMpV0E7wsDhqQ3+ERU0!L05XS7;hmDm9ItKBq~Z0}5LzmW^|O zp;OamRG(36689D{O^5c&zJ(u@vs9|8Jq}`fhcl_xwQj$o`ZfhCEdfiG^X`&aN8lu{ zdxSw)7NV?}TWkwa(C9>y2n|V0BrYs2#HPZGjE=?3=~-*M`NyfU$!o0J&u@oyy^B#u?*0MQ` zGtaYa7-qgX^x0?#&wPHH`h)Y_to0=v1a4tt3g@4dN_~;hM39$tI)5wuB4zVpny|Db1?jsaPJ0EN76Z+|6b~-x}^?Ob#M^+1uOFoUvhA0i4V^ zgFQLS4Jv)XRI^^U^(T0INpm(?YeKNq7Od002os@Wthw65e9q>9F10~UWl{U}ayFUp zw&Fk|s*#^&a#=6vb{f00c&Nw9?0-NEjf!l4K0bpZjV<>PyacQ)=pq;o(!FmnQVR+nQWB1cTsUc$Un0mA

    54sSFhSEBRtg9e=QuMhT&>l%DWaGG*1uzC0)wr@%>lrPRip! z-*J!cI)bl`>$nFUI7IVpp;nBEGm|lO=5)+z5j!Hp%xby($U0#=UlEW5i=~f_jJ#$CU!rR zIm}gyG4e-<#ts`V8oU5uv6j+5fWY2C*rvRE z>A3vtvswt1E%0NKV`1(-P@^OG@~%E619g&?^Qu3@%`PF$D1e#59PGs->B{rYltpU} zNt21*>6Ps_D`Fzd)772{S68&ok}!<;gmI}H)^MO-CnpafWJUqu_$S}ib1O(Itm3rp zt&OHIzV{#RR2M2iHjco%RHya=qFsiR7VoJeuk?<8UD^3{`{peXQP+>!qvJZR<2vqJ z?!HmMSL^nP-SNfAgZ`UzUnai?%l)L@jJgNBe(WE7-}c8HPoMFvaP73)SN$A)`&#`8 zf2j;E!jZ>u`8@w+9ch?Nq??EPRyqCq@V|D1&(!$|y?##2OCR`jP<4#oiIG3U~ zx?az1@3&YqpsbtcZAn~9fSx~zJ<93$i73YN|@8XX;t3+HF!%bI)9kKmUuL$M?VYZd|^6F{Y;`qgX1Mfo~y!N(hrL3CITH-FM%NpZw%| zaplVMF)}=?{Cc!rfl1GrL+c7?LX(Z6A7R?NLnwZtv6D|d)^_baymxKUu7ve7_j<=# zNPW;|(mK4o(&xSZcqLd6ecg4q8_!-k8-M=upTu`we<7ZK?oy1OIvqVoyP(kzx1+hS z7>kRy)UWDG)q{1xQ5ky>xTrk~ioSE_YQzK&|QP3I-Aq8tT)@ELl z?Q<>|^nKD`AU$Yl=xfS{^Od%dOJ&w0c^>me0a}har+O#YIpkhf*BhoR@AN~P^PaE> za&RW)6^4Gn(I0Lzr`JkX?{%Ru6)OEz%Efs7m1p8d-+v<}Cx;@PO?9X?$*XQEM^`%k z88|=yFf=l#aWt-RR@NG_5&L^hZ=_62UCa(5%tE`Wt`VU2=wVks4AM2NW7k|>*1oL4 zC?CxE#Cl3KB`%IK)3#`2aE>15c=_zETp{x6uY9RLa)n{ReJwCm2BVhzSWhJ_6toL6 zQL2=qR;xuX<6Ft2(bB7NhUVthHfKWBtvNtnXa$wvO5x~dEQesdg?^{eX==I#JVW|P z@I_zI_^kQ42Y%JwsuyL)eAvXqOq@M89n+`AjbV9&Q}74S4r0DR+oq=e93P*sW)t%U0*YcWnb_OWT+wK5MqPNAv$EEe z{;tY}_6{Zxx3+gJfU%(0V^HPNGXgNiK)J6LgDU&z=y;5bj79&zpiSOYDg#af=rBJ+ z@K`LBqfg-x4mTQGHZ8~4LPHTNHhq;^jEzp%q+_{^wiofRGK8j)a8|e0`e+(yp2)Ot z1><;i1x>NJn46o6#igadauGtWQ`4uF7n`(#^P|GC0U1GeZFnMv$4*5-d8igooLjTV`Fte?T(OhSM9qJ8)`euFmlG51)cNrN~=qF9u2z#!EQSD3)7DD zE5ol`#7yW!6sn`f^_iXn^{M(teTyl_ZqYl?F}Y$@&*Xoo@sYtgNi0SF6n4Fr8{=Q<&&EJhXb9WV2kfylI zKXw96a7BC0a|iRwgI~15bzH~EL49-tUme$R$6QygEBc1|V*1?am^pVgY9k=xJ|XsA zAyT1v2xKANBw*0AETRlz0z%0MSrZQnWOjwH+s5V-G&%0Iw6`Dtn3P#Ku^R=4@NCaQ zFebM>6DUlA98^iVAbAJ{4sJ!2oE=NOg^~#cgkKzR$=P7rBIx%-)FCw6WkD=Le!HoK zJZkgXJ5gU1;jqfV#cA?=`rKiRO-{u{EhL7uNT>dZi6EkjMwRn!Oii%K7O=jlPdHBv zAtQZ;hftv}5+TPmErRGz^5EiyE$bVlYX*!p$LM=@7t?|INS~9h@*ungQOeROD_y5W zq9RZ{^>XX9lXp7p7jkLZPCH8Z#B1m>O5mVg_@r>;MJ)1Z698?Ymp$QH=@KawhZ=K9 z<>d@H4m!Pd?V9a-@2QR**Kr-!aZiE!)(gJU9PsUMl;w;1FY1W-u-JZoLS83%{e1SF zqaSAmZXV{pBIo4v z^Pqn)k3=tVlRlbxBpL|vg+7H*$9Wi-CW862zrQ7VxI3P`d@jEC?wj%QE0`-BjnR=> zy!_JhF)=wI+7Q7OO!@zVmG!P$s^nuFV z6+ivykKz}<_>=g~Td&14`gZ2bnK+|3XV0FE%aIeRr`3;m*T)YtQ52Ho!76# zyYIXilWL>kv5Dx(vooE3h8{-%v#mbDs>P1ln?4csto2!!z9CAbj}V|mH+|LR^HGLI zPpR!M#N~^Z;-cDfbZppbsHNoTNTN)So(&q^_Ve7`=x71Fho(y9j7_Zz^j_VituTK3gi+t9~)(wed!jm_1luP^Df)|K>& z;GHvXY>h(0#aEs5iEYmFOFsjNam?*2y`QW!ueIC>EkSlhyi$ zHbxM4)MKg(j99g;JOWMx8(TYCd&8_&nrM~edW%V*=e(&6>u1I|4mgqrrg+b1hs#B+ ze<&tTO?w=k(-@qcIUVIn$=anb`hi!1CkAlF!e7w*LB>auW4BN|Q2;f93xKXDS=vCEAIw%<0sDbGy6|Kw}v}6T+KjgR`&T zEip#X_G`K?NrSoWfVB0Vd9qvccel#4yfhzcf*CZ!$j4gh3Jshgs7G)M{)E?uKopHV z&S~ciHs-CK9^p@_6g%FS1B{l+rO1^Bqg)+Pe{#ka0@bo$s87iuFx-p!+Oo=5S6c~} z3ie13{Feo;mHwJwrcvKidmmVHaDINyrZ?d+GH;?a3vR?*D4MO^xuhMB_LlLL9nZA8 z<{yn81yKF&Y2g}YnfFEC_sW;lp9gA>6~lLraX#(0rTJ$IWZWvhZq@I5Xbr0$5k&Xb z24h=wxOVl1XdU&pXgg+A+MbLllW9ghG1l$;4R>_YaUJK`xg+@MxQ=VNOd%V?lS45v zb1J50r?ns&iHr!UJt62rAyx=-#0^R4Af(F#sQY`n3e&CPw~NJZMnAgQ!V;jKB;S;hBDS zV&v&ND94na-|*RvH1v*LNjxcShzfsKU-N^AIbO~f-`dAuKkU2rm|9J z?x`O{+uG_{eER99@$ttWd$(H0bzH}F+*9DbF~QfVQ>RWeb@+K6chdWB%BRKPz2`6L zj;HY?UO(yngg?Hu-GlK?^e6pkKGny2o_Fo=U$fUwD#Ly6T!bTk!mAVgSLK}FgNZ-j zkC*phUO)CHeS2d6U;*&0Z|T~4ZI>RPVxYH7gXsw#Sh?667tWoDS6_cArl-fFTF%Bx zS1!f7-+MDo%}n~-m%eg7_IJ0uAqveMXm=RY+fB4jnr0HgoL*a7jyi|Y?{b(u%&hJh z85#Dso7b<#-0fT52~QbnwE+uLu6^=Bz|_y>vp#g5UDGgF*`1BX3CyX3z4h3tuPNQM zyO}dLQk^o9$!k53Q<-`>CyWE$`401DEB1DidGc{Ysp-%8IiP$`&Myb-~*4u zYYL{fG=_jvghTog1+_D9k2R4U!6xRk78Y*B^5UEYvA`4zW*Ev|Bdao`$66M%WtbpI zVf61lNM{fsfC3gUnHXJVHAd3BU<{@Hqu&UxFsd(&L|XuFgAS-?>~TlGrt8D}XXAXnBhDA`t=J^cy1zdyKkKi(p%r1s#>Q66 z%`L|K+)~WnU67wMEcFi{T*?dQSA5nYn+EpOKj2|BYv_B%DMC#^tw(V%nRnyHHHFPv zSjO7dXF;jI!GmZTGOjm;H=0{@t&`E7*;3eEw>^R<&IFs9Lfd%6xZOfh#)M#gYjfRc zjgL)hybcB?J=s_RPTv>oqcI7du2ie)+@xiD`_{EsTfVD0B^&`ifjJP|TqvgV#NZX- z*>pKHiLkB5k`SC zc;BtDhj~-YNb+nJZz$-Y+boZnK(!U-8;OrFk2KI`+S*!=ET#f`^2TkHq@XxGy?qL+ zc~|rMPIFa$6J+VS+w`H@uGw5y8}3G5wO{QwXe~0%9z@HP@#?vhx*USD86W%ljtNQT z@Ga$=)qKpEgc_Us%~)SswXn+PhtX%-+kzYQqiBIbL2z-X((I@m1Rn^15d33CnKQ&N zr;Fw_LPvO0@c8H#=J#YOGatoDzviHt;fA)}*=|I0b5&_74dEy@wzKgBxI>5po}<2b z#VrUH67B;}iLO~k(=nZ02p&P+<_!h8qSEdbKHsuNFEkNC)8(ZlwfC;-hDKo{78V7E zYRZD(g1Umo!RrYBb_Dxq!+T?a$_`#Z`^-mm00Room;;VI*8)R5XqD0TY~)cra+nd` zi}~B1Mtv2{GooQ?7p<_Z*jQh*U=f_3>B-sbWKHb@U-W|yKGIvXaN)D6x_FSc@TccJ zzeq63-xqbqanVVx{r&6qkK;~?_xteQl>0JyLUDBjUme$Ra@kTg#!ipMnTzLRXmmJA zTJYt1waC?iD(wqJx!^x`}H!(!aw`GbnkI}@g)*}7M364i4Ghr`4I<${1u zC2c!Bxsd5L{iGLE$?^GD*7Us>)lBRP!{RK}SKm`G$2pn|AOcdNj_Z5M<=Aq%he5$E zp!M~Q_~fIH3@zt>E+|b{W`p7*au#w`XnaG@54VQ{V0g`o|qVk-rkZ_5@Wkr`I(^o4iOA3eCHkeaQ(e0r$dc9M5Zf@RXVRIRW zyhCF;UD4N^VKFm%Hcp?rY=+^176LFJdy6pPGNRQnLAB-eflaX;nLxw>!0iD?OwowGtR*+L+kU_H>&ExI1G9bXoQKIiJu@MC_@WPm z&m#0f)6E)a(0(}bf*GH+NwAk+dpVwa=AyN~AWvb!ac&I#0L@J3o@_PxY9sN?^Uqkj ztW+wRA-1@<==8j?Oyx>Dx(_0!I!ufW#ksSmea09j<}eS1768m?!odJ-Zycj&P^7Gv zEGW`*8-CMw#gP}KsE{LM#_iX_F8}C3W*6# z`(qjm?GWg4)?oVw8_aCMG=dtN0rdvXJ-q{tb7lft+e2-? zzP1>v9#`!4?+PrFAW%!^q5)IgdRLK0+fn_tv#Bf*M5rxPUQ8&?-?^!FXhxp1bgXgH z9w#&wSAE{{G`b%SY3$1{h`i6~=?J);~HCa2cnS1pWxG!xY6}~{5C68$?G{Y$4 zuGaUtq!FRKG|aq?#B3Yd1xI58&4$PXrXA5J0X{J+XH5kQy>RU{HtWP){ZnR*lWsJU zioz>>@xqHQ#Vaqr6a!kzuB@*4tYsL-F!_Ol_9jX?F0JR11_iHxE%O3sRlf1w?ZIt= zv6I~Aee>1x!{>PS#l1LR)ZLqhxW7NWc3yU>8hC>KKp?xSHS3+ZIcs}?n4}SNa+VUW(`i`~@JQT7-Ly$IJUtfv2 z`P;E@cisYx;gQjpnwn-vX+GGpSv)kcm;(rpFc_^vO3fHzUP7A;_~48v&Wi-+fpZdH zV$a_g>j-EWKRbfgY`&oROyj4w*FwBrl?M}dY}jB7B9K84hUFi$wSM`_U&jCZ+rNw7 zy!U?GxsBi%As5;@h3KzURK6bLJ%miP8guU=R<8#JrzEHEpep7W-Ik(oL zsCnMzQk53MX6oBl9n$zODW1l!=4ph!8R0mD)ZiNMcG8w|a*Dbg8*3}ZMF{%3*?6Am z7Di{&K+a}Tqo=Ak!ZQj(It-tL9}#Y&Ig8Nbz~)fV(Av|ymCYcO zqYUH+UaJW15Ili{(y;9ET!|(X^+HgF=2V~B7!76myuQ8|%S(53)wmZdAkbnwBmp7k zw4qIVm;_ClS2$aYP46B9!dLrx$EF_6F{BaDC^UZDudA%9${%_|utZtaXTY2{%CiAL zeGA`;v%NUe4m^$dU$hg!Z)<`n&W&R{fya|T53N2-Mv4Yeozaq~`4HrBb}DUmfIv(2 z$mY>J1Ak+23e7RWj{BI+4m;}OB*+4W?%cX&4K84=SgN_bwiqj#&oJ?9As;k?aB!tM zrkuCq@BaSp3>OHK&1s_`YI9g!fFyMpc zXmx>QA#fBl$|4>xduSWaBEBGIIG`5-mECSk3`}fHM7nWWOk_+znBqIwWf#nzCT@0A z3cYJ$vAt@2S5y-&TbgK5QAhiX1u+u}3vw1c+gfmMYtg~Nn;jVt`w%X>TRYL**wkdc z9$On6FsWJKDR!u9v%~6*H(rYo5uHqG7G}vqw6j}={-V8c)R#p>`&p<@FVn)5KZJ^y z&%tCzhDE5pTd?IY2+Fu8{j^}GzkJ{7S3GDqE!xvWOdeLF7jWsdoZflzeZ}W1l*lsj8=VN1S*|a8S zcO>R~tI}wGb?5a>ML_VOGNK7%I`NQi1*KmxgNgP*fRvcsc$V-8M?}}F{Ah_mbGC?0 z(|MwZb>9{S;K*0y$Y;IAF_RFQQ4VIJ=~m~%JJQd^;P6Xmr=?YDeB+nqb}v9Pe<^%?mjr#rQ0+rhx)9i%xX z_e`SG5bC>HUrB8^Zuq7TU~nU#E0?nI?z^v9q!`-&GNW z9qw(s)XBAu+Er2psx`WZdqW3Fa)MPeQj+o zuanS<>9OXY&7%Srt#x3xa7DH-pgPnv4ls?U@uxVf$9uYSf}umLeW*C9Q{KY#;gaCnPXGY_^hrcP zRN;vj8lJKSA7_xg|NaNDy0RFxYDutKw15nJ!Fg6}_GIY>1KNje~u>%fW^~;@#P+TKFOspZGX?T(>w0zKX4v6wM&f%T+kK>HO##4 z%~~TE;RrmEjg2*LY~ZY`Qh6XsX6P#|rBmsvMX6FVucfiEYT+*DcyWFf=O59~Sm9y( zZRqp+?O^iM{I6lif~zB zw*8IG$c(eb#!Aa19i|)iqgbj$|KP9%5ZT^djh7@mMliCzx)|Hd4YvV2q^!mh0s;6$ zXuo~%;fHbi)}r!ZPTUjT$g52>Ce&UClsJ2<+*eik^2)mz^}5Ep=0(>0j7_xV3d*-o zC~N$2wiFu2d&1%A3_vy^&W`JDP&FaXTn9rwrWdU8E6FgBQk zUZ2~-Hpr8a{oWM_#; z7=>&Jh9J-o7K*-U6F0OAT6jFu-VhUM(GNPGpv{0ayBc~+%O6j!)YbiQqP-sy&Nw}Hb zro2f-VdSM#OvptZ_z<)CW1Pdm>7(o{n-!WM?d^t3=P(z(AyKkgJla)5FGie zt0Fs}w_Ij@mYveR)+XIudvRXtryu^{o%rr|--uJ^FUH8&Ow7(s$A$B!bKPcLg7 z!sbQr8f{P8396MWp5#3S^yjms4t8T)?fRF0`SbYy{KvnHH{W{0LPCTgw8zZpsrb$t zFT|-S!9MH7UG<4zs3)6=oa!??IvnTDUx?RUdo`|Hxe}uzXrN$uq`SrR-mw+~f~+Bp zq1Rr!66eoO3yxJ66$hFhZMdD?eR-@vpe26><= zYYogfVmn)@ueJVVydkiHLCu+ZW^m)W1QW^=>nI4l(QLzl2PWn)F=|1w&l^f(inDZl zej3bnRUDxTX1;84kxo-PBE)K&UBvuhF0XipNqYoXAYIDHS!X*<&WqA}#MfX2sxXL1B+IbPrU#D~_J)a}}G4g<`lckV~uKj>R`_Yyn`+kSWa`6Qp5Q%SdvaE_yE zdkiJv}x!c{&~3cOS5Gb~#>Fq@4^U!Mi5+#~Qo@P!Zw zfi8mkQbq8iIbnHmN%PLK;R~Jwf-+3)t}bibC@)}VU|`rnFV1c!Zws7+*Ep99K|S~Y zEzhFABUC{!z2~{F*=WS=+qV=q7tcQXOgwY>Vhjp*u=xW)KVt=<4EPVB$sL77!wk(a zG|SMc@mcY%3+HobJn0_%g@dm`8kqK@{kxfK+y(opug0{(7cIOPj#3}m)|i^@(R{0U z1!0%kAfq|i_(S0lP~Eupk@{*r^2%>zc{Og{xaF}@Vg3des0|pe@VYX2&gVi)4Z#z6 zs$P2s=6@lpY-rqk@WK1h&^*sLXl&LE8^ChX76RrNyQ+&KfLGFHl7j074y3AS1ICux zb3^zi9|J?O8MLTvr=mYO^mm@2y*O17)D!nWs5Z6cf$hV%n}tI2VEbnqUc<8Ouj#vvGdb z{_dvWeJ(cYm~mdWkdVobaf9V3G|;FkW+H)C=1evWa2^{p4fwEEIJDHKIk;T*oPZ`H zbtSJ}HWw+bGIKj381y-Mhez%qO$vKH;1t`viq8ZlDgi4VKw>d9V+Vxxzc0;@x0-9>}1*# zfwZ^1D}rDvHrFtP*qRicVt3)v<@mu5eh`-~UNmC@1mCVzGBv3M7KmRBPPvmmp&(yiN0fLSi?(%g8P(vuH;O|I$7fRjo+nI}+K9rHPm1_%DsW%#5&O*0oHz41YpYzbQ{Ve!I zU43C`$u^Tey?V{{>$r~VxQ=@Y+&3rqn#R=y8+UqCzcBym^ zO$5X2?YCZu*I#=f%B5a2qF{QIikTP~s719lV8#v1N6xfeSzEO*3mUCfOJ)h#QNFpc z8dpF0C~n`p8JnA1-ay6<;bx;Azy8&~nQ2(5_K6}&2T0b#+DIlUXV=?e)E&G-2eyEW>0WJCu{wNq6itmSf@W?Z6TPjMIW>|J?vWLA}21 zrkO&}|1i+0yC_n5c6(D6;^JZ0LF2)&gQ0_C$?lhqhE~aTb5-k+b>kkJ6LOpK1k*_L zEP?}=es2E?>SJZ@l?dyz5t;=w_lHEpS={{`OYix^Pl}V-hKDYICpkBPEU^q=aE3uyLRf2o?KCD zAxt&(N3qx^`W>bro7}V(GQGQ}exprcAi|K;6?(ZRuRbcMoSX-xc6Qt1NttWv6NGQG zv$JvOnP;PaU{rBo*rH{$t#yLh%bZ_4{e(8cTKr0Ib?45UncuiXey8?L8|QS@6XZQz zh`_Se*BgKG<9FkyfBJ(sbMACtesWrE^zutD#+z@ejb6MGH5llE5d@s@x~v!>Y6yVOsNX@ru% zqUwvL1~8@aU?z~WwKy;DPz#~nV$G&RF=a+%cKf4QnZ^R}%Q{YLZq{j8&ePGTQJ$Dw z%&Xj8oCoHEcCJbzB#reb6e)2chdbt{3@lYL+um{J;Ei);CsxrApk<4iqH!o2xA(pnS5_iu#!yO zp^d}bRIBz|u(Y*>K=mLAepGgNN6Bnl)|zC4gX6-Jqmj)Q)t@~ogT`!gL;cN0>MhqC z;clq0PstJ<`09;2XgV?Evls*4i4ZwDZm`VT`q==1(1s>p+;w+p4nUKd!gqn6;p?fMJqT`u(^L;k z7dAFGm3EhCiT)_`4QfCj9A}In>{L5y9;YA4i+=EC8?__+q8;_wW?kc4?E>7`T%q8o zC#Shac~H*P)w{w42xKwYm=VsaS<|Z8KdQ6`ErdezwxM|ubB5Fdff{hyt@0zRZK~}M z2oks3f_XH|1=pJk)_{gCF^>^px$vts3e_K&#ATxa?F+{U&D^rvG8+enJ=RF;$+O|0 zt8U8$B?UtGqQ2 zEG^uLyYn{{CT%974@jf2u@tLIbFFfcFnEahNcj*}^WDIp#>~i+#?4Ut<~Q%f`@ehN zT8-2j{6IKmn&NWX`un2pejN18xi6dVaUA+}`Ums+Cft|Fk6FJX`0BVnI>+QaJUtd? zo;e?5lUl3^$?s~RgvmjK0{4hN&3l^A8qJ0#k2H~j&=Gzy;IKh!qJc?C6Z)1W2!veh zmg$v8m;w&Q{;o}GK(Gk`XGJ8NDA9d72%24Q887l7W)W*ZOf%td;3q^EyP22=IIOzA zzu&tg*uCN%Y9a_A0Cq)SVfqlEm$iQOl#YnF`g%RK>S?#m)9t!M)Ln|Vv>=?Gp7BmT z_m@9)dtz=2tdfaH76f>GmrwH{yK^BTM1Vq^>7LzMEQTyJBMp5MN>x-$W8l*w0|ArU zmF!56yjyvacKX6(3(@EYz2~MKKNSQ5GKEgxd~Llt)NMN3fEO(Hc*z||UcdS|Ixozh z^rLs40Q`-Rd?$qJ-gZjU3nWL$2|q^8xwrZaK@Le zpXd2CG0sy9Cm;Ftw`1P(j3$l;-+z_9?OetazJD3-bWeES_GZML^zJil(JtV_Jz?&9 zrJwf3kFUdj5vQ0ZruB#Fzl>|gCLQP}o}rJ*#e97Co!4Swe9-hShsGmN+TO+t+qM~! z2(9kU&zqjXG!Jx6n=uHDzO&bi#k+H6_zd(9D3k73ZJh@*K0am!{r1kT8FsZQT1Mrl zRH|lDqD2CY#HKQs)-Yw*x!q>|vBNje((R z%&0A4%+JhBM6Fh_z@}6wnijVJj&km^*)C~6!0<$1lFMh+cBLql$1G5qp6rijE}xI* zpMO5ioIM+-Pfy3`+36S>n^ry}QR{1&L^6G@@*Z}JPIX~b8oh&|s=k2{2osmSf);08 zWT7eTVY*f{v94_RG7YbP)lgS%_>NQh)Ie*&jQhB(wCPV6wlH4VWVjvOn5(q55VeJ_ zZp3@<{U(0>t6#;+%BuU#8hGjxzI*+UilBFChrHWgZFG8iG=A~(pQz5K%n-y(7`x#6 zYMik)9Myq==qs~6(RxMe&Ru<{O9gPey5AJPPF@Yr=IQAY?pgEacI8EZ3scH>h?l3wBx0VrngE z39#vMZ@U?Nm5P~>oN?4>)V+3PjKLIz=}f=Tb!b8%2u7=>QYuGp>l`+i$GJjH?OM^= zS$Qj;TrUh%G`@g4)^Z545IUd{nM{jivR%O$%1J{KPk*Y<_cvp!u@cSAy1Ett7Ft(o z?VV<9HrAC^I@2o&py?ylMf+Mex5g4C)b!0lJHY}17Bh00uYFDtWlC{;cAfgg%ym6m zYg1#SCtFa_*~r?oNjsSF`Ci5aFi1S*0iZgqZuJFPkmJI8!WGq8WYi{{i8eYu8fVX* ziOZKR#@OgkY}7a6_S{@FnoYrb-kK=_HP?ytspmwcXz&8)4F4*t^20o(^Y=$!5zqK$ ztOHMiO2ep1)WXTMso|G9l4}8S8~<~C(6`?|+O@;C)A;;2E;V5(lVGUWn~B$7dnsOe z>Dd?==~sJz>keb?&h5BZ+Lw@t?Uu(U4HOhU$;lm>yGYMAr z&1OMSo?K_eA@4QDjb#=E;3H^MWRSj55eL7S8@fj|q*uDhChID2k%Y%F?}_V(_s z@lv(gXPy!K9?}~c8I8fAG2z0R=N{mOO}RcVu({!5FW?)w&E?@S!J}Z_VW;>l+8B_t&`Y>7iUCj{)Jz zkr6ca(z#}gSKyd>)HMd_OE#rrb`NvH2WUO3&Mp@lI~dFKr^W+)0j^=LHs42Wf?y|Y zmY_Tb=06oH32%8S*h7nYU*$^L({!5!Lz+9l*J!%V-M((vU?WUFbywf#yosZta;V+p>QiFjT5oD^|8Y|nI%NnDf8a6nSwMTRt!c@w~d8-A{S7`Sm zFeJJKvVzTSHQ@!%uZq*cTKdQ9_8V{smwh$m_l)(7kP zMf{g>%(xxFSI7NPxo)jQ$Fx{G|J*Y%c52GR_W_d@xKRTNWSSOxY0_lEYqA4ONR`Qi z-KOklK*KAkgA2iej5YINUm8IcJ3_p>r$ta&U07Ep3a*}%6@v+f2?GL$^f!g{ZI(|S zRc&@uAe`9T;E-q*6TKo7`ZZyS$SY~G5rX%mEW(?GI$=2!a(64)K0g$ZhA^zL+0a5j z3no*JPq#aN;ZnTuo$n+DhT4@Xwc8Y;0o7~T5&{6?gasx92>qJ~IEYkK@YUw}L*NK; zr$hh%=iy&Pg205>Rce~Z<(-hy(>pI*S}>CumYjfs_xBW+GCPQF zQw-nAlL0V;G|LMSJ@btSyiWP6?()QC=OlTM7qDePmYD>+<$EIFhzOCeDY&?C<7T|~ zyZ7Vf&AIfg<2tV6I_}%=zCn$z>A!9v+t2Y_()B_2nV@+7+Se!fQzS)uLQlM7_b2_4 z?nC@ZPG9t`o#to#NiM~?-+wmd<9SED&*|Ma`KNjJ!Mc3g|M)-NhF{$C`^Ep%Sf;hP zO^HFP9Gc-XF)|S40%t#Q?nxm=h6l~4`5*t|Z{u(O_V45G|Nb9hX=zC`;ABiroiame zv%VQOu3Z(ayB@c0-iYPJyD=y_d3<6r5Q?$8d1Q3lrVRW0hhlYg&AZ1rrv-CTZQ2_% zRWS8nEW!}2_76uz;Y*5#iM@Kc(K)34NS@*q|4eu1XN(sID+=i^!AH> zFEN@BjzxoP<_v{7NR?oUvSsp6x0{sWM~@ zE|{)noO=BO6K*q>7jD>8BRnw12|_Q-B__wqRIX}248Z=#7BF#DQMh7@S%y==RAvsp zCyjiuqG;@%S6ceIzq_q!QPw1+L?eye_1RpXnQ+A6kbblyXd46}Xj4%4p6&y+gD895 zqs_y4Z!oZFTh0@K@w~UcZQ)9)yV~JU`RTD6flMH9l{-WuPH?KSojZHp!l`T5+SU`$ z2x5a78Xv4l6kI=dpmkd6*FjQYnYxeQmKR2B7%dB^%bpCH)42XNMj0)?@{n_g6b?ZN&9YKURAln(>ZltwO05h4O&O4TrGW13|-Ff+gA6Wl~vbzXEoM0R-G=)W6r~-ufY$P z;>zcQnSdwNZQsJK9jC!sk2+H@D{C>9>{xTc90zXH7h3z%F%~fCAM=Kr>r1h|wyeHN z+A4eME6(HYp)v1&4q~N-@I3Qd%71J{_f(_2{UXK^9T#g@n z@9nsJ>8#qTCsvl1yg2~$(F3kg+cO@~++_0rd6FuyY0EMi+h`S`jl?>U)oT*QB_=cN zNQcwsyd~kb)}=n`n%1L6;|`zJsSc-i#QQu)oJTpnwtY%Y`KbJijs99G-hS)Vm_3a~ zXx=;#GP3UoW0Ib6rAJ5n7MlGdaQ2LCjn|E}1<$R``jW=cyztGk%Cc{M8Ctstz=2or0OyAl%Vps+G`7pe zZ5c6cdaECl7ee{<)g_;)M>{h9m5|2^LL96rCEgoCdyO0QO;5MV<@q%6nRu5g zRFww;P>o~N8-YG&vt^5zA4E%+4Kz*7Q=73Z+_SVeA8YHYK4)%Z^i))9V-^}BFlB@L z0cjvSGwmRlP@i@8pqY%|OXb%bM)}ba>@D_rfHmriu{8g2tgp}NJ<4<@`W17wD)?`C~ z=EM??LJQaDfGQINXJ|WbYpnG5SL3zUUW!*2^Mp)*Odt?6oY%#~fgo$MzM(r2a{~k3MO5z70#SKG1h80VH`$gJ zco4mN?9@>@crS=dpkNY(1tP8R^g2}MUwrwc_|BVeiVz)6i+kF*wHt)?wIEP!n*=-% z$SJNDn(7C_df_8a|M8A*?s$5MZW3XT1WqY31Ppz~owLz|O4vknafhdebmvJ{Pwk9# zam=H|QVQ#L@-DZYxFnwhqI^v$wF1h!Yyz5AvHXs*vvUyw)amGVkFuv1a@0v)&yMR? zhlbhJ)zx_a{rBTHzx`b-EG#>8$8}uCb=*_nzB$3y%*8E8`x_>OM9~O4^r}Y?Kf8<3u+Mf5i`E1z7@J`FAp8V(1D%^43zHNWTf3{s7(?9sf zyDwOmFXGe2rl--TKKOF}v+3&XgMl9E`O}Sm6Ojf@#ik`pbFbK>Pl27kqRTVc9?|Cc z_~@fg;vfFue?_HSjtdtr#_7{%VrU5ShS|7v>t_6?|KI;NK6vjp!Fec?6BDMDVTQ4j zo!!fvqk@nO+MM0|wQ5aa^Rc|V94kx9W;*s{(q^)z=x+1x7Spq{a_=UH!j%(qG+(a4b$a`=7ft51=)5m zb`ss6gj=)@-x0cOMK?ky-Z?G|a+dJ&-7rsKF6tIWU6w=k(Mn2!9MXaQR1>JJ2+KNW zFSZ+))8epygmp0WT1@xD&Dd$ID2&S8lXm#)hY#ty%hgJ^yVn|AXfmX;l(1Y;kF~WW zp9{hUK{Re`29ACv>QTK(k9XW7)M?e(T5MZ-4Q&gZjs}p@QGcW|k{0VL#TC53q(s{Q zhAHQhb#<52k7xw2qrE#atjBZ(#&&i%@1(Bq=?o^yM0{vuuMcQ5wKFE{hyvsDaKGV$ z`(Z$*_G=3*DSuOOx}sbekBQ0Cg43?Jdi7H?&28?!MR#Kv1g0|mcSOhUZwm%6&X>+9K4#f` z))`tD-RfUUbEs3d)`~EjH>}A}=^M~Hiov-wSR4^-3C?zQn$f7Q#oFqUJZEyT#?5IR ziYY@HRbxn%U=2mv(uSPRv$eSzH?Du8_pD`yRG*UCL~Ge>zv3u=m3OCE*Sbz?@gf4b zOzds1M}2+HFh#qdEdf(}Uw(UYMfu;guz_*M{zcY3X0~TAhqx0f%lfV`4Tas_PG>r$ zvy75poi@y8HDZNt*4CE24mX@^W96l;awGhrUA3-aZBPHGiWUYNUTHrxbJC_t&p(7$ ze;}B}%p~<?v(X+6K^;*I3Xv8Xg&s@zF~3Rr2x1 z>o3PU-+eQldFFD=o}P}uLG_owW_^7_Wkp~YF*!LLZ@%?Py#3Z2arW%2H9z)u_oKg7 zi|JDn)*^!^(QKr%@$3L=d0;hNlW#khmp=pR{dCAZml8SY+r4+K7Y}hqpMmq%Z5xH4 z9hvPph|@FUF*YU~UC6|)U;_aTxO#YaIQj<$1!JjCn$2x*^yGSHeoo=`;>DNVh|{y@ zt+ledv*)wH5NM5$O?ZA-US1L$G&M%izC=5UvysxKSKu1QS{)c7k9=NzruPV;F{@ka z!`vWdP|w?!+*9Tz)V}`XjFab{jEme3v;4U;UNgEy$<9T1>kmEE`o5OqB zwt3FEJ2zu>dC`0+G`%SE;=-KpTqA0lzxt~E?qjr)>zkX#iFv^yn|>J&;K8JcoQ*z} zxvF`QzS&UP>+6dx!5ZfBG{&-=FP~HUATUAWOyO&T=8L8AwV%udmo=uDQ>?X2O99J* zakU-CjCA#|c>u3u4%lp>He&1&R=EGh^^fD`jZf5;8>+`j+_`-GL+DvML&|E|1l8|nhZV}Buxu`eec}H!y7|V&^=& z3vXY0-y0$@Z>g`UN7b7>7;E4fXqvRyT=0w;N5(^ejVy{UxbQio!nvt~6;|^$0>E66 zaRnSG4Yea11L!-`3lvIiVS$<2oQh%MxLfmvzvb-$r**IUnW01|7jy$NkZ`>hNI9K65F~ zfFuWNR+IMPN;3c^OIQTkM203o6B;6nw|2Ho_;MgBo=KENG@kRhu(u1rSWsMcQh>N2 zcF+d1z^jETOdM&@F>!mMP})52ZnL|vX+f3d3V%b}i`_d+eh9M=sP$^HN~-aLCeB<= zm2FFe9*26OdfeO;(MMkVu~^w*;iWVh10ckon$O3-Tw^Rnl z)HA`jrnFoDzP8dLoZ&&wsh`>@%DYTGdPhBY(TbaDCnrM83##1j+7 zPO5yIQKmJY){?9}>0?2R?^$2&Ydy$@KHATwA5~t?UqL7cUa(*-hgryWTT(aG(`y0R zn(LvzBNWZ5U##J#FiFdZHp4{OPGCNCXk@}?>0ky8Eiwd}&QE!xEpbaQe)IY#8cWw> zO>0jWx;_I3rmDiFx@hgJK4gx-6yT25%6IPE<_K$>S>tRa&VobBFTuLt@nAP{1>m!y zB56IoyAewZH)C~WA?h2;ap%^xxc2D>dPbO~@ic!Y=1Fr8^I%Fs?Pbj-#@%*3ZeIIX zVQ#2)2%*ueqWuu&cDcN)(_!q--@Y0vON+)I2q;vRI z#tj0n))+N#3X`cUz&%~UM%lbzF{5#Uxv!+P!~991m4eS8+HJvh3w}M;NSiS2cYD!a z%f-lWEvBX>qc%98e(I00iRrjxbBJS6t(IeGuo{DdmH5tgUX8!_i=V~2-+MQnxqLaM zCMM;_;)NHUkJn#+C0>5{#W*uNYZGyt{YL*cHaEORB!B({Aot zJ@RFYViFSG7V}rq5G$M4u(q-k%S)IP1_va;3&JEegy1MsZD1t&yg8ZiES8leSd zhm+<~*rbw3;=QIcZ)2=LGz6!#8=6#{tq5NB8Hk**sWIvCr1oKx54eN5jX89yeoJljJH?F{ z8%M)2BUsoAG@YB){#Ku``F*qQIV72`RFws92`3dajxcq3X!D5(Ha)MBzUhsO%GR`C z5wo62Ll{9^GP&8Md6aY5Y%UbIqF)uOw~Ww>uxw~RaJ%b1z%2Cq+;xvH+R*DFwE^d{ zqN&IjvEl&jYfo8JXZ086e!JBlY?4TGH1nHq6DrRv64~(xF+)5E6z~27aq}mn zz# zA`Z1|COC)(7AyNg{NxQ`&n}_O&8BIPr`17_efN9ckMGNKR)Y^1Rog)j81Yg$1UxMd zk)ZBzA3;#0!!fl;M+l~Vx4`PCe?;E9Z6NbWM^_q>G(_Cc?}P_Vn54q}7I4Mbo^@2kmwT5?D+iKms zO-xt5@|3=D<a*5UOy-K69W6w6aGE6&`W=xN&SH^`Z@mfOa8TM_2k~=cmjW7 zB43kNj>jKQ_WJpKdfZ9v^eEq^W7_x7LTx4>=eA5vveD}>7Uu87=EhnK4iCoY*r@20 zhDe&UTOFno=X*SV<%PKP%yTh3JZ1(ROg^+z*lCR!Cd?tB#c}Q0C)UV;hNR&zg~hoo z>~u#!!cJr~Qu;V+M|3>Q`({IFn5nvN4JWk27Vpl-ifAZI@W626Yzj<6&ClJ4n>Vi7 z}emWs6Z6oC~5brXva4PLH%< zh~pAPYX+S2<{R;~uFB=2P%8T@7R-Y|gIhpnh9G^dN5WfctzDj0`41ZwcI+TD(K-jM zgsvVKj|!vsFtyXBL4;H=0QJpgs1kjj+N{lFC0&)9{LySuIxrPsNOPtVj9F-FX!fMp zrML=f6OrD9j=&=c*AOb1DTvU^LPgSU*BPJMmt%&C7`~y07&(41_)mERmXhTOjr(~ zaVB<}oDH`kI7tf-`ebE!EWLjkdzH7y@3#GR#%_eS5oM zQ(rmdQLAw#Q=h_?Y|6{-Q0rHO7V3+1)(o10TH7|zJXtc6dtv^D#@%h3f+O!9;7PU7 z(003dldAI1JmJ{8&2>IJa7djc}ZJs8UN6{2tY8qW=#>nB-$#NYeT5E zznui3oDr6o=D;>^+)fvd+f&~4*xg=NebDO68pokM!J3w{?j|QE;@M{|$e)e#=h8WR zr%p{pM))wDBQ_S7FI|WW=g-9H*_oI+eL5~)JQr7sPPGZ-4XKxOwwd)a&)QyRa0C%WD=AUA}zDXA=TH%qPIqf!Y|e zYIo;v30L2-RwHI`nHMmThu~|o4m_@!*WtgbR|vw=io9P2TjaxWyv4 z6Kx{|Fg>bYUS-i$W1yit=5F6qe{5O%ESKx{7}!-EY?c=I-D|qP&`3%=vO{Z3@h+>f zqOk@(@OgWxWVMQwqsbT^n~JgVDUVS!y4g^{_ol`!0uxM0R{J#H_M)vNT&U+fLarXP zwOZq@wLyXn7zk)Q$J%_M;s_r%8%t`7hJ~G2T!Nnmc1c=S!2fn^H&%o{(cr`UBO6N6 z8U1KG@qEA>Wjx&Daf$Y9Mq_+*{8aQ0O^7Z@f;i^>W@9Zd|GKxct?&p7%aK$2BJ{Tw z_Q6&()&7{7q)zmyM*#SLUuE1}h#Oab8|xc$F*-UH{r#iLA0CzPKVw#Z&?^YMI4>1p z9%hi?HSX?V-Y{tZb8na{pn+Rb6QP~1xW+~BtTYpfCK(zT7k(U9TQC+0aS-`JIm&%Q zYFbPcvq?mAl*(t`n6>>hH!b2)oXqop^=JpmYDj&~z z>JMe0kwm!^M(wd9*ilx><{&=!;G_75fBfgTe)EpzAHpJ-Q#vH9|HpBOJ~`QU+@sw| zZT5BhFXEU@JA$u{`=fA$zG9p{e>TQB*Gq&QlkSl)L`0)dza{`JI3Q>>pu8Z|J0^6d z5bjxQFdT+W-6`vy#RzGTABSyo za4owu*u}&|Q!1A=nTrtR@J}tGO&B4#(BcC^t*-D55p(PcJlNA>MtL(qvRLv?Jr$C2 zZEx*FeT|(X%J`{ssUOOfYW(C+e->}N_PR~f&?VHD$-t~a7E0N0%b`=T6*WAw4NYtA9~&TxQ=@&+&3opI*qBr`&`28#`mA&^<#h1w|k!X>7@4$_mtsb zp1(&5rI^o-Ju@F3fBq`Hem?W=LGQ9YP^RC9e`K5ep8c`zeW+K+6XSkU9(U6FM|u5- zmTJRbI+uY>MN?A~@!|{5ni-qZ^X*$VVs&-hJEEtjXXDiLv;|Wzr=i)01_v!@ViOvh z!O$FGr!ow4Hj0^k7A*`Ngk~3vqS@J5$3Xx#G&B?w6O*Qw5t>yhHRY8UKrpEgbQO!` z7@wH3woJ3hX0>h6`bE8)j)|#LW*k9p_4W0~*|XqpA7MCh-bz7zEc%n3 z?a;p#v?WGla>V0434GGVvcw36#!lxZQGNslDlg%kf4kn?^R9J!^p5sX8C+(C75z(_ zu%Qq^0nBK$(+q>q^cIE^mbjRkT2nSHA)5tldhH*|jwdX6;P>PI{GWe}|L4E{*Qjr- z#QF0x@n?Vb(>QzXT;v3|oM(gS%>GIy`ulq0`R6Xg)a0mOvt))Y>qZ1mFw1FkuW97n z{;CfQKQjPf{)vWXQzn8B3&i%-ZtAP!{gCjgiro@$TF_;|3w_L*MQJKt7XqULU6JBg zKuA3WCrS!aYAdTSgfW-DDY$2ix)Ga#*J`yd&R@6~Q>UhNUsb>D3Z}7ElFakh>+2qS zSTI>$!X)96>epkFqX@`)fJMQw&!IZN>Pge}NCG9bahKL}yLF!xN1YMa6%}u2Xw+BE zE*hVl(Kwqj19f9VVFfRhT1|bcvACZ$DV9nFGyD-=4GxVcF6Wu0vzBN>7`(JU-%9!?FZ!NQB2p}-;n2s`_ZmiLO zA?lx3x|qLPc0W=U)^rx=k)HY}rKh~<|J|kqA(V$9miQ6ddXJD)ZKqDl3vc!HkHpyc zcvSm2Ur=>b-w2ouM|7;B3uJ)<%GnjULT?NX55$?7>3Ht>=i}VD^A-YHdql>Obc;3(VUmwR2(&^}Gc-CKgOdz~O_=Iq7VS%&MFo&6r zF@X8LxVR8=^KQ%nP)UU&kN6EIR>F@)8+yjf^A>|J_~u> zRT{T$-!ebPW+K&&SlNMJlM$T2mjJI~vXFDG5IE#=2z1oSDuV?L8aJ5I1NPA#10FFq zm&;~^d(ap|P@Occs4N?pfj!Eyy1J-(t#}T>gyHq8pIZB-zrPm4f>+`IFKNRzf*|2_ zm7jCT(wIb0y%cLo1K|+DGw>=fKpvDC;hWDb!>ddPeAZT1oDYIq%r=_Gp>{<$MOo4r zQ7WUxHfNXte``x~-td8z7TQgD&epUWS%p?%#TTYH^vF&pl|bP zlaY~$m^^(x`Ub`=%zcWtBU-OX$6I$osL{-KDeY83; zHB0+Z7Hg5KJdAhpMHpY-K+BM`(=-&p%?29gI`9Kpy$3EUa}{T4G>@a5i`F6nVa{4pT6zbpLSF$>^bNv#zIA1&I|5W;y2pMl|vc)nB=^;X-o|!a6otU^R;bd~}QEBX87D!I{gz-|K5=)UCzGA6?Hqr?or_$H;v=29p}sVKW6tu+5t+fBlzmLKX}JZ zgQ1Dhm=ICdH`wn*RfY*%=-)eCg!IwkLe(8DD<({K=0K3xq@gAn2pc9L2n=Qp7Ad%0 zCUiO5>P=Wy6DPZKlGYasdh#O@=`dL^MjAL)H%(Vu1)v= z+8_PsC-Lla&saq}?eyc15D+Bnf>hg5VZUd#6#-!)B85b#r6;wMlT1#1=5EtB6L;Ja zj<~vE&h)&=53cpj3y9V$-f`On1;cwe7z!>I4=NLRq(y>Yjt6-Nc@jhH#lncNKL3q6 z5S~Bc2vW(wbs;_C$pLRZM}V|UD2b@iH=ZF1NTyu|(uAnviEquumKO!T{?)JJ`psKP z$4Pcv$8}uCJq_*~)c896*T)HLqu+#rALgX5tcz9lTudLx}nLRz9RcQ!@yVP1({`!HM+ zQ!sg$O$ft8U+%)#XKj%f?h86NnC|7s0~R^H(r z8iQIdxE$Mz!&Y2zUE z6RdDPkIJ0QvYyzpKx^Ud4UM%WkDKv{35~^(D3z<;mzlrANy2kXd1x#jcYVES8bt???-5rh$XsVuCXVXtR_1M{5jJh>$8fJ7Biv7xS zQt`(%2KysltobaVN_9YW%f)&ft;VjX)G#sEul)Noj?rM@D1%D$4~}{KvEtfNnp=%D z2Fzp@Ug#}pJZ3e9Rj$RmcPzjg7#OkuJZa(pCTRmDeLA8<>T&1UZGcEwtKH|FP8wWeJ)Zoho_e2k3`n;%jt7vsYD3pVvQJv9~MBSSGc zIToj8PHSvx9#L5r7v?orT(?lSR4T{F=(zBEf2^*r#a(>^mJyy&EjCba9unscqLEZW zsI9(4cxLm8f~m%4-5W6K>&wRFXgeaH*w|Q$)fK%H?9mtISqKNi4?_3>3?Mw%++6j% zfM(h1@{-Mq-nn%n-h1!YN@Fz!2Zk-&Y6~)wX~kq}k+IyXHoyuI&53D5giX1OaB6EV z#e$IqtZtu*&%(s?B5jw1Y&+I&^Z1~JXn(~;(-HHB%ggf?Y9Y`=V~H~nSC(!EXa7|+ zuMLfiS-6L=o(<*9u?W@RQ32bOmklJ87hw{@aSigwYaTa#Jydwjr(Kzv!XzBYeB|=0 zttby?oY8)4I6(k|#uRaxs}Ue0P)VAq+ZwQJA^~oa_E)#&6XpU;2{s#Q>#e$RUs354 zE5ng3h*s#Ws?X65HL}%ML5RsYRJ+1O72y)WSH9vp(#E8ZP`y`p3XNfe`J0<7s=wM0 z;8j^YHhEB9%qb<|oN`6DN_|f|feR5JVR8|iKv*=hvN`o_kLU>DZ+MMt4nU}1E)@f- zP6$gIjWw08DY#JC^J+V_A@mDo2r)&>*=4{sLPPkTm~#c*z+a4BpZlghVsi@Rz#Z!SgJ~Ww48)_cv$@ChRqK%zQ&&msL-MMo;{`sH(IsWs1`S0-$|Mai1 zvVxgb<~&7H0gg7Ali24t_Exvd(2S(H&}XU^kYQ*76Xpn0FBQXCe^7 z8iIkz7?%^FYa9CPI3Rz7Xqq?>K0uU^pM_maf-a7pHNloNiD9yZ!&DKzk&h<~l>^}y zJ3Sy^wwo-pc0eKcYHWzGct?}l?oy9tunl&k?&6xPqIZlJ5AWrEkNA@cw52k#_(0wAN+Y^e3 zH1ArGb9|EHHxc>CL0DA z{eAjxOF91de4@#q*XRRi7X%*ch+aVpO7sf5*ZV4cqLC|6(G^DF#>TqOA%TfxGvzRj zx0-Qx{$^bNW{JYd_ZO z8=~L0BF|227;0J3u_`+z+AtZED~zZa5<_QebJesQw7i)@-6|(cb-ZauXg`f!g{A(q zp9izwCm~bog&a&PnB_dPQ7$oM*>p#_F%_8N@Es3pfPOjD`U8`BiMF)qw(U)|PfG~p zykLfL4yX3%?CL?lf?$!fC^N)pVnB9hVa8YVj&^BU2*-I=PSQd%-78OoFKh%v zIA~#xyy^8s9P2;94e1|x{j<}0-71$&DN;Th;nd#xhIvV!sRGWm;EQlH-!^48dEaytY97c$hw3=X6vVMaJnbwG`9uBph)cQ~L^w~Trs{#t1l`H@( z_(DJhBbfCNV*y4yT1hZPVRXXCY@b(yu(46+oGigX7Oks2uPGb#O^?A$j=n>?uGdUV z&eL04Ui4T**oEe$&#+d>h)bCeK(hlMn5^{=Mql5c8RZBSR+g7-{%mw~JbH_0JaSG8 zeUvt9qWuB`mHwd}Fd=&P_Kj$0t&3o5czimlL(@^}8?a!U_F$Y9RhEo})b#TK-K6oQ z^zy(@kD4W&GsebIo6wR&2(h8@kG7OoW(XY3RLyxkk7g6F1YP0vA2PJ!lK5jA)x6q(h^}8()EI<}qNyV^oczIEcY(swH)SU_$MZSO0p0 zv&xIL9I^m+<2YaH+NU4K($Zb6qq9-%t9p(B=iI)1%hplG$0n>%#D?1}aG^9Aql827 zMLQ!LX5$6vudS`d+WLz6khw#1na0)n`bK>6Dd#`_TU@(#&Dv6E(xCaYe}EuoFB)h^ zAz0B^L351r=N2@6Zr!>SS3kX~^4wP1>%teD`_&tm(#3oyLM}FM0GDVeGj|kv(IQP7 zuqiL|8t}wDVJZKf((yU*f_b#qEG!V0^X%xa+-^5Y7apRbJ~H*!nhVZ zf{zha)92KEZEeXW^AI2+xMM>L<@Oo*2+~zgHj-06a1%m0gvX5YG&g7tI~2a#RKL{M z)Lw^bucF!pjU#x0grTgAb>PZm zYK=HW0xl4iZ#OrrJqs?O|Jmq5xfs9TFxq#WBTq#CI4{jN=1GF=8PvvC8S}+TeS$p& zVv_@B^bLr{85kIiA~XrRpC+KPcyGz5UnrLhtK45 zAhQV1Q+pxM-w{0Axp_TS)&Ag`T5Z_yYk|AUSE<&bSQ+vhiJ9DnXfzyi%2rc!SAA8* zMSzJAS!oJCZ))BE-+`ZjNeXF`zWQ#nw=KbAa^N#OI7hfz^Vfg+&;KR<$KU>=(njM_ zbBOX{Zf^@2!SRH@-+@c+cWu1WcE&TueA~6}kH5nmfBz_-#@M~*FXN7<^L6{j&F}Z+ zPAbbu9%$+azB=v?-mycXP_0;-tEmZ)14Xwq$ulW35r7y$vP|}%M|M>44zmf^YSxm@ z#0%=$5PMEj$QUA-GynrZ{J!|^!;ytdd5?-Q6Ce{iXdnq82$c|UTFf!&i)ceAA>_`x zLb2e#Ox>Za%FV zUx(g3^yb@d$7`>?qJ`6l-a_=MHR&_z4w0m1h&~7dT3HV!K1?XICOLoCJCGmg^6Ptr zF;a9O2n(+M=rkah+DMal&YN76UMdH96B)V-~1-td+(#zY&?yy z(QzHuaeu__n-hGUp8acZ>l6L8=Nb9--0@J)UkdsadVW;+$M7la@6R8#!SDIcW$FBV zvwv#y_GToLMS2I_hbf`8)s47$V=h)#S7T&&AcltqP3xhdz!@ypKKU@3&2`b+qL-Un z3VS1d^{@XLAN=;War651*sO1wZik6DF*P9q=pYv7@5D#%zZY}2K8?+_Wiw`APQuWF zF^Rb%n8|E_+uz@|ZzzvOV_o!CR}}K1-E)*tG*}lqxY5RGX4 zu--rbgFs84V6-15?SbT=87Ze5RgP!Mgn72a;54%^gMgzYq&sqn?oJM2LGt^YD}pwU zci!uj%4a5`J^3ns#Y=)R1S|wnTkJ2!Zu7R*C+lX|b!Ewu@5Iv@3g&2iLu;9a>Ibt6 zMq8>!VmjuvmQp(_ZEx`NPI$qA3!$=g!Dv*UAv{vMr==Kax68nqO?7t}@dzrmlW?aS zEeXO3{$McD2NudeJMX5o8VL$^lJFs|t-Q9dK#%nC$rVezF+DvVXJ${w@bFO5YOr<~ z;aR64{M?M*e8x;in0kjQdpehedSm$`3BjP(iG{EhhF~%ahGv@Rc&!f+^0G63Yim>2 zX6y<^*u9T=HEV&%A6ddsLNGgfG*)0@?(M8uXbiKR_rQ)#0)Zrma?yOB)O-`MT+Q7Kh;aSzYAedL% ztKMyMn=tZwF%y<4m{E;p41GU7c_wltw8Sc|$J+9Bt!Wo5kSegbQ|mCp2Fy~`IhSGF zY-_CDjm5>=QLl3@kJ@5SZL*t$L@<#N{3Zss@R0hGaqqrW9x!#$fItY@*xK4K41o|8yNl60a!)IiNF(lVRK^^>;j`nxQu|WM`cE+ zjpmZaP77!4?Whko*IjpOmN2%||HV>&%+5^2OD|oCx4!eb@bRF9I~&4b;1csQls`C2 zP1bTpH%HF2#v@$&yRSxJJRkQsR>Elw%sqYHo9~K?=O*KgS1-l6GZWD(9F4h61gDtD ztJVesZ5Ln>&6>uh@IB?1zj@))?X7N&*(F#?{Xk+rQlX>8_%9~p>( zzxw)$*7mn7fTooYCRm`Ldh5r+UIcfwYQN$Yg-5nxWo022?#}xg0x>ik5iTW7=WW3` z0yecvp{Oz?VRvt#5(6WX8qcFq?i=)&Wv(r%jYd?TLf@$S4)cNYb90)%IA^aQUozgs z`y4-YDW+C|+pKVoasR<~Y-zqlK$6K91>Y*;;+*QN`l9LCTeT+cwNHNQHZNBY!Xp4i z=%{vA{qia+;}hJnx5L=cSknB!ri7y@Qa6lgcq*7?ER=^-kGyb?aH!Ak+7?J7Q3ckR z$5loIRBYVfmCD}DQ6~K^t^gI}Nk0eM!(S9ET8=vk1Ea;f@9dW4cSYPxuSE!di6}oM|kAkd-M~YzX<; z#83XvFDjto!Ea1wIreBSM(~!+S41cEMQ>?9->NDH=3qhY%8RoXX%FGEjkT4ydFzJL z937i-|7XxH6Z{zuaPRXm*$^Pu>CG9ZbLQ64(n2)1HY}v=6}_`B8jthxm`8z|OfMTE zx>ZE*r{-HB5)1K_|Nb85#L*{cphF8aL{rq`{SQBl|Nh_qKCWM%Q@1DFX-q*p+QF_( z%ixSuTK=B1qG5KG7% zqKHKdws&_#bTfyrBL)OP-pbnE_yVF)lNR*LE^)MwU=f!HE6h@eD3!PU=SI_IYioc( zAY+r4-DZ@L^b_&i6V1(r769v7Bqf2})8`JgkUSGV_|Xq+mz&*KXh>0KFLYVhsU27( zLU1S4n;O*;oHiPbxOVME{L4T8GHzVIqp`pOzT-Ns<2vrCao?EW>+G2` zUs&VovAh{Zt@-II^44ZJ;r+>8bjOMBzZuVh{K?9Dveys)_q}@(?>2B>bo@8!`GZa| z-NT5}gXpB)-Givt8<7!FjK;y(*oc{mXh?kc{s-~?@7_xcf6={n?%a;+pI(hSw{OL+ zXyq9#2O>dl|l+M*EM^EM;8XI$>$&-eC zT0bNU6YPLz95i99uBY=@U?#Dli38tla!F~KxhFagflRkGwGd=z>_kgbN@?)y#tkGzKAED|$eEtn!Ko3dET!2Hx3t(&X~1Z_>5lLtRaleEbeZ2)L~n?`bdQ+fz3 zlHekRM`OuxZ3dBY@=ghe4n9yHdiTGXbRx;)*{ z(~S@=BbeZx_Es7y4@o2(N;qW&t*^4OHlpmbm9-yGjnVs^?e*XcGQzMq((o?0KwE|7 z26@1Yb=BOzsjn~{m@f=QzE|t$Ezb7=7BEek81ZPZAfQ3xB9|*ffB$e43Pp`Y&b8|| zb05ZczPA#kO25y}LTgL4Q9LZEv&-_~&dO*3HVU zN2Ss|>nF7E9Dp^u+6>U7ya`t^_V}FES7_o{;I+4_7^(jdDshGRez1pNH}xHSWwfto zd&-8!mCq$2ZtPN+tQQ1_<2YvhfqukMVU(&eHue*RB#-P{Ua#U?(urFS^axvb1^ToJ)aVGj} zWrg0i;0DvR&?onByHFpf~A($}xCP}2N!H$M63 zBlYKg%$%NyGv_YE(C~ycemw?N7H~7|56)Q<4EJh&nwdQxL!;y7O;OIiN=f0m&1b?? zEwGDu#ksjVaqHG~j|JKd;WGKQg-WCe+?4blAuEEdW@FvsgL!Lcc+_nLEYVID8urzU zw-FR0=we17kv^F_2llgRiXD!eIL+AyLV7{!Y?e8w!bvc>y(cpqV z0yve+mFVSMFtrteQcU!7qR`^Cj~==7*X8(LiPl zL%V_x5jLXjX#tSN0UO|x&~?BjF_BBHt=tuS)y>xfKHx7h7L&QugvT+zh*`>#aAr@g zUwNXvy6?>Z-92gJJVLKD@33J3-sFJ=rN9B3BH#zz73?quIKvcy9r#K`O*l#S;JyrI zb@LU$x%yZ5pv#*y)HmwW1I#VTAMT(ryeE92{t#|Oum(&I43AqdxwC^t9>OZ&9hHN! zq8*J;mGe^38e_vtkKSjpT~SfJ5Uv4_2m4Lsg^5+ce|K4>XH$me5fv8r>`^;`|7bJP zW1|rC*pmABH@|)_{_p?tH}SjQeQH{f^l;0w%M&XOmg1&rS~k_Sgf*`z$^ue0kpCb z!IleC_7eOMDh_|x^;@{MSyX##k9BOMqR}&qCK8M~i zp=C7zbMSLY(wK3I^X{AU50+Oy_dP$3SEMKM561J~vGgA4TXF99Cpdvb(!h}K zK8(IfIVL71&D^PPHsW9Z?Y;QNfBLsrSXhc&PV}xkG!mwmF#l9h_`#vU7#p9A(ebh1 z>=5X2HgBT=hFNhosIj}gRDn6kPIAs9!CX&&)CLA!j1PYIUi|jgzlwd)PLPayd;6x} zyF@UuV>-jx8`g+YU#Ofg0yFtq^kgfh*X{|TGKwR*zgbs&&KPT*)uGSHN`ngKG1#qg z6kHaV>o!MNj;pBX@YPsr3M6pjx!Ae_C{<9c`@i5x}?~l9m+0 zB5S4{s6Hk%VF}68Y-@UPr4G=~gyH-bwS&?~+F0}tVX%BaczNa9RGHUSR$^mqS!*rKhap5l zu+TDPr#8j(nJS`t(r@oZr(7zp`#sd>>(&OqEE7!T-CY>F>ND1r#8;U}mpe@U**qDv zzN*C95kZ74dk99-xhskJOc*p+Ea2cin>0JDfy9DF@zGdfxd9*BFsM4iTt_nzII~$! z!65>j6|E)II!BCho9M*3Zz)~NtIR!JXl0;LfFL@pzYyABYHMg{)Rs#SD!0!S;y#n3 z+?+*JwLqY!P|-Wih)KdG`roFtLS<6cy}53mhnLAS7AZ?J=5Ku**RQ^>wa>cBiO?=% z0o?lPqQ?g1E)>dYW5x;$=Dg3+V;zrn(#q1Jir*ELa@ovh>YH4;vR-4o?~RNKM_XDT zN7>Y$)~4DKY_!Y}rga$tGAxa#zq$IJ&8=xoh@c*=EyfLuaZKXDSkGGfWxxWNt(|79 ztSqN-ol(9*Hl%9-q{={Xz&$=+%j@2jaE3X_|@<_sPB2kp~JhnQsjF3VtRHq&Yqo( zTeok=M<0JgbGf|asp3A;wdaHO{fSq5{iesGYnxU6F z-3fQ81TfnXE?^=TLDbGRnsI3ZGg^(9$U^`Md|djF#i#Ol zwe^{^XJT@4%I4*O5wyFO7VkPvS@YNC`bx~tU2|OqhlV}Q5$pm>@IHV)nEf8B!h3A8 zM#BvuG`uEEln%7cqJ(cn-!LrzKWvz8C@uIW^gDQws>Ql>$JAEsPQKpDHu-Q!5`pY#=ORl`iZ&2CWR47H<3eHR5QrrN1rc^DaC+ngzO*aj7QsB{ zeF--pP(zT#pJ@Ztow+855V_BF%k~lvA*5ibzNYqEh~=d_ad+-&EZn{24c1tz$`=sa z2{)+C*kpvT4B?vVr+Eayr{^|s9eJresaabCyS?EhBN$=~{pPnH#DD((|M&QBfAhcM zz4tyA9IIZM*NEdZ6^?r1C_C?x=Uuvg(DCZHrx*#(BwXV-`cGkxr+L5sqVA-$zAAr` zJ1N}5{FAto;{QJVNe;@eBlzmLKWNvb1@XYxNKBqS9Rou{BG}SmbfBL@GrN3PD-#40 z9JaMJT#P^=R9IvqXksT81a?&uHv~KgkU@pOt5-yacM|CyGocF5A`Xa?jQ8W!=-m{=wO0C$3Ww* ziH_a!MxW*Q_>)iL)2p{*VJR_@E}T0PXGPx+4Gl!CucGUqg@Nv9C4y}bhsPNpz~ME7TNF*-gaKM_^MUtYLtMkQKCrDDkpV;CZtT)}3i@_J{J zgE+W~FpwfK{gNgUbRrCDc7n66$XVM3EiRaD2(dUM9;Pfi)XRPSku40Exn<#s!lVsP zT2HL6+SE|eDuLm>t72`&c4JL+>4A6Q!!TEaDLiGNUM%xlBj>1bDI-^YMQaj<_Xum0 zCK^cy!yq!P;pDKSgWv>)73UyvE=N<Y?%>-~#W$0Cie8n0%@W`OpT`yIXbDA6gs;-cY_l5Q|k1Haw!$LpT*$?-i$8 zY3yOLF$uR|PW!X^ssSTc_1!@Lv5i^6y5J55HuV>Mt~DcC1>^?|rj3%}o%)Q4w80O7 zN9xlyL(a@i#YG^p$2vlBv>H&F8Lv%Y1_C>16`GKCb}T$pdL4_z8|YAa~kKxsP$L%{xFsn z=VE2~uFba%4vq!dW@tTN0umEnXj|m6S*5`Gd?ztug*OtT)d1x5aWJv*Ft9QG#(R!C zpq=!={p0nz$CyTbp0tuS4fq87L7o#{w+(Bg}S8bRwM2Yn=6~En)NngP7o}yY859g?UW- zkQM?|3xFBhDn~Y7R6kKJ#-9qczZpyO*NvmlPQ#`3H1`>6+iY*wrWp#BaR+r~3`~s$S z_XO|C)53efICB{MHO3kO)g*XgtkDxmm;<~Zd}AE&ZC~(e4PdpO=RR*v;2SV`Ae^&g zejRlO-(Z%nD}yjra4eYM+%EIx5IhPsqp=CjM0*IB#*A&ViN@=e1@xGz>{gkH%Z3ck zhdp`Md3$TaXSE^ZSD_T2v4+5ya_(v##GLY$`mjFQS5kuaIhdkh?yM^We6q< z8_=#w#4@{Wm{=N0v#AM@Nt6XMf;8SE=z^GF0Qy-ASiBc~LfA}_OrEF?gQgQBN$8r1 zl-+;qKvCKd<&=-zcBowQ3}Hk*O!_z$(`zer)h#Wgo-W5E(-UXUUl3vYW<2-YbDE?% z2wL@pkW*dRxdhR~z&Bb)@iQDbRJ(F0Pv>@Irv`V4$r>UE`5XACKj`*}Y z4zG83^#RXNHR+ibBJ_MsVVu6NEKm~B!4J9Vk=HJdb7{v({|-xO+RmZ$o!y6+Jfz+U z&LA4LMc}Y&tsK=_UpmyZzu(067R0$=2~~UQy(6Lt;tZizeWUJ!a^HLJck%JZ*96-t zd&hNL$93G(<-Re&*SWLj{`&aNzejuUJ9EuR-`f8EFueF|7#N%n|JL>v4p6rCJoiYi zJWmSOnsttQX37WOJ?M{Xw&C@2bpPo*|x!*^!}l~)h?f@|L6TV4%hqR9WOtC=WFXZ!FN|QMW5fkb6d2_?Wk{V zM5R)R*_l&u@%-sHJu@zPzG%&na$h+{#wTKIVk*kj{@Az4#68jcdDHALS75%_%upt0 zdYqlf_04)ElL!-2oRP7zyewL7-{um{BrUPKobpAW^@JIwgT1=e5_7S) zy{*SyG7%R_QLbt=bPktNA-;;)q{fEZ2nL>aQi~o%zyfXT@#%8lVQ#}L{(Oab9!tGilAdf zQ$x?nL2G+snY#lD6|4YFjftYIbcUMN9^?rv>~o5gMwcxm?595De6Fn8yHxV-_MR-} zrjoFQv4NRC)>>>jL=%R!4CkL=(#b-*uBbN`<`Iw&L?vIR9mDFP&`#ZBFs& z3rtY$E1#|AhP4O~d{GZHt2i6(o|XpvCRkfv)3+@%snOP;xmhQ|z+)}Aj@dh{=YU0@ z%cb^$=?Bx%Ydf_o>j%~bXb)N_<~6IT!VhZ(g`xk6hp;tY;Ow4CD$l0IMb_GnXfpbo7BixO3)%{}A?@v0U%nl81&;_|F)`*%qVlY(X&=t@N({mz zSThW&euW}hNHBX#feAX8#)@V~AH%)0mO&S5TJ@XS`S3t#fCG92mwOGvJ52TdLCl-w zJZ3pN2B!Pu)TyXe2i>cU=9(GJtcNhMh~}A=L^Pf9>@v)GZPl8?m_v1^sv1oOJqh|@W+y=cW>853#y{{{-&pnf z5qLwW*PT(l8T+nn8e8ceLF8dyb>j(#M&&apTkY&2N7ftE<9AH1HR2 z#`(vtIN!D&xw!cdu3JFQ(Gfe*SIWeh*|8X?72F2K3;gaWj2Z*&C0prfjUV74jfs2S zCTj&_^cgrG{9Y_G<}trUn}JieV{L6&A;6tU0JaiL`)nqUct4@X&k{ZK0X;kBjXA`pteZ@ zE$}jCHOYte5+ug@+LAoNqC>YO^9vedTTL{C)PBO#2+JHta~xWoz{{?1B1bV`W-yya z$Op`WOMtO$rGv)|tnj}20NM(nJY#8l3qcNN5T-IY&S4{N-}pGzR#(&(2(s8Dp5S3; zYeS%ca3-gA(U=#m>!$zU7b%_YF6JC~D3}#IP(N~Z9okq5mtjMP#*@m529hxf zH`fLG;A1q8z-897MM$H+H18$840APt{ZdJJs}0aJgD1DSxfUx+chr8X8gIQ(siwB3 zjp5VSgraaBX9EJOxdIyFq7l>=7G|lx*dV~z7tnk2J7a;dp70lfb~HOTQ+pwJSKNKg z zm;pwcPHn1A@6nu(ARY@-2sqE4y%gheWxsAWDbr7k!#_i`vVb>yaVYXNLtkbq_NpBal~X|fr|(c zc6Aj+u=I)mVlrZ4!p3!@!FdBaCR`gr(kxEOg|cm&6PI(u7$)vWojmFN37fxXE0}H;`{grkMGKnY^y`v60(b!PkG(kL#j`|D^ zjl}u$7h+~sM4~2f2rf*7cz2QNjb+wmh?@Yd5kb#A*%U!6rtsC zJg9Gdp-+ykEI=Rvxymap#3+jl{VEFYbfdOF$DLgElYKklN$)<-JLs`^j(g-pj6ftE zeM?MZYdmyk%;+l>d*g*G&&5kGJs%g&&BWw50xGN{ZqAJ8Emo{$LON)1 zBtcNO=rv{04YLu3Q4+$SWr2VKI=a$_mO#afJ$C7{yB?_5E2FyfXAEpq~Zs_LbhMBXRw*n1l!J!Ml zav$Gf=3vSYO{i`(Y+xV)%PzE;U#VNreu1vtV@08FZNV7~V;JwEM@5UtZ~$y2q|bg)|;#~F*(L})*dj%Z3a|*1(P$G1f?$R^$AR9+Ff8(=m9y($ zTjkx3Qn?tMFGHKHudT)6!kpT?>2**AZMJ;T?Z?>I-`~jX4dc|XBsglH z%|<-;wQy6e7ws3u1aOMWyKm4!LRbSlGKTjMxCvI$x>JxX7)PUnb_OnZ3BSQ`#@JIH znDI-RGAbupp(;19O`m}LIE#ofm(^Z*YvE8IjRkA=Q63tjeP#U|hH*@EQog*(&lk>N z+Z8VRPygxvj=%f+e^N7n>qtvkGoF0+c<%mrAUVIGZ~W&6{qIM)oQvtnkvKIm91|n` zF*00HcW!$V0r(Oj5Mu(=1>Yu_^Q5g+LiHzgNTxW2hXjD+&3HjD?Ty5&$<=SbQm^I` z!XY$YU0GB+G#nRmntf`&ieMM`VS_aAfCeDEA%tmI;2~W$KDWnWfB!(to;e${vuC4P z8}!&@T>9~=P2!JwdOGgY}vG($`7t!jZYl-KfoSWG!fwmP%kzW zfCItP@VCGpd>4L7thg}irgFSo+##RZGJEsy7?Wm7MECJ<=S++#|2Kh<^E>|MPF-zy3e} zO|%i4Nzz=`=Et@9X($e)`OoOXu8m(z3Z+c$bJqBCzN!d;Kmm?(43F{LN(Yz5^w;Oy zmyhYc33pPy5BjIU0Z|>nSI7N9yJAJe!(hKAE^N}K-7-w@2)}IhZDmE1uMo2k9uu00 zOd(Kq!tsp*s7(hkQ3%mvjs)#5FQWB+yQxWcZ6lVKmo*u$D@|0M*>To10Wvr+q=_?W zDuJj?Y-vIRx00#_D2f1~mgk$UM&2q1Q$5Ip?`anpW+QfDb3==51auHFdKSu2*o1^r z+Fc?fRJSGU2D8BPr>D|ks%GlcDG`dZ)?o5kRq7K=Jt7QbvZF8DAF4NkA=+6qlpH$_ zAtE8jL3eVr#SxN*V9?~rOHF)^qG$TwJ6x3(J6`#~BnP2~0E(SGz)6~PlYoiT(le<# z3*H>1PYA!lS(3$D922YlJn`bvdx!Qa8yGoIy;(T3vv^OF{#q<7E}B?|IL<+YDSTQ4 z!{nj^)_EA|aFF>gMSA z(Qy-V?Bs6`_eW{+ckKN)?vJ-0bce2w^0fMW@lWuCJL&!7ddKJQfquBpQDgi5&WC7Npvzi=(A_0 zcKE|+wyE*`Lo@EsJb~GX}M5R(x9O|k?yy^=hiw$=^k7|8Qv|dwb zVIGOid|JOC;1V61gi)+2U?iz+R5q@zxE;)IXhJ$d?I(IN2>|fvT@ql?Z&}giFqL80 zrk&Z4%2*Jft%<{$2jLn5CPziE=J-6od}ZyT*ZK(4ls_DOq^^>Kp4D3_iV4YX=>th=->;taSMEEQsX$4%B)xRxWYuq;FHOr9vtsEbzwx&%hbQ|YYy(yu{( zWMQVdu`Z+k8}+L3flZ986;L!FB&Kex;kd_oWLEtR4P0xS@?2Z5oV4)*s|pIu#tt2LA=Ugv>t>I%jZ79Ci7O=URSM-4;R z%$Re(C<+g;1Otu;+@W8}!fg|!7i_>c=#KhNV}nh!xZXpM46UK>a>}2xaTs^~PF1m? zyaV?*|EkeA5Kf?=SQVU?^o%}H9jpju{GjlpT+u?|2xACWiR6Lnz}b1MoQle;lYag$ zKTrSlzx_kHzoqr4tyq-aW7kc8WNv#}c=B_tkI7GunFHA5@T0e0P5=A<_P?Ybyzxp} zT`3zE2MFcW&y1l;8A~4!e~IH5<~pD2(Rf9g>bh59y)p^l@nSSy3G^z$s^b(S^t zz*a_h(ZLlR$^~0C3TeS9ta%vUWzIj!7fc7i30sFMZ|E78WGl{yxNca30I%c6_hb3 z>q@1H=Dgy_GB6`ppva947_}gDHsW#RZsegxfd8zmX?)QN$)@eIA@MC zw5HR%Xi%|;d&;u&JUlo|9gTbXq<{-SHcW`NSdl0g&ScdGrUNIg2XHn$Q+m&FAT485 z_38JUrVDM+bkgDSa$#lD8)+;SqGqbA=MCWp?XC+q+Nv{3$vO4El}8#=!(KBK;;Q@l z#)e?OqGwoxshkeVGL+K6n`kysTQsk$-*KCWn?qdWg169gXawN14rm8WmX=cmf^djL@9sp#Jd0@*a-|;R*ReORU%xPC(Zg2f&C(n_7*UV1cDN8(p%x zCwju!l%gS6t}$24sIOH$;b33%l;c(g#(&@+io2uKYT}-`XC;@FdH`B;3(7x_d!q6_ zfgezvu-f(}7J%(}hc;$~ll64%vyXhH;DyZ#>C&YOX?1let*tDj>U$GqXl*POnJ-GWX95mIIm~QElFg@6+*V;cVKc#V-=RX!@@! zoNdF`9siKPOgmA0O~SW2WVJ9WEmXwhRnlBx-po!@3t5YRRMwNR7!^n=lOS#cB3&pkI3U#wiPE!ckV%alp7?#AVK&s8R<4PO@2TF+ zYCClrEc^_HZ*1tRO}MRj>&>^Uykv51plB4MvA2H^?lLqniwdg!g0Uv}n4BPr>Q}*# zXhJD4nQ8HaN?=+HMxEqw`{Bd};}Vl3_r#n4UoV_tQuSxpMp`d+N#hAM?!)YYXQPA> zTrZyLz6m$)saEP+*TK_pq~WoNyPngwP{?7yg$vGx7(FqX!l$u&1lk6^vXhY=Td~`B zCUun_|KvNnyXpPkevm%={m1Fxut5zbVG<@`626Jy`6<3$ef2+|ryLm5>4$;)W4b+x z=e>72@{T{xi!9zAzVq0-r{Xy8ar&pmGk>~y>X&}=dG?)iVk|Br{pok~5z)CR&FI^I zy3KDwqD@5*VU5z@4FaHQj@+;(hah%2P~W zT>Bn;nQn=9vfCndL5oL6P=iN@p4JEKYGzXz0w>f~b0h6;-%3|MdOzK~$;P9B%FkGU$oZ_e zRl0ih!*uW7O+b<^UVcgO<+QSPAr%%bsQt6)aBnN^DY9#3#pSP!t4iStJK z0+-eyM69v2mSN|*ek7D5R_@p;3gI8TDV82x0kf$j9sjnni8NCPut*2&_~JgI1Ae0@ zLU~wJ8%k~m?&pB#06w(a5}b#+N0|bQ-$hZSYm_P~+loQ%tHD^qWXMBs<$lzGeo|Rh z46ycM&2yyZ2vc<*;iKC^+A*KaJ<3C=p!E^fF|$SU!U()rCn1OfW*`IWt`Nu)XcyN+ z%GH;7dPNH!^SY(AV^?b{)o*5o9r`nZZ(nPXhVctP|=#Dp!Okz=S(ZrTWb|? z6~Q=4oBH9d+SK*>j=qWY=E$1`NUCxXIuC~k;<4=Lh?mDbVM{zd77RqzrleIB)ee-p z;GV5ra`UNBUQRRlWj#db$mY&=>UL^+PyIY~taZUo`sFWwWhH8N|b0WjwfF=lxW1rxLer5;w0;VyCC8%|5*Qp#%m z0-TQqZMO?r5Y{g$ilBV3uB814XK5(zNo%#L>%6hCsqs@v)mklmcI~R*Ka=L>a$W<` zC!Etmxvc5IJfFcOTm!~zphRhiLI7m~ZN?&GsD7Y)=mK@~x=)ccIMJ>w1%K*_0s&%*6$+kq^H6Kx zJGOzaleU>8jIF^zMQ7B-~{6vZz@73jEdhear(yOmrN|lOe{+#9q;T^8$*gQalE})2}t>#hm8;d7gwV~9+a)-We ziB8iu%o(HsFK`J8S>fzDls4dYuhXX25TM~ZMw!XlpJt#+pIT)uc7d?6{ynV zTCZpqrWy5<`U~r>k%B^~YI?wU!WtT7MWIl(!VA2DMxY#mHqr-HpbJKZhtgvKO8e}B zR_XGp?@VUS{XMNQWS548qF{Kex$SN`&^!kn2HpqEQ-U29QF>WuK2+ZHBk~C34@32Z z=4@56*+N+yN-31^2Lo)~qbr$0i!^2oF`r$Dq%=-)iEbw7M7u49K%tCsI350|H5|^n`2K;r^8t~74JV9pLC!2b%w99jMH`gD)arS!+G^Q z8_x!?X`=X=gl~0V=L>$2D@(X9VP}IFaV-vEcr_|wm))EgVNLQGO&U4nx3<#3?yfDcICqO3dYHm@JM26;5uwKq^nxZ!&JxhnrAZ4i z$__1N+>RI<7TRWrHOazA*&nf(qw&r?%7@_&7j|MO*hQrJcUv$wECe9ZN~8%B*NN?> z76gY)F}zHC0fTRHK=`n+c`^O@U;c#_No6sk9a}ry-`-AJ_qS5L!5IhaKGb4F%sKF6 z0<*#kW=<0_3=V1N?|?}F#zGQZ0zZ*RZp1xJ_Mym96qjMEJb$y(k9|4u4h$Y#2ns1r zkV-dJe(6*BkhK-DlH_FI-69|Ne_mSPqgw<>=n%6o(#i*Q2 z;ykW$sbV4M!qSS}Ai{^i`(yEeKo126n7+TamHz$T{yF{pUw@Xi?%hs%yF1>5L^I8! z38xVB4OAa?V&lRImsaZ+u4oOhsC5B~pp5vv`{~!e`nPoB#%HOg`m#fx`eG@DAQyos zyeDTiA^1HW(7te&rdB%-tlOqI!$UQTz&FD8emYk9v>oM{y(B2Q!K6X>G!j5XIQ49# zMDzI28iup65dOy5EJ~rZi_dU!I=+Fk-qxDO^bxu-jb)tRHN$y4w3l?j8+&KH%N9Ne zPOOK(jp$2uj-x0bZ|VczjgSzf)ujL9t#$YvlfI3fBUgU1t%VQdmt^=P4lBZ5BOung+df18oT-# z2QR<;vf`^gv#3~JvO7M?V3Qrz19le%4H)%bw|kI2{rGoj``!(`6N=wb8Nu#M+S=ao zS$xpSwe`)kw6d;ovZ#87vJWKzmK1YZkAwfXYUJ zs=vqLAY34ZH4u2Hcj-3;+^Yc`#unCBxIQgcIMeA^WBs1S>6R7qczXc`C|DVvlm|W_ z{GQgBHf|wY#nRzeV_z{8#Pl9epq@FUolnymPsj~?^nu`yBBs^EVn)A}FE|x$6cI$v zkKPqr+xzME&8ul|Z&&Yf-Vt;|w1RPJy2AKF@h03?UG$-A`WRe64swzjwO!GLwyl{^ zZfgMO85T(G^!NYpkLlWHHs_P^8?SuaU90ik(2&tpYRTa z1d55Jg?zevVKJ38ALQmThI3`1l1iM(g$0!8GWZEC6+n%1D8R7B1V5nLl)=W)hH#&8 z<;};cHF6r19lS>uX9XMDeRz1NSQRdHRhO{90-wtZi!O6sw1B`y2&|n{fPQi81T;eZ zCwQUgMj5d$x_|ffEz5&0Uc6!@7c}2vSah8CIQNOMjx`W@QD@x3p*Z49?g&Y99z(Nu_hXNkO4cDIPRIk_=ESfgLBVdE|Ac`{H!h)Xc>9grJZ0H8#CzB zY10@i)==U>5179w&k8%{2v8{v-BRM2JuwEkF7#D3}JPn@2aU`7G8J1+6874ZQ zF@o2nz5Ts(@9v$nuWvS_P%et;?5uDU3o9&)!D;1*1u%;6>1ocn!dh4Tsyvxv=5R-v z%NizFnjZ~?o1|g9=`ZF+@iQ8WSZpHWWIlp+L7PxILf60zZ?XaY0vJkQ>elXHL8mm( z6{YuP5YZsUTv&^RH9BJ&4omJec2SRZr@QYgb!XE03n&PaPIH3onON z;8E&pOt~Kf<9@H1Ze0IVJkhT6Wjrw-H0zwJ#u=m<4gZGd7q4jSKuf75^B)e6MNEqk((p#ixa5 zNqaWUdGSv%oUJ3+G*Ns_!nZo09AbeyB?h)EBFU~L7J;0-G$+DWsg$hvV)smbo}E=J zkQl%)09x?s9t#*IQd^0kSkMH-0mWE&p_pNUVd27V9Q;hPlPzDEPs<|CtE;P?%)R4= z2}uMNmjJfrQYo0Cv&)8ckxjxO9t=)Rh*&Z)*Nzo0TIHA_Z;NTOpLk8s@X2H05)*f$ z-b~#l3qLpiTM=G-@#XY4|I7a^EiNr-V(zEIS}ipju}ESe(?JO+xWE9wym_%K_#&Xl zXcDGB&9ex!z}$fs!2=f0TVO=OL`& zcMx>H^hmTo$Cvunv`(H(bZ;IMQEiHJ3`O!0Y+}Z3&di}L4>2Ln}&(bTezARoHw>NAs zYoyqT9`4By>fx^L=vaA)Z-W0q$ctqayR*gJxjYnP2>VzUAV5Y@g|f$jIPp-tv%imf zq9d&Vu)N5mg@whmy2cLuywCkbScjk!VL#`3Aml+9kBcM@azEVPOZ&S!w#=y4cGK4V zo9XH&pQNAv{8#Db&AV=1rCbtzaCXdY+QUs^w`;)4`xTwxy|)M^8to}P&})q;S{bqK7odN-6fg8K=)AVMDT$umW7 z02H@5dWP#W+<_sGB_J{&2F^x28@Pv{4F%S`>V%+EeXM>YORghO2D~z5>z-XUQK!-O z6l)*&ZQc{VY=rN;h0=nTBG3c8~H=!Fc50EG+N?B~>mzFW6%7hLCVNHCwpJ+%t~Z(nC0o zbqVV>T%aL{L~(-~GH6RreT)K%3bI~g(z#%Ib>V36qfA^kn^KN?imS<^^5%`t6tAXMqnb(@cZ*AF zUJs!F3?)~`?yeBnvKC@21B0^aM*o0Uwr~+}EC^OQ1iZ{)kfE^r%GnyoZVQzsIAH~t z{^(o!JjUHf7_4!R#UAJTQAgH;7u4?6l?}t0O@_E}LlI{jL1;fxPGS9WG{n-ap4!ct zXprdCFvcXp?QlZ~?rE$DXHX93=F}F|Q3*oXGplr>BaAI9pJq5S2m-@-MYV0gq$xVJ zn3h&9B)gD8Anrayb{&9uH!68^_{ zf;OP6M1hHA3Um>n^}+s*=q}1G&e#j985EPqSWx~kebilN@YI(KDtEtM|XK1A^)@69`p-xyfcDjt=p74fqvKoRh)>OOR{JXk#LGYMS-Ld+Nv)ZtnL^+5D z9Ap~cC$cPX+%RR_2|ls8`q;{K<_d!6VSPhCcppU|b|9-xE~t;4bwMH%w|^mnefC^#_wz(LImf{%Gx%?0F-(xxf?0sPF1 z#*{e2s<33739DVsqpPIFg%#1N#e`)ZE@v~dSXrtMG^S!xf%5Zsqf(3=6yYP@150J* z6s+XBec@h3{Zckg;yzLj-3HEkW4HxfpB6qf(~WDNq@AssY0wi+XikHUf!|nWF&;Xd zp7UE;UbpfMUI8A4w(&d8w+nfw=S8*u=y;&HDrhs~3z~r2W%CcyVYLWuvata=1n-j5 zy`c5s+S7_V)t^43ABLLSuzXxuyJU;+R;yzkhB_j{W4M)z1717oLK@1-Z%=lnv`>_?#Wb))4TkVL5agRj_-zW>XAoNB5Nc+Y(-S`IYq7fAcrq16LR|1yEyco9z2+?3}5j0lH^2F9+R-A#^_+xBn1o6A z=7#5I@%0)OU(n>B$DgY_;HA;WgS1|hKTN}Y(u}W9fB!*|zsT~DaBkX1V$6x>KYO;Q z4@cME^%%v|*Jtm2$uggJe5`K_-Omqytaj?-(f)Xbdg$ZHF>?4CBA=u3`K|A$3jzmy zi^nOK=hBbgc_Y2^_8Vz+ZACoYjD$~D#l?N%$* z>s7IFC{*IiuY0#|q`P;nEB`$U(D(KZ($%ZCQnxouo15#lOhI6Uu#SyNVReG5q+F_$ zmsIa5)f-_If=XNv9;r@63qKJ6=EdJ42x0`s8YR{w^W^1Ce5_{#LalY|W?j#%IN^|f zpXCDtQ1HN;at~!nF3n_ty7L2}-=^7FkIPB~rX{^I zOpW@X;m-y%aB|!aC?Vm^eclRvsBdGE(z2FBnSnqZ0V>LyrtloaDne8&5Nut808w@4 zH~F}Y#ywgZI1j#CxigF9ncAm!cpCkN^##JrmdD0C3LgaH2vezu;Eu4=7I8UTT7{w} zU@7?Za3eNt<*i*6DsS9>vCN5c%cfJwXYf>n&wAI2MU)h5>J-coDASJ`J1BjqbD@Ax zJFhxv-K{>z%$%gdy?g1#XTMLi!#%+Y3j_q8Y6ES{Vj+N#9jmHND4q9r6Ur_uH*iVH zMo^9e0G=q^up;r9d!hrZ=}k8X`a;-GoUKl^FRMQ{oUXHWBTl~ zo2Gv#^}NRRSXW#9euNlSv?0F7*G~%;Xe+Yeg0tlE*^~6%k6uZC^Pk>J>#LPi;A}zl z0dkL_V1|&IR~Qql%{v-1D3y@k0235MwszC{nX$n}3FZKZK1$N1B`j<5i6bixIQL!Y zjr+n=1n&sb=>cc~LUmhMseiDzLYY;!0t6fhxdOO^(4MkdnoG!w@qjh2-G>T~3d*OU zHU0g2chvt);lYvTvu3lQ@`tHVD)<~PtQfbpZl~+lK2zR$PxBI9e`*K2datcDnLjKy0B%;A4}@QAte8`IC#i)Ms`6zn zoYDB`_Hc#Ac~P9N8H#&0mXJ3JX5dL5;})^3c`R3`sIZdC1(#7)LhspdfFeXcHP2X) zY=scYkYk@$1>Eq+ge8%W{?Om7=B{bG37t`2#E~D+1eA236?9hwUYP>Rj{3YG3Y>f> z?52g&M}jdj6I?BNUI9L$C%95%PPe6-X=czh?qRj;xdtp?E>QW*4e%FiKrx-msf~jKvsnS$pA|iY?+98IG>x-G;aR{dEL^QX zq`?Z_#Nxm_dz5m*!Ln%6Y*Awh3s=z`l!3Feq3EI>Q?ys}kF#Lj9n%L8nQvcnADJ8q zebFu+>5uN>JvJ}EZ_Vbj9v@hXt*x)7%?lgp%B79;;)|EkE3bYpUC?jf!x1(pFL7-N zbVI31oyUJ}!YEME^9|2JN6&^a{XH9>7M>-|>2NyVKZSTUz`;!vUz6~i2t5=8m{;o> zMvX}yR}1)j^^P135D26f$GTuLXVPI8WqfC>D1+JZ;<6aNnDa#ztc6spV9w3X1~Em; zE9uHhFQv5iEMkgbD8`H<%r3)}-_!$U4Mxl5t3E7(J6d3~ zNbj~gwk$gm6B7A~vg=}~MRl*sd(WE;e@#JcfA#xsq(A@5zf8pv=LpQE%ECfgSy@ht z`d(UCOzUf_sjO%81A+ni2L_%UPd2F*lWC?!dFh`_W0K-Su#S6N$Mj`|7C-sc1d3v7 ztoVYFjfpiTTitnZ?ZY%(Mr5d4&WHZgM|>;9b0$!IIw=Vib>EDR@Fh}GQzg(p4EsT~ zY5@yvfoUG^Zo}>2($bP}8K#ze#Fz-rc(%W{mwx;H`{@_I_(i&Q?bc`^HVKn336t=R z4$n>T_2%oZ+tneoIq35f;)6NnVSJe013UJt05-PXE^Y z@x(ffJDN{hF=f;kDt-;jdxL78aLMsT`ZFaAAkCq2jFm)Fvz zi!a#i6&t%)iXgnR!UJox4(BZOVt2ptfuCiA*Nl}r;1&XWtx2+256z}xp_mqw4?FMK zMUSAJ-TCYeXV*KzOOyau^jLf~?g)P%5*Xc>26oC{X<$u(A3`b)+_y`%De;klf%EV? zgweZ?gwZ{OMhFVULtA-Z%P#fH5!NQ5d?Qa_9Rf50c@MN!!gc(S)Z~!*$mYXM6dao!CH^rV%vLU%&}rD~b(a24GIY)qcw^{u=dt-4LE=Jo9{Z zR~|qn-?yp zwe?FWD_q91jIo6hAS^aHyDfI0hv64%`BwvKS2tZL5wVH?N*3IkbQ0WmYGqzS%Hq(U*FIW)XSNXP<>2y+G z-_RlYmNHRrWo8%)T00&^{Z%F9pG`U8k6ld)2k1ff7vs)KIQs5b{nL&yp$gIOC>{o) z8Kz6Zi)^l}_mZtmaU*H>aH0{w2xUpLiR;1zuc=W29PVu=+~(U#EsvrC`arp1b%QM8 z!;e2nfBRqmA^pq0{yP1~uRl!JZ`|?PGmAS>aEoA?1ah$^*872Ix~3gx!{hU3SXbzp z4_)z%f?>Hlo4)_*#q`n(xF}E)G(?NT2Y1i#w^#U$IivNW{YpN^t5@-QN|i-LM-`&bFhx zCL3XUJ+}c^b0!mDgU0BFa8&iyTw>ZSxLTpEvJG{$4f=rLFIwwiVSrfl$u`O3;j_hp=)MzOulzUWKCay7gAgNAB8 zF-=q1c44IcZZ$a9kWDX(R-AE0BYhnkGO(D%O<>YknN4$ra+=EE&UV_g9eOz!ofD=E z-NvB7Do^D?^TBP-)MRtQk?@5vjj}H{r+oAd3L=!RR*X|O-u0#c!Bx10Wu`a7=QuNL zUN~5ESw6o?xB?z~o)-Pk>uM98p%|ZJ2N6Lo1#JirrUOg~g zTb{)nqx8@KtdW5obF!6v;H>Z*SWx7Lzx!?a&98ppKG?i`(aJ&U4~@hPClMxK9VCp}- zVJJO`)n}lQuldOzzqzmc*yO>OfY$@p$$;{a>2WMhe!h~{*Vod<>Z&a=Uw!3!>B7c_ z+m4kceM6*t=5v?D_;Q~_sitA7(}Oxt0R`?oDV`V3OGhNcm_Gl#Nq97zg&&wSQG89p zcO!`Qbj0kzRO3Gf|l)0yCTv6CcNXgAOEB_(PRF@rz&f*&#GU|gje(;0zF2oOhJloEwdhN5o!rxQirdWQ<-8JT=#e1IU21vGJAZ|K9j?>xbt zm>I)gG?k@|xKTi1%A%$uoc1DK?~L1xAM=kt`6T`Hr~jCK|G~#%RA8zmVG<@`629@_ zIV!&12#c@Ji54C_;T{zI>>tn0d*^I?mNZ1C6Wu?1UmvHUtMVW|xa9hD)IBcF=JiM% zzx#E@$I2T0{xb1&{%51pJPyOh{~|n=?rbE@R}cy3-GA12?#;)dKF*2fwo8$4-u*8e z$A7*yv!sm0`_K=%|JTmatEOmpo zg2%JlLzGL(_wJoL>En++v~YTPY1w=v)>rWVoEuUov1>hCxS`NO@H`L?Ca%rO3T1Bv z*TKQA1$X6A(Q6FOZNd#2Zrs>e{r&I1=`)nxc=HG8l~-R;o(N>~UMt|bDqOK4SWAiX zM*1oPrI#%^da-jIz7L^FW-2pUL!i7F3HH=xb|xcOClj8-Gor9T=!*afAwB~B+$?7d z#jbhc$#F-ZV;8=DB20T=&4iE*fgj%?c(USXfLkjz2$Cj*Qy~xvoH#$gH;8k3;Q@QAaxnzj}~xwWG*4)=G2&pj)hvA)1+6PJRx1Vz9a zRx2oa+a5!V0W2X`S2yf33`HMGAtK`ttE^Tttb14!q3l2*Qk<`-9-Ox`W$Pb=_pI>| z%p>?jpl?@d>Mq9JSSd7iU5EnR7Bj5<)qcjEm3;<*)^Wl|*SE`AW0|zDv}h&E%Id{b zDz60G=x^4VN=uuKBNV7S5O5;|Mo^BD#)5X?$(-7SE3>It`U|TTjSrN9pdiXu_1V!d zEG?)Cw2gV+n=>`$=WXdDoS4yikUl!Wo$H~M`D3dd6fTwWVp777(x@1k5{ejuGKz)&){Ova|h*9@`)Xg^0^C<-r7h(L>5^=jI>cgGtXP;%l% zjSUwZc|lp=7JZE%A8Rd?+1%@N8p7>b&|sBKi@~Qj&k9SjIA0FeiAyW1BL%g{#i(9@ zk+})wN2}TJ_&`3vnM{l!Z_HL?ZIAUCa~Ja>3X_9_eY>NxJd3$(KF+uYc65nqOy`JX zg@T6&?V+w#_zLzY?!cYA>I?j^Aj5kS`I|PW&FywQ?QU7Yl~q`@f-~Oot9-JVoa<~Cg`TUh=t2?G5*@kYIXA0xC~0DI z0*W<_ZH-Bk8`GI7!IJm$K}R*VE#n)_Y2Zw^T@~#)5DW$?OJiL$V`^G35{*PDgNxGW z2W1UiXX697BVGh~klhNR)KR-)P8j1o9mr3{VlFB7~-0dxfmYA${Uv~xK3kLHl1!?yP9rX`!wZ* zubY=dmqwey$pgh&&X%}YmCqcnb`6`}OvE_gTsHcXK-;mBhAtAYC7_8H8@wZorU&Q^w-u=HobZqqkw*2<*ueUjwD4N=J2JP$#l`f- z>)%g5di#gz`Va+xa#m7XFb8Nqxh>F^8YU)ORYOFV2_SaAp{VigZ)|{>yYk|T>794q zOG}!JnEb;%j3yWu2EmyA0bWGr9CjWVex9IWGGe0eBuN*Lub7&#lF5oN`p63dlv9ci zzIBg&;h7a*qi1@TNME@x9UfjgZ=PGxrTZ$Iq9~A5@KIE5Jc03)Kc4xKAJa~*SOCYu zhTkal5W2t+2@0{;6VAd+5zH_v?Ps5Un*Qs5|8MCxzxr)zw%AoW36n4hlklwwe-y=6 zEQHUG=RVWi#QpQ)=`@eLb0+HJv3uvor|0v;_=NJmNFBdSe59PS@w{@sOkL>E^X@+q zo#b<3Ts;2n7muFsW5$1CJny|P5-H^IT)$*Ir<}7wh8`~>#+a8U)1_^}}LKK8FD1r#^@d!4(i&vS$tCOFDzOih8KSTJ98)y!BUtL{G zue|bFoKaFLTgXSgyvw;>oc|l{2tydonM=4{TU=O7t#&KjzrSTZbZvdjeBajg{j|Tg z&wxbjolIID{^ zME&MH9&=l-0SlLB@q})kaK2eB;o1^D+?GPZg~)?6L;{%*#&sZo^SCzb3QmIOYzQgG z?%}bN2vM1W3O^S9gq6xjxp{;e%~AV&U%?8XasKexEem0RKW8itdTlFd$JRK&J(OIr zMzLiB5x64wJkfoG_g>3n6>+o0*Dc!-qsLULa6d~^HGaq)X)+B?& z)T-XI0Qulx+mEo2^qFJFgT#3`je6Z{TGG2W1mk118Sf~-1qBcSQ1EtlcPrhval=X~ zd)iRhz#YM^71*rx1c$N9FqF@n>&3d9wKwY^EE%wPvLIV&hQnTJs()B3EiJC3%EFRi zi~y6h8-i67U##_Pp`vohr(9XG;1&Tqf?=;O1@pkqP!iz2tT<9&GnQFz;_6b6ve2LL z#aM%Gph#dn-suUS?d9cIeT8CNb<=MwO6imNVku?jO1hp`WX+Geuz~7{V4pFFqOt`z zQ*IswV}{|#Pr*kpp#KE_=wHG82!-gO;3Qfgc+>WR>R4G^P1(66;rEQ_NmVdDNh>QG z3Ab=zX$GD%w#a{&e*4?^(?9+5zp9T=G6DnPtYF}EE-4|jV1RK}m!tdVg`mZwbiN9D zKf3Za@TCQ%VlMsFU%r?A@-N;_OAA;(4c%7oh&~0kco&%fu!bh1=wYp1Z#GiDH&7cx zCV+wx>qh$5R>3NP^SI(HxH$8Q(rr1*1_)@q@Pl!T<=$cSF!eOHaU)9}p=?T?FHo%6 zt)OloCLn?X;3f+8d8{=JSJg%J#N{D%vSp+CbINjtL8?~w)ArV#w7q>#^T%##;o(J< zqK(Lk*4H=E#Y>mfS1YPR!L$N+pp43k9#j^WEFb8qzxOn+VbO$j8k;YeM}Qe_^dM)p zqS4EEfr&91?@8->$dPY0v-AB0o1UHMgI~9%c z`Cj1DvF0qna|Xq(@Cdh}DopLbY6?Z8%Adwks;qtxyo7sJI(dE(yp?zLu$p#um|Ht4 zGv;=hLg%3ff?jgu#Y~p*ftA>lH@G89LxF<@;nXzlFsrtlQx>XcQDs6SQH&vfLm`F2 zg*pHq&Cd`b0Swwsxtw9?%>?w_k;b&>6|MlMGI_nH`BwCV^FvWww%Z-m?N~4j*R&^s z_lch4uCd>(TbWDKJxAzWI-U84`4Ov3&P1HaidWFMa}b`i@>eiJ4u=w6G-gKgX;!#sOKp`0jpyhR&N5?u zIuieZUWmOYqY`HNNs4>Ad+wv=Y3r zbr$dzPO#YnxmnPA3=~9ng@YU;0zJ96wUu^u_mnqsxS)MxPl427JWgG>3VTquQSh_T z_xSpB7~g-=^Km$v?rCYis&HPJ&l>;K0;71M_?m?8RA6z#fr~Tje1ITpVB)d_!p216 z#g!*_4R#Sum>f?eB6e5~k%q|?rU6rMA6zT)1|tO{68_n7cY$wZc47rX;RUUJ!(cPH zp$}m)g<v2fkk z-OA!Y55A#+9iA_L@0IlSJMW~`)m2Zlv1nw{3c^aenPOr>qOm|l&-f+{8Tk(BSls$T zlf2&1O&B5pU$BGujC{P4gTkyVKbGA1=kIs7y-$XYmtYdhQ#aWMY;T-p3;wYr<`+__=*j3_#AHHB~t0Vn4Y9qjLU3az5{du;PVZ{nf)YgmB^Lrm&NXwl>p6-~eehIids^!p z3N~%^??Ar?2{%ZjbvoCOv_#70_c)B|h@uSsn`cx3hTOujIZUKsnR48z`)oP_p%L6L{1$&MHgAP+Enh7p}kp53xM(J^i5o zvqDF3_QpPh?eO!4!HL&#uD>$0i%Z={fSI4Gs5%w>#_joum6yAUQ^&o;87=vIQE){m zqcvs*W#YK*e2=cxB$UbsusM%sacLu!Dx3v{K)b4S#DUhG0}Dyn9UuMH6Fll^fBUm^ z@79NE|DozToi1N~!2(k@74|xc`4^kjlyjk1Hr|@7=wrG4ok!D^Je1E31B3$^cu|*L0^XS`h9dtVXa)j|fM1 zceedLeYd)P!EFnLprVxl2!gftxAJM|{z2)DfEr<~$D-2Mxtb(b-|`rtl)(I=Z|T4P{XePhoP8x2>kk^B+88FL-`wK{gN#mjLhv{u zI7z(6-#A2`8WS2rm2xiq`A>eBzW@D~Q=vE~T3EKS5qykt7m}qgR!r)eH9PJt z5oY&=TUc#j;cItuf;03T7l^nwq-@edf4ds)f(~$lw3R8JE~JDRn%62 z!1IjpS>p`LHWU>ohd4J8#q88HxLXq33Rc`q&0wX70!LL*$(#*|+q`b;&{lKIODI=K zZ#Sa)jWsFrAIdP?4`ydj=!9Yv+_k0A6xL5+5ltVX1n&1x#&=S+wx9O)w%p&G8IL8F zH+(2e<5HG7O=ArNeNg$LlgO8d-jw6HfT%f8?ZuTJb6hA~kQH`pMTEkMGdnrQs!&== zS-}KCz`V((j(Tm!XA&~*&2xw@Fn0T@7qlPRFr)g!xnAlAwaTed9Sa z4S27wt)>eX!qSWMC@)K;71KTN506P4*MgNF3PG$Dy(xjYV_x(@@a{Hi;tRmVJ;7jT zC1!DP&3)KyYJ92h@qPu3gkFUkVK(v5k?I2>jpe6?(dZd-k&umzJ8TTXa*wm)*i>?S z)KMFnK87Z1E5T5R1y6x2Q+TDcQ=(h&YJi&D>2x;9t2AF*aW4EDJ#_%T;R3L-#>xwJ z1ipoQj}2?A__3-k_!fyN|J67$01j)SfHVqRbxVi#V{E?4YsPm>IjiA{4AAcibh zY=xvrdPEsDL2EMAqJTw$YQhxZ0S&QcBH<3>o9kIkh`4NMHCy&Q-fL^ZQ62DQjq(h} zJ%|BJs~9%@u>in5^gG0cm}eeI1m(%V0LJFRH)LD)clpj4vIm|xX{zV?Ei z8OJbIfBI8Dqboeo#d|O>!K5QtL5N}HmcC&;Z0V)Qe|Xi*(-h!W`C8)htOFf--u*vfj4GY~?5m2;ql|OoGnRWgguvC@l6fP9n=2~|>D_mKm@Z!2 zw1A5+5IgbN2!t{VUJe&y2q?TUNaY|HV+TBL3$b*e9IUoD zH+F12!46~&i^qxw_e7le5(3p}3u`!w15Xfaio@DtYildL|J(OdwR)K5a#^nxEZjai zPHSr$X>H@8nlfWW*v`&Ob@d}~06f6s`Q3xORLDF_-7 z=i?gg{@vSdJLhq5W(-znC<5V)u{^*{50-1V&+~5nBluh32_J|%uC5hhoIiH^=4Z-# zI$gSWNibM6Z;3^~coQHn3wVTJi#|cvXE$nEo8WpZ&X+>KBN&-C4MFO|fQ6OTAn@6O zKZ+FUfxAib#|WsV)INmJdLLyJb@ke5iZvJt2;I@zhE^CQ+?-H~>O()k8DrZhI;AdE zCus0^y$4LKWDst_#*7;SX-~P+B1rUC{WPFLDM{ z-in+`1%;LJQvafi&FI}Jl(kqP^y+D71uXYa_AqaUGAsn%;0buCF@q~ME64aoDT{Sz z!vb`lM=sikTmafayXYI*aXf6KdTlQ?1ut+0y5-HYN~g?I?O;3o?4SQN{r3IeYwWTf z)wopkj78LyKYr+AyuLmg{CFIlm}~yxo?p>L+#xVNkJ4OzD!uyZ<+QxW27#{L)tXoJ z!m%{oOeA;J<%P`#Oks!LLCAepyPP>VLm{K z!~K@>snzQvD;?bI_7dm5ZEfGNB`vVwJU6Vt7{kESYj{BYP)g=! zRsSQszo&Tu3sH@kz3ueD`@c>f{PtJr`n6Bf&i1wySkRl*)pgP2D`{zY*-GGWxjEyy zV5!Vp<#U*PukQ^UD7zOb71OGY#tQB*=S4eL*Va?9h_Vpe7+E1|Jb?FX-ewFSz&D+P zHmOaxHiRBvUA(t{Ao@^L`-BUE3l`4E6u=WUfur=Ht&D%h3Y$%^KJK)!zQSc_Npvln zI#_a2zVZ)TWv-y(L*53>#5$Mx1YI2G{?!h5(zfPIHlVn_bK%0XFfTZlI7<;F#j)lr z+ySC22@9`5Uo>5PVws!DVIIK}tlz1+Zom-5V69d+zA$fMeT#C3Il(j={HKnLEzNVr zRpkvm4Y?g-5Tqq7^NPlmegb!&XNA&4_fVu~a-s`Zwb`0kaK_zVRykdLNpP#Uo<`WhzSHY2n6kubDpk^mpl#Pu>?EaLyu@u*(Un zP&(*H?X1@i1?OYWV>4=>Wuj^ua!BSZ>W>n2sQzm=)h0CoT08l;;Q#<0 zD$l`D&$JTjvfw8I{wIPH01k^(0%I=59p{T-sqA@P_rL+>c=s1kcy0cK`y-wJ+(qdb zbC3Y6x&ae#7WwV5#u_-zrYDqPCLVE4{uNt15?`m1G%NVU;_|rG{2#rl6F7sL9Hz}M~|0l(>0gRd`z9!+j7c^=0+g&pZUbw)Ri@@RnW58lXbES6x ziSWTd9EmVu6$X<4)5FeAm~;p$XM4q=ks{9`U@*N*5KN1ZGw(n%fsR24k;ClTJBo;U z#$*TKW>yFxSr9|&MC5 w?5*gMb!(y*B{?NCMiUJP({D+U2)!pG#F18)an266NF zO$Fu}Q_Rc355@5q_J{HZeHMHFA7CauDqeXLpH(&nnPe7$_CL(T;o+xHQ z?=XQoGX<`JIm~w`!pMYqR|!UGxfAcuXZoeQe2?^8@q;pXhfAmPrEWjO2j1hhKm87q z^OP7-{Z@=goJA=MFx7oDkp^?dWKRFU!?|Cq?EF-uYuk>T=%wuOpsnKjE?Ge}qUlU9YbrevvZt z;q+fcI4}S6qCOnCHV*|)#BW_&`JmP6=EiDTsLY9P#%=Ra%FWGMu!(D`W~=$&93M8K z!Pg^nLMVkG+d?Ao?g&iz-rwIz)!KoT4k&yOf?J3IKc|Q=45gQMP>VN5NXqW*z1@3> zGl}>OZ;ycI&fRHs_xIBz6&Zqp+~ z#0LmD>vn;J!Un+?@Qy$ldJ?4?)P;ajOfVTKD6x>kN(MJ)3kxg4vCTA-Thz0W@)IGl>cd#V ziV30N-rjxV7I=-|5UYc^LfLE3p5VnU{x;)6b;Lr9^S-JFJA!|>Q3NLuMsq&c=7r0` z-zD|F@JnL>SW;c`pPj`jN;sf?K?%&}&snX@$I2Ye0LvFbXkS0vPuutISip(Z1Ngqb zw=Fny?F!AFGE`6CJTt=?Uq|Zm16xlbOh-XrxBB3e*IywNWywZ>ULYf2jAGSNDq)F+ z8!x33&LX%)dBobxn-7Jn&?NdJlgT?RiZT=u2%R}g30Glpu3bMhYkL-OqYMDYr+xNb z*VZ8P4dVuvZ3%aXef5{{6ucRaqiOXK?}bvLWNSgw0pTY&isEo;3W0t<^-yH)tE{7` zw6eOP_AD7ka6R@f|MO?*zx~}$^}MRSLbxC6Pta$~-|)?isOe?1A1=9tNoj^&M6K=9( zpAznYD{b}V&h~BL;hy@CbJttW18Ydy))cPYzI9z=qUCXmn^0VAE-i1Q_01Rbytpc6&FMU z$M~VKE4X2q$Xw4DGB=3pWq3XTG?f2J%5VA>ygh=pqRc{3$$W@KEjGV;7m({2R%W<* zwam}&gmoOO2Z~;-4zYZLHt=V5L;mr{a*Uf+wY{;^vzhfas8HP4RzKF zB%(Z(;^6l*f|xrLAJD+j{c$|+-si>B?@Yqe!)dq?VSgryuSxh$28d<9!(oe>82H0v zS~P^6jxYp1b4$d#FGlAC1<28f7BVmm5OvIvwE$8Yh&Kunc59+!!c_*79kdT-3Ze-i z)sQnew4z0Mz|gQ0jCC35*+F2XhSFPYqI|J9;{w0EOr-26WhY%v3^D}YIg?O<36o$& zi~>xcnRH#-e|4XU$dA5Jft^*azwu^z_uY5J4B(zd%!~SkZ`$gKk#-3Vf~?{Q9)hDj zM)1(JIu}s+=?G@5gAG5JB+~ghV9G=dgJh)`&y_b>I*?{m4#B-k5u{STJm{0rvj^9% z(}>ykf4uk59U=*15#e(#{3pBw=U~uB5P zx5;r5CSejL;oBCTo8s$7Z~fqb;_GQq9}nsGR~=bAop=As#1X&oM~{D`dg$Y^dw+~b zIPd=Hs1H*8!7;KpljjqH-#C-@Y4NKFQOi+?3JBj37^n>KUI^9@gw5w?Qlohw-sZM` zpQPpG<-`tccD%Do8orSC*kMj&S3ZJY@`0zrJv8pyu)IRxhsA}@;}x$A4+YPS&<;Ku zejBzLt1Nbwvo>IdGvy%kM4;7ZG?mwG;vA2qrGLGCrMr=C7`j8cyOBm3$$>lHz4t$y=bW?lUh7?ZE9!Pkn-^O( zrvW3@uLf=YbX|}A3T%EG+MkI14{QQvD0O9{#n128TVy3Z$DqkQN^F!D3F!YZAY8=S z6_unt4WGdY#sr{%VrSWUV?wMuTO^#PS4}}ach4i*npD3gCZ{q+26<_P|JD;p1@}!^ zpW=Pr07)(K25O8=vj2JmOIeWj>%sNmXVokqCM&f_N(dAS*~S0KS)DJ65A@v=iC5^H z=D&;^-y=DQTPuAV^w_^^@^)Ly^C0eL?hw@s#Q99wwwHS8jV&LHjNIm9n#^!kjBcBf zcQw#4QRWhy`lXE}1~r*ot|bJ{5%{!1hbiI@AY?mc@h(;d?j_u_@UhG}wPc$^1ok$| zQW62Xo{bI)+#4HUgY&Slx+!FEP9Rdvuw?7Zv{2+jvJT$fA71Vds>nV3@@_RL`ywD>OsJ7?R4GB8G8YyJe z-H9^!-n3J3#hj<`M7EF6YR=o54ZCLbn}XA)wIa>(WFoR6eW`mmfS&yetkkWE%O zbXf=x>}OHpA$HBDH&Q!-{R~~P*d%>iF$8>Nhyg{_$Xez_)TkcGi92#T6W?8e{}pz+ zPjh+0(;lOswqXZ`QjQYAZ_cX!JOad^mByV|6`4N6PMPk8lX50|01*VU$Vkkc*xRu% z&DvJ&`KuJqADnffc(LRSPXYTj^!GW0s3OO>F(^|=@Zxpq1(@LDs^xz&%kA1iset8s zCbr?yxoT3K`S+*ym-V~1mmZxQT_@N|qDG0AXahfsHi!#*4f1!IkXi&dW5H;#M+!Pv z(yoZ5bX@}=lv-5zFqikfiZ#FHDq{}1`}_#2REpROUn|&4BoygIG1WdSsY&iclHjrB zU!N}D&p3>oMdN%u(oXywY*50!!tI3ZO2Ux+0N+h;cuO+<#ku??oB28FfsiomYxQ^p z+OdmVz>j%>e3W~=$t7!V__g(Q<-CCB7k9|oqUuUH`^%{?pXxm29jiII{XU_Qzo4Pd zuHQ++UU)2faY+hBVt~P(QICsKlkYDv(lyCwUyfGOHrN`s_;X}?^TRPeFUPX1)|$4& z3`%ESR17;?Ota7^OW;_MUbTKX;#U1GtRPMd>pr=q5lmKfy)o8~3v;^^MK`#+?xJYoD zlZIPhv$4y?AOU)XweAZJ)yS!-W|cBC1r0NBiEfXhuVrrJ@CU46Gvtzl0U>TmQl@?_TDQ^)TCs2SF(te;KQbN$5NK`z zu5!bG2Aauhd4(LSY7?DzLDr^VchhSb+I&JstjpP7ru^g%+h6hw1H_?}zPa>FrSX1R z{5()(!LOnOva;Yp)BzZLFW_{@g~|7rX2UBQ&$F{OMQ6N#LQLYx#YW!?3^HBlGl!y} zamYVa+~h&##ychxpfY>8ZHPN2OsYt6_zO_YCYquUHS)? z-C&TEn~5-ppzptg^_Dz}c8ft?JDs1OPP~-=cVxT|m94DE=KuSsULfM5cBKN6%}RMf zM89zM`M_-AxrAvmV*J!rQ8c|z`Yo@>fV9veY<9X{u1ip4Zq;4;#m6YjWom*{@pl{p zwWXvOjX$|Cv{^Ix<<_Rd1P^TGFLuq=SmrCJS!phM9er^FOltt{9dirXQP4 zP9k}IQ3$%qGMY7{mw>n%+qxcQK8Uygold7ZI8?2|UNN02KA-MBn}*Ah%l)jJ^W!XW z@~ksGxvv#}U%oSb8xQ)jT)X|R@ zvCscDUZw^Avq@POJw-(V{~-->KblV*zLon0nfR-VJ$s*TJ#pe2gze-HKTsZ?8McpP z6NZh`ce35Fn(Px_bmENCG)aF6R!!Wfd+yEoxk))i$bv5mhQC~K(C(7jBFhxRF4Y2P ztCuu5h`sJOZ>MS@-#ZgDL-DayEZ>~wh1<@vy`Gm&G0-NR*+>17`SGz(Rrtgy9jDb2 z0`9IyPRwPJzpxwmaCSY;J)G~M)AbgN*|m~7s`wN*P~(Phc#A#?!G~1K4!}05PDLHz z#g5h-E2P!@3M7r*d;&JsarMhfphG)=otc(kkzosUT#yq=Rn-Y2KcY_7;O$gaGcHHZE3uL&HSyTs z-tsFGl1KGCng-0rZR)EzW_!iyvsR_agU9za%0;aCEyLw*Z7nTn4-V6k4b=|9w2&^U z8^##mN8opGty6qhg^XP~h@oVY`~cGwBoSNYZRvRZs_;5>-0tMD*#2Fgo=_PANpBW| zUMGX^hC9vwWz0D7uDN} z2%OSQiJ*4os0YBeil8EdbpuDS;jJC|h6Q9sWA`$f%fm-BE+U|5dkbDk$-F_G8 zx`q%gCW1r$5XG!GbhftU{gcUa$%}w81M@lg?JX5OJ!J!CmHayVw42NbVm^sZomd$~ z#SdpISXhQi&aA2aGLwly(_%rvS)tV^*jC*!xerOfc7%NM>DVluqX?Qw+uY1?cdoN9 zv1knqH>ZUf6LfzM5&!MQL?C-C!So2Kt}&L+A~c?R7;4J*DQ)W2RV6^%?(n4?;>rR7 zQd2eAtYgCOwHg`yWuj_Z%-iDn9f8?>u2``u&bj;i&cU&k+FjI{RYI;oP}@&+>RIN< z%7?yEBxm9SlG~3NS(w0}8Id!MRr ze52yS+VTPMg2NOSRDz^m1(0>oIl?0(rkP@ypL2DLz+W`|;JNYnwKZES%PWx$TeSdL zY@g^4#7hK^q{G+3mbvijjQVIT(%UH3szv%?PM&XVXmn)YVT0^}lH#>^qd32- zkE38Bz)tn-{9hO=l7Z?__lK$KLE>OgN9a!`#c8738Mj3kG_}Q{5#wXSWdsFY%a{Xd z{<3d9YmR3=hZz#{bt1$(>K*lYo-IyK6Q7S))`k)G>G!1gFkP(3FPIaRN9DkYa~k)^ zLq)@7&!nI|yK4|TXYRMjbP9F0Bh^eone zHhyqQ=u@kY3t;xJE?o$m^*WBXk;{Fm-29@yzV3-<&jizHTUZ#{&Fc4&HvIY_y;hWb z>g}z;)L^)ASez$2ZTZBTFFWnf{k0vA=>PIQVkT-sAv{$*cceq9>1Tm*cs&3%IS8%3 zH*ZC}=6Y?(a{E*5mJ#cwTMCVY>A`kDMM{zB2i0b`axQ;UNa=U5v|{< znL|^4pWG;uh&me^N@@y6pmoPR3>I3%#L|#b#1QUD|4h`2t)0#|mto9tO#oA1fIyFX zWA)?UoPjx_TLNbOba~sCx$9*saR}ss?F1|l=p~~M{esvt5%Im}#WNHd)S!(|G4Iu* z3a;_J!Kr(sFG(>9X-iRPAL;*yZ(K}0M~Q7wa%3puim3beC3i|cs5du%4-CK)2UBlmTyC;Ypa!2{j3HiJI_O;yy z(sFu%`oBBckN%_sw;KMComG5emAJ9}^6O5oso~o#VbYX~SYXoKH3QC*@a5alFgxkg z_-$pvG|}g$rq9TqA*Mk`;kV9vw%6ZDL|xxsJMVU_^9Zy5Ewpamp6$P?;A-m=vQ?E) zzFoz;KiybWXvzbg|2ljv)5f!}q|3_*{g6a{U)KYOiM5s-9dh(|bgat5_HHa9twezr zyaJsovI7WNUndV5Tj+NU2ygWC^y&{{Zvm9?DNA#E4G8yFrpOXF$8~TdFrpoGtkM>Q zZDUd&Uiy%F8ZB4;Vte=$IWG9YiR^vt-pK90>>gcQOxcH zQtG46Qt3~RBT_qk)mwoTNM>p}9byI_;mJ-=NsbVvNxOTD-|-ylOWv1zqw$7ZvT;Eh z2Dy4g{v+@b>XEzT@VEWOQm%E$%I*P0QUHxpFetpqoQ~9c1R|KChTN+69NmvPq!UQd zstin2#fHwD=`|oHjp)`Qq1IsF$DTSCiSquJt$49d5+NSnPN~TXjiq)!#OZc0Qna%2 zpi9(IOkSa<$DfU^eXyt4vaDt#$|oC7t@<{!#%cTsr(YO&0a~WoDRJB=y0}BDj&BTd zenL=Gi?X;SIQU)KUZWm2bt~~J6Y+uzKLBzVj1c!E3AQW3(5g@Kh=@MXyHdo`1PXWs{ti&&h^1;WOBWRmE_r4?wf<*&Rr9zSSJt zT~t()VuaC*mE9LWw;v=_*+kMhBKNhq%dRtb7G!nn1kMyze%}vzWr5u2^ppsZa3fz3 z6I#Q@lOfb5669v1KRZ8DN0ICJXB?s(IhVD7L5kx3`*gDlKMX6h?6sObfFk{dUx)9$ zd#Uo7{SK@AoIG(SZk;7@R4|!sjX*&=W7X)=Lpc_e)DvZ`o)O#d4m5ri5-JE}PCT8+7(#Bk=gZ zB0U@P0B_~9(WN#oq3JcU;m9V7bL18+9Ct~~ z!zql1s*!9o&)rL9J8|)AT3^f>^T9{{7nhkBYV2kebXCMfi$OA;v*OG}d7FOoX;;Y@ zRFFO}#!@B}xh^#hTVPqk02lzV)pO>5j{wL0-Q#PqF988JN7X$5Hxb!3#e*(}A)W}Gz5WYKMysM2FG+4)fTmUx)uNwpR#Nt`Ge;ZLm0=*ym_}Q@g{H_lX)*} zu>?l=-F}^wigXnqw%2g2O$Nj-2WVXaZC5&2syId()NBw$keAPsohk7U;D%Wmboc2X zv>P6xVe|F7GH#W*5^2CRk>hDe7YY9jyLOK=*|oKhDH`UmQe+-B{=j*uvXfHVjpGNO zhiS2()WkGS zSTGfBwvS)1-5Y^?OaTDqZrX_+=rDPQ2tt6hTvp3y@H64Zc?hVAXmQ%;7PF=$^$oH= z89K1eBR*kOJ>@t2swMuMf>O-HLV`|Li`ajo{UBw@wjptFvN zo?a`VoC|chKZW1zQ@(?KUj87GRUFmroQ_@%3m$x>0R13oiTSODZcHe?&BC|(6!J;c znOG@=gRVe&Pk*8p)K_Bv+&@NF61z$1l1Ms6H#Qq!f)>`ME#Fn!0Let#p_w}kWhWxo zqT*;1LvEioi_h`C6IW#KsOzP?g7bF~^IebO)(`6&Y~&y*)@x36+-|QP`dtf6AOukmliZq&$igWoOTY$n|UV?^i2b(12_%Hf8M@VcZdc7d_MNk!--}nc|jpp%_KS zgA9#G^f>W|+gx_Sv$sgX3hKMRbHQD=zX+DuN8$HX0X^>i*7=ZH12tndlZu47JxRf? zhb^r6ET`^FZEZqz*>hg`l$@L#cOXU7=5%(f8WX-o0nyQ6Z^Z5%ic!pMRMoc`VGtKJ z&-E(1n~M=HtQEY}{5->0Ys$rDm!*zw97EUz4|y&cjC@Ih$v84*aak^MtfWL*(E21JA^11 zM;p9bqt>~*A|D*@3o3F6L>nX67+S562mFEv@?jJuDc)7{WnpAl%9#IU53#ElXL1i>?y3l zZk^sIG1Z?0wygpwbV`uTToQ?nMCzwDx7T?oiWGtPgemMbU)(}?&!np8Vk+FeJf=29 zR4`oz48ZEC0{0s>fqT|4T$9}ccV>UDAcTL?qMp3{W?Bc4>o-D45VXuao(iQ{&bZ$9y|4Gx>Hc&Y1b~+Elst* z{zUCllf7Uv;ykzI1F8IPqmB%_d$?Uyoxg|Y67jZuNR`SRtXglylNO7JB?TxTW_84d zgv7x2jyo0c7oT>wwA-*Sg;Gi$?zP{E;F}7a;4;;(0a-QT-~;S(S;m4Vm)&D8`1D8O zGySl+6x0jE`niGdjN^o1c3S{bN>kmpMW&j&8@*eK65pcowjB=gn5Df#+-Kw(i2;_M zYNXP7^PebzVa~x`Jn9s?Q}Iu5#93u{E?@8r?Eez3AnrDv|-ZgVeNVA#b(oWC`MycUw2(wJF&HYkA6<)Rwddm#aqR8 zgyPfrGy)}Vqn%@w;DJ+CUnL?#^0=>j`^!_igB5^_zgjIn$_Hl|cC2Y4AXV_!0BuP* zN-*vy30<_Q$C#&@9q6VUX%jn#o$052euBRY9ptZ-y#S%#NvlAv>3qew*!j`bJ2X8f zVnWoS4XD57dH?%8U9-;nx>CWRDxb^_B&u5jQ9jXfZH6O~%~VjCQQHCylTE{eK)W=s zte~y_$Yr7}4VY38G{L~F%h&%a4sWuD6<-sWP{(BH2wO{yUih`2GT99n=Wq}!sqOR0 ztH5Wq^OCG8@-N zZ4a>?5-FY_N#g~dq@xE#tLy~JrpAO*%n74Uk*+cW!)xfSF=;-xq>}x5ud~b2&YMX+ z?Q1c-;dOsqx&+IOJgGUwQUY6Ec1oK*2$z@Ax z7&JQ0&q|)xJE$;?`brgN$BxCwI`xs^z{r|?7N9M@vu#iffJ!+s2BqD_Da*w zOEaO$1xd4_`kc|f8W#BRU^M<5nf{d_r@HtzYhZpP$9_<4Fh59JIAJ2Y3WK-zMdc|I zJ*M{u5_;37`>|K{gG^30aj@a{%CoE!2Jt5sy;&McdQ=TRf1l|L7xOfx4mZg*BoXtQ z5SQ4^Fh!QF68I`n9J~JIVp}jXc@OM{2&t~`wSK_oroC~LXZxrPtKg|u|PN$2#Pao#@;2sl-97iDY-(QSJwi^-V0*w4qowxjqKMIMUrZbF` zA^dpU*KBXROf(nqm-l}>*zp?X-wD?GflxdWO}?GR{MQAD;mb2 zjd^fb<-Ny3=q+{AFQe4#oAl4C)qyv-7eN8lfD|B4mlm4U>)Ck9)9SR{ltgdi=b%Y%OMFcwfs^HKWPSagLj{bldxszZb-rA}zbUm!btrn$^-cS+7ZL=k*; zxo3Jv{gOno3bp?SFH6DRP3pgA`k=+5R=ZH%xd|3qo6u7WYC702Hy2^eXA}{b@IXd((FwV)zDR1VhHtRf24it!iW84Zyh& zlQ9I#KRJzcx3rFahpevd+t}pZzvymwn1rb=7?@NGBYPO$bES&?GRF5i zxl2Xs(T6iC$j>g55e<0Rk`i^`&P+BV|5ZmKTO>&AyV>TUX-mJ>*#n`xuTRV7es1(Qd2mbAscU?0lTS*;ETofn<ed1c~EgsX2tzck-3P7`S4_!e1Fk$ToZF5NC33sunR5rYs-Uj)9P~~zc{2x8SSmJ$TJ}g=MFW=0_^dE>?J2Ypb18}dhGRCJ#0XRw*GyV zU}#K}-r|B9`FC;C@&hX0SS{T9iHi4psTs2UgttVVx6!nx1i|IoLX)r0E+Gi)Sxl-l zrY>OwrNgnqoPeOl+y0{L<8XpoH6(8`f=l20bW0)^F_M6&i67r+BD>4Be}%D{q`1o8 zx*G5ATx@39+P}2enCJ>%iQ}_T7bF5(It2&Kwe#`FoIOUN-yecb_%Zn^Idix?65D4+ zY3S-MaCoE7szi2eeG@P_5tGQ2F)Y=CVcuoxm9!H+);|{?n4v|otA0T#p^u( zRd&hNU%P`7*!$x~nuqj2bpL}caaOph_7l41Wc278kreQ?Q}^?|#UU=d2!O_O2_*3R~q4pIcAKWt(ZG3fh5< zJC%4IqRlS`a5|#*N}D?xCm~|W{mVF?vZD9wp_U>CY)CM+`SsAB$vtGN?_VNvXt!XP zB+FolOLF;q?CNVtL!oDe&Z%Bb3;<#YnUF+Ygb3)=1eHpGlpRz-yF-@v`w zUa}ok=W}i5`;y}|-$2A~AjF{yE?2~EH;FNkym6F+%x<(0}Ddp`?$l)bh`-zhI}k-s{AUM1&cH3VQPJpQy6i ze-nzNm|Js8V!*dw?LsSv zPA)cuwF6Dbhn4-pSgwZ7`yZ4ae-;fwW0t;?Sre*!E)h#9%dmpTvZDDWbC8Ec zt%aBtT7?%8fp^e9UFa;aqsc^zu5vQT3v0ay@ipI#8{b1RE3avop5_Sb89ZL#`R1ioWQwY)l)+21< zlxlGQy+qt1z?MXn)drX6gc=!g*jDC(2x-80_zRf5rX_t%OD1=w-Bbejtb@gQ0K&BJ zfpJD-16)Y%7yXBYyaz|0NgQutz&GU5YGh3c&qfbnb14x9hniOcyE1Y|noMw2yeVF&K2Yy_Am7UP!mLUX+k7I~_yn z5MkuL7tuPDU?9ialQe=*{@f5V7X~1vt}#||H~@dT)zlS#TK(3Hpv{Pu;;N@-q_t}5 zBKPL$v{sT=swuZy@{Afwc^b>R26dXc2oB3vL3)V?YQtHgEt8(XX= zofdGuRdYy1RfzMMLg%W51WNsI__{zAqHRx^3V+pX&cI_heCl>iCdxAc8`3e>;Uewa zQ;p>4IMSWqD?lfudxh=G+t)>F8x_WE9E1SVS4uJpWMxn`{@s>hXDwF)Nttc?FV{$D zdFUI{e*`$Gvx)YxA(@r>Cp3Z@d$>QQ9|AV|k;Fg$v*Gyc?Ua4to~hw`G4Ej;0UUKR3H2pX^jdB@g9d}e{qVVPbKg2DMyzOE; zDj1i2U2EZ2c63c25@q=HOlvI^FgrR}-A(pFz^124@Tw7ZQior~q z?>zRG67YV1Gwiz*`0D78KDFKEp}^B{;30g}TSTRAU~r#~)N@u?fDsS3!Huhmh#k6> zxL;-H)bQIY$Z36l_-LZsQS_OU*&s8I5OaEUh`IrV@AIdgBm#-|RrC-)Dg5J9>t8+A z@L0)kaXHxMu{FOg)lk3D_OkJlqVm`v?-M^`P)P7+O=b?G00e;m$pT92G|R6z6IQ4u zGNj*V4L@`jou`i#eiXuaGyDE=jS(!hEFi_s(iKri*m1f~zRwUa0+OunAE#;J&(&IlevTYT{beb z5AYW>&0V?;n-Xq{yx}oU7$)<*eJ(QncLQp2_U>%K$vDIjmQU+=r++fTPxCI@{7B5qteL?6pIGUvlC}KC( zaI7|(?|0dbyr%h6-~`7|ceO`W+hVwve+9KZ;)Qmlh`k=;F?U0QV(mnz0Ga>yWJUkS z)3|&){%b9?f5tiV^N=jyRBygtqevs?X&y2^dy-4>IU zgCm4!MGut2E?Y;CfK_ZCf2ab!vdNiF{H|>I7VMJT$1M|(>-X;No|}i4^OKzx(l#p- zU;9+*?9FpM4WJL_CG01oyfGdt@ux5Gy;q&CI|kZkTTUumbA^bbjSYScPZE4I_qMy> zrco%m^(79JnnrxQ8rdT}00xqa~2LgOl z?yZ(x`I70tf*NmE_ueR51EyxXw+;C6K|16UlH6R|vOM_u-;3D9ny>eWLi zFl4^Zda+#@!j%X}pNxeW=2aD(oJc*ds9djE&)nbH={^fV$R-d4OqFO>FR@0+eu~HC zg!edQrA5Y&2%bd_G;aMh4aZC_S5u}@)|Pd#{l=4Xmj%dtHUQi^wT_rR`t=w5)MP67 z5XJ4W)3Hh*mcw{pW0G$VQC=NOKp@tB72OijH+9dba915ts;ME@DbgpYms! zmlf&NFFD%0i)jjCh6k-iTXt|S zuyKqEKTFl|i-tDP;imwtt4s#JT14LJ+!+bUcXT{dKT4X0lS(>c@)x%{ZYi=>+hT{j zUqGHcsyt*AGd^Lw~UI2g)_{D`T5*DkyUkKA-FN?bo=+r$rtTk0* z8d|huT!p3^8H{u~{s>p>YkW}j?b9*kWAqGQsK05v30ASZ4+sC8ijgN;scA=ujljj_ zGkM$+D)6$AIAzx9kxX#S)=|&?6WQ)|@c%}tI7@n;bwul&`aZ_ZBl%ogrW>if3 zNiv!-W5%N;Pc2{!dAD``IM-J4;AUZ|%59)}PkX_YA{=z$y+XdVqA%Ava%Yhg#DXCo$7 z7PLg`0LRrOh;TIb;b>U{*aATgJSwe>OtE6u!jm-x~xeNut#);I<5IQ#3dNE0AM>OHt+<^hO-HhSH zVJcE;XX?`_&G%sA`PGKwK$W|W!}V3Nr6eFqxM>C14ZYLYMGLxIl{88m#&l5|YR{Z% zQ|YG2=j_Xc<^!S|c6`gsm%EWy>1?g{)bYxS=|UTNxB04J7h^#({oUUpt6%vS*`{ns z7~>b%rYf^!pQgz^J|k>}3l9n=D(%31ZTvy}0EVl2GeeK86uTkO`xi17(-!p-=h4BN zy*u&LeVAVHjC>}#fjhif02Iux1|uhUd~h4Dcfl#?YN%5uUG|%J0j)`>IM^1G6f~Iy zp4*Xys({SR`r^#0m#bp|^J0sXv8Je;K`gZejg$av)^!3C68wL01tK7 zkn@rVSP7^2{~_o@S0<*6k4&8A6e7}qVT|rNi+RJ*f^qozz%+CLuJDI{WytK(6yuNPd zrR81Gc`xRUoo!;?CMwB@WkX7uzw+9btpe$#O@40~E9&kSjo>-pI^-I)ihrPvEOAOY zHO+uR5Ee-;uy+~Frlg6752KGB#Np?pHR+jvcW-ZNTnenj zDRN^Gj`9C06*y3)i8{S!;gQtts1s;mhl+c^^{Gqj#!WBq_{NGvEw8f{2Lm|w>#@B! z*P%20*o|5A0B}8Xw2kEW3$|=PBbEJ<^yAP%V-d!!KAvZ~8;(~p8(%q{@qtq-5zXV) zY`^rBlji|Y(qc`Y+#4F+;h)WiJdx9B&W&s zx>R8mdlwQTZrOnD^q)MmE8H&g5}e`k2&eomV+YxPM2byhW#JJ?R@kHN^Evv-V}xNye6TPtF6h*fB~3HDm={>m&yGp1AM~ zphYR(1vDa9Cpn-6fP9E6CzUUY3#>=$WHh0ok}41BC|x0n>YWVX=(F;%6=bb7{=E7c z^Gvu~IoFsa?xHMj_<9|1y$m#mr|Uxs?g{r{qVE54+JZF)>EL(YY|STvS-JkL3YpV* zapqiXChhij(Y=i95HNs`=wL1WX;QGI?XxTn0ct(8YLtT%!9B%Z$0}&dWoRuN>FVpM zoeOr6+GcgA`R}@fbw(!qzF=nQ)vy^=djvw9150b?B7v_5SW7q{x`L0<9@3z<-M#V4 z+&lHZJ4S1Os(QY@iWs}x@tq?6EY+HE{n>eoB(aJV=U*s8)4aA1 zzzp^*pK+o*P84<_+0c;$F?g41g5wuciYq7oQSPo}_2>(pnRnPB=O;J(Hb<#hiG!BRf zL0jw_qD(agHJX(pOe8hWIJE#Y-fzg|i;ETr0(moY++UWIpb%wNBsFQZJhUuA0(KiR zZU*!@|MDM8d~DA?Dt9o}o*$0RpB2WE_5Xj=rtt1w|2TAl9!oP103n?|&K zd1YEvjXqFD=q4&{&QNViec3+AHyJIHwEeQ58jn^HI}At#{R!s6%{F_bvc8ptEm*;R zjLzkv?<0?wWCoTxuQNT1XgG+1Q7d7sMwZ-^di{M%sp?9BK?av>~sz4k2xbG+flVf@Bx;fq)~Yg{M|o5|6buQ(raA5x!6{j9Bz&wv}o z9WojhAF>4huS@4|4p_^xw-Ja-GCt6rR$H$JBc^Di^c;QF0BIe>ueXtL42duIi+4BU?8TJb5I6{1v7i3>mNV{{ zEo|>>S@2-aBl$G)b(RT*)cxMem+KC|RA}GNy;Y9?%7j1qBT)aGE{$hSn>!6x;^fO* zFioe{e5Ux>T(55FKP?QryEG&_x0#WigvV7`RV#>&`7J$|Z77WW#@GEi6hlbS!dZHTyx?Yjk>FtV{94khCr;lgg+uY-~bWOjiNx%L}Za}=? zUnexi-ocNLx8>*|+mV{sw6m>5`TFK{ayqhnj%oFOvuxr2jSY9TZu`&=rP&JQO&>P(VqtrsLf53roB8W7G9*>?}fOyK{Q|0`Giy09BWEjw|wcoI#hkc+!W6+ zL#n|$CdZc|MpJVj2q_Gg1Ii5I6>>mXRFcS^IQy_kJVm%HKq(k$s4FPT*2PwfWs8cO z;sVsSaM}77^?0p}vP8D=J0Bl=$)o~%v8&}5p9oSWZ+UN*Fk@g3w#7a!jtr&nnY zd3Jab_)dbu`+X|sE@N|#XE2X8NeV>x7@LokOKz$n*C`Ggn9Kwe!o+$QeBn)Tl=T38 zzP+`qrjw0fFQL4X^tMY2xhmch6`Z&42DSW%mAVVQ?b}ke7Cv?MV29jt?~U!rDgweS{wI5CEQx&g?&X`^Qo7R?Xk{ZP+(=2B)^gkvw&Gr zoHeU(I-a=7N%dn?t4_{01nm&yHs?vX+@U=)JZY7=r4m=_ zG$u3<`tXHQSnxS|V)zIZM!QQ5Hu#%IbP7pK?^=xD&bNi4cgCWx?BC zr${xotxkvTJa|=Q(T;V|F1{&9m0Q}_`&!=jX_DmiQ!1%!ase_{oM(jkCD?&$#t7A6M;&ajqzlF+hq z4IeR$lg~w{{xkZ+)>~SBe%UC+!ZS!y6@7&f_dsiE2?b|!ZSjqJKcID&cJoemi3pPR zVBxQk805aTBu0+~as5I9aIsYH20ljLBC|FQ2vw+xkb1lLvQNY)$Tcj+2{wAb+Fm6AoFfOI?G-EczDbEwrZH}ECPxWrzkR!>_UXDc5W z)~Xk`gvnZFv&#<}IM^V_ezEniWMySV^-7tF(LXS*Fp<#bAeZF~hYh|hRi#17iFOe$ zbKw!zY3R?uKt3Y{uJw1(k16Rp+fLj`$ExMe`WsAJHqO(geHHBxwHSb>f+bY-EMWPB z7|blE5B|lHECJ-Icc;yNl_@~MufHp|&D~@9g6}=bYr~L5rb;xDp}6Zwh~RAKM$UFe zWKBX;!<-@&J>EGW=nE=VcInOzwW&I>+xar{OCSwPm*57=namP)pB5kAH=$6<9T81= zD%1?!nO=;ika=Us(p2r1I>!5hiO!I3nuu?q4(NM>njc%Opn`d5!!LGJV-_!mFVP0l z=2QlK4T92c*Pq2KygX*`WD=F;WxEDIOClBm_Eq`rgQ$chMAj~*PmyS{Q)zH=UD0|1 zVFY;l7~#a$->BV+CP6WUGg1W>{81s6DoxQCu;_BbtKNabN*t+6GuG2+{dCO!==veY z$Tcv$fR$dclwb;tmMcg1;q*{dCvOR-3OX8G`BFxWg=2O zzr8P*dvcwxRh=E9DfV&yho!UdYx@7cwvwYkS{furH_|N)A}~Ty7|rPJ?vQ4*NW)0! z7%AOd1Er;r#+%Rm{rwSp@9{d%b6uy29TY|Svq<>OXHH%7$9+#rvvplW%iC{`Q$oAQ zru{9bHDS_1yMez_KtqT(&bnTx4i_Et*)fd#Fa6*4WyW`xVvRc7;S)t}+fcrfia%2h zYhTh;;wIDhbNjAMuOwR{I&kil1IAFBLq1VyF=a2X;@z{=)&&i4$9UW)I!DH()g{Pa zm(X0k>pou^cyw6oQ5NDb;-SJ{gR$tAS8zR!M-SSPF@4b?6^u6xzu#8bRN?A=?0msZ zX7n+x>r!0F-0*_c>1AGmQOy#<728gqZV;tMePqor|wj!|54iRJr*> zm3ROUmYSekj-e}uiR6;HfLX5NXR6IoJTI=O@AVhrAdi!QZwDral8V2HEETBys#SnI zt-3*l@joX}A0&QHPktiVg?eztVn|16PlY6{1FwKJRE`@R$r6ue3>=RGnIe(@D|4NG z`mfC8nWuJM5;$}llyW(Av)6wfn>cX(`+&D={Jhe(Ht3#K?4nO{GH}n$FTzJ`?4<$3SK?ZImh#eXI zIc~f}UPh0dSp`9$^M(STp5Q$lfcU|-aJAZS@nyMvF?X_J0q-o}?D6=$0xY^`_M{ck z&bYBr!y;gN8Ih2Li+I7F(rsEE>on!vWedWma$L5GMPeCqvM^E8 z59JLt;X0Kd`YS@t8Ea;lopKwGjF*XPD$N<%ZaMPMi*bMJuAHtu^I|76ab?LvTJ<#~ z_OJ+01D&7rvQ)R3jg&8JST?H{*KcA>nujn%Iqb57Duy9U9dv8@Cp;zT8c)V{O-bEb zyo7h@b*)=V#Wwr930p^g+vtWb_>bF*O*pR6fD+Jl;)p8G@aR{aAA&*hDuSumGT0p2ssN&Xl?x6>3r6+!{PQ zGgb8d6t7V=iN6stdVG@qv*@ZQZ_ciu%rns!9xPIw93~224@Z_2NKi|eKdd1x0sN{` z{g{VRh0~iASIvwc^f5j?&-E`cl0om<_3R@vl}n8@u9Z+`RRp^`|WnVUDDW9=Lj;h36Y`! zN=#6~L&61N9twc&mN0n+8QE#nUM#VJ&s56VsggY?h4fxAAMxlUA+k38ty3*UZoWkD zYtowLHa29tx?nSN&!9uh+J9lisnR9`24AlkH{lim4QM)F)(XGH-GH=Zz%bg`Yzj|P zpNULt#`b%V1!g#1jK@stt7$+4vy6e0I><-mH{O4>s!?OsbiOr+$cXvhxAbhnqP-*e4S7^D=xRo#2a56#jwtttd27xv9 zF(-eb(KZ^l6^OAi&lE!$8nnp%dHvdDfqEvUC>)vONrHxDRug7q%9CEU88!)PI=)GW z*F9Qzf(={dTn#lpx;VbEv#M%a&|Umg%8HmO+&>Ti_7pJpBso;Fs1QV4QZN<^iKybp z-^4^X{}3YTXiJ}j1Q4XNUdbB^Q=eQWR7JgBY|E_?0?LkRC8dqp2S@>Gt)_^sfmhVA zG=gh_*;Cln^YfD|X1zOSAcl_F)3h}AL`7@j8t-Hg&B>6%BOHqCof!ElWWMI2Ur@1x zF4JNZOoo+sc^p@wkv9|X?HYKbV5YLKb-O(L*(l#hLXuiz&J$c9!hjND3cK~m@9vi& zb&%v%t;Pi~+l1cjRU;z@dkfGzgY$)5Hnf~r?-tQ#>C09GdR;=Je!sSy5WQAR)iZY6PIBb zrg^2^S&73L-sobc$fzB<7+6B*hV2i&5)<#lf(EQ*P9jq>P2ZRKpqLy};DvZ2CNTm| zKT&RqKB)=&KXt%c)J=3Ad0%4+{_hF=^VPKBnvqKEQ8pAy6$Rfem3wTcumzLJ07b)D z400Ee$=fsl|FlUT_AOj^uxVovMN4$f{0NpEK|hzLnmP%ZhWn{x2D9vod+5;OZ$Y_e z6siEPIk|13qWHA9>)ckdZ++Pd@`&;zgT=VmZM1Gee*~r)d;j(|4_|F?A~^RJ|=pE-2`k^9Ee(9Z1T zopvJHL6)yZ0*VApqS)e1*424J7mdn4bh(T71EUAqYhG=~%me2S&%R=@T7H?&c+pz@ zS-v|DdtwhAWr>k6uaCbh{GP(dX#89W#4eVAAwpCKPL{3E4gZJht3$gC?UEFY<97;P z781)Lt8q25XZF-8ercDUpIax%Y1ikf7CBgMa8Hjv*rehisP6{!36U#7OKF|m-MP4b zJ#*1(G9fyl_`l!-qc&zX`W76xsfvhTcPu39Tl*??^JC`o)niAiuLku<0JG7bN-cZE z)Bsn46yp{*5eK#+zqi=F<;In5;yVJb9Hf&%Enh8&hr0}LqSbB4;2y013CXEmR)9;G zhQiRP8)E58BIyC6d^)O@7S*9Hg+}^~XY=4#OBihr$CUGheuJ`5vzv4wq2n~HW;*h4 z?xeB5o1Q(Kl=%3&h_C!9v|s;y%jJlbCO>B!itdQ4H}$fu%4yLUAx+{G(V~+xHIFh+ zm^YiOLw=q@W`rhwGU}O_`jaC|B<#zUYQ3MC(y7ZJ*}{k1xr#;h7V{t7;hNjkKN&I< z0XZ72>neYC3m5c5^2}33RTVq`H2UUWuGf@y=88sN+6_}+ zwItMddj43mYVUmGI3U7u$DgCPHK9+xC9nVVnwr1UDvQM4-X zJN(Q}59=ZWLV7Uf4GCWJk`S|m^bJtQn9i#>3|63=5_}0ONO4D@KqgpWm7V7rq)5jB zyw+MUT@Iq)Oyyuj7*|v;;RPe+J_w5qth~|Fh_&hJ;DmB{*%xX`DaFRNboy88+X0+P zXP{?3g&zs>I7*aljOz;A*F#Y6w}ehAG;s@{UmQkSz&J)TAOrnnRn#Vp+!7BQ0SSos zqHE5YdNsJ$8(3&hTqICy_KJO#WZ0bb<^7>;jZ96lb=e*m{-`bkrf2+7PL=rb z*=e9C0PLd0ysz55sVYzOx5N^`*z#^gppP6Z8e%doW0Klpa0cYirBnkNLIz^CO#`~N z+swmPNI72V0#0Pj)ckGsJ|JwM`RenbomW5SHD;d?g#pOggDQ>aWD;+w+j%h8@Vw$e zwG$lUg_2wd4fu@nGs2i%T|wKq-xU7P`rke~y$HL6=5XU#f$iXG{yo)>;Cm8OrW%X$ z)R4%W3={8x+t8HqQn#&zjg6;IqHDwf(52t(j<2*{Ssch2zu0Zu)@qhNNkcHD-^0QM zS%JMCv~7`79mNPqqNT9VrvxE+ZoF5%M7I`<*8J>M6$=Yo-x;l|_o!D&%R~SmZlR?W z6-yWovb;0KkAxy;mb9!zVW2(UZ`dyS+BL_gks8w11El=KdNuQh0V|uUf>37*vIQ=d zAby&l)w$J1JfZL{3dj(LwZ;zCK#uj_4v6dx*rBc8#u4Az zoQp2aWk_{K=GRou?#&t5eX-xx{1r39T`<#dCT{epXPDQUKQQ2C-<;lE$D5q*iXT{C z)^Yof%bt3IJToV?IHe6;vVYWPH_Y(s)-ZdJ0#3@L)7z(y8LAF7qvEy_wy}Xl-)`!3 z<(Vx;H3id`P~SmjRM}QWjb^6BdY4Xs94Fxi7GB6(mKiy474{O%j>2DX^BPfKd8epqu=~IQtiHv6H zjv@GFr?dtgda}In+whDLF6pkYw;>#E8GNg2R_EyBhsN)hR)46*su4A&d1^`-kS{p` z1jp_e7|XXTmh;ZEhl}pnLcUgKZx%aFtu0gP#=yx_2O8A~+M;=hpGQxE)9~}KT!z}O z(u8WPPoge6Lh_k4Qk|Ms@>aYkElmEPc}ChYxaD1)nhvXjRs6oK#~xwb)yTSxcB2?JDc|f>iML(R~R=#hz{RL258Ns9znNt z9=K2LTma+i88Hf3%x^3T8yg25>NS~r{tf0Mx@POU-kXiRIly4w>2;-v!?GSeU8g!+f{;G1XrkvwIzgOXyaqG zEs=lNdid~_8Y}RWeY&%7YpB&k_x+)dJ+VTd*Y>#+39@;AtE{p4o1q)PH`gH~(C7P? z^KH#YX@F|9`uIc4FU#-@($c=U`FF#d>>gmApQMV8K>U#{<)FXxZmoegj`!EKfnQ&S zgZMi8kSzZ%eqrWF6TR@S(;ChqQie{aJx;>XYZ;FnxL zX_W6IVX+kPUhM%S6;= z$8&BC;QK*>ZtZHjlAdQxo>(}zh~MZc0MhGFq(%Ccq-oLd5{iaKu-9dmFalL009*ub zdSmG{;r>LTtB6WXCNsKFMtqqPVbWq&V_z=Ty6=x~BXlSM7v|XU<0cG@FY}4>=xjVG(xO%i7;KyD2 z`rnodobpYvu014#UaxmaN6XKHve;C`t*F$7JTG{iitb3NcC0XLv~rNAAY^7;sX z0{uOroDHO};wrEG1im(_{jBnG%x{8W%WK(u(TV86FZ@)z+}K0#yU5!g1#B_Om9}2t z;Jqh$N=#JB3&7DD8EdJ2g^EhE=Lox`EMyR^B|tK#LaU)=Q4CU+JbSop$-mF-o6}im zUy{ozY=%OwK6ZEJzqkd2*V|onepBy%CelW{!F$cM0Nx1a%G-2I*EEH01z=eI>hK)Y z0OPOGcM$#yoFPYWx+nN(Ol~RsSz6%mZEsf}ns8r(kOy`&Q2VH3={H=x*^{85)a}%j zYQgHzdP`4KnlECPprfU9Ysjf1gJ11Z{fST_nOY2ff%Q9na*7-yrSv<9#(loly;gep zr}{k$jhUc3g5vdI9mHcOM7i*;v(*A(i|Plzyy=jl+MC4fdx`U_se#E|o!{tJ!v9d3UJ z9oJw|k9U)SdCyOz-HnXu!)!&L9WCF96AlUux$V0N`*WFw%#3z>jnfRP%9wWk_`z{s zUvdo*bkA;byDr`|tZVBSBRAQyQI0G!6LK^WXMTm(b%#0uIFrRMq z;42#QkcZ_*op*0qSN}yXbPDyXpaW(;K$>3PGqp!pM<;!a;oYNUA2RO+^Hq&kB65&m zR)-BW0e6A~!(z3K0K9mrrER8KgcHRqt)Bmyt%ucLd_48Uc&_*t0K-h~lX=p{;8rb3 zi-ajBoxU64_PTIL=)SBg;E3EyVc z%+#H~00u!B)RpWLx_v8xImL;Yl5!8>PE+;}|1NH3qrPj0pLaap_qp@mHXkF@SF$y1wvxAmmRP83p0BYYn|8o z9)~gg4AkA*2gx6X3R6)qZbkPX|Ngr8__9UPQRn;N-YyI%Cum6q4%0@Y5QHBA0&GRa zq7JIQ7Jmy#ugFh%k%;vwr#pEe?FK_36FK?)c-%DQ44)NBSEIa%p$gB zmPzPn^C!|eSvC-KsGYHFQIfc^5Fie|hksQ`YrQ%g&6vU4@ZsaAt%~uunneWfGM(3% zp`yv-vy(IP=h2~=C%_MmPF2e;3 z1mcp^pzu*)OJsiW2PV@iS7}0ey}6anyQ1^++*fnmT7K9KkhaV6;eW_BWf*1ur;H7b*7^|ibckn2` zX{wC>&hszv&&36e8pz>Zk(-Y(UB#wh?9<&oL*517{90~5 zDJ#bWWqql8K@~D3?rv@GZ~HW6%+#=Q|1VZ{^m2@;&5vX6Dma+(sPP{VvwzQ3apEMY z`%7r^o@^k}W-_+;OWut7Qvk&O{h!%liHUw^@j-WAA4+C%-+y=V{$dt>jeh{VZVz?c zL&ldweV&7hr8_KtW}nqdJV&&Y4Bh)A&OZ{LZeI zLTAr0dNn3g0+|lAO)R{iG}qFO)C^X|S0rMDe)_GT549aH;^&LbSd0w6D}CtEtHkPB zg8aB6;H}B&mOMr}1|9hwgysg6HnI=-_dFG%gW| zVJ~U+36#u-cpsf;;IKIY1ZMAch$HCmIZ0sbyM#TR5z9Yb#x>}jw1#z`E3vif8v6Uv8# zDA^$5BKF=tyN%&?B)luOIF$44LhHEl_L6!D__L zJQX$00T`wOu420R+ngFOxfA@{9OB^ht;v~5XC&CuabB@c2c{4lP9KZ0 zOjb%}F)CafAnSE3P-0DFr{K>L{_!01NV`*mBAC%@Sl{Bypto8aaXp&T-tHx}XK-ba zU5xhZufEkQ7;1UK$^dWh1`{_$Pwr8yGm`6$C}KOT;1-njKte zvjK6^aPNvy8=}f+$PdBr&B!GwXBxEcb5$6p<#(eY-Wa&iBnVtJe%!lPI}vJt7O7ui z?*|z%4KJj&)PCiLhK9QR+YsMj+zW8dqpHC;YHG7Vi}@gEa%{i;cj-3>(=b{lP@b!h z97;%b0uUG!Wl0O;@;W1M3^j?1^)Te;FoA8S#!rG!i^v?K&}b+r?^Ww!NjY0_?LTf= z<5(kE5S5TOil)*OW%$rMqU~i3i8Z5W0CNN)diYY6W%ScD(9L)v($Z^CDXKCGd|!Y( z0%`>3&6eq;Yu@KoHY(0%^(&}1BRe{=CKASC)vr;Ry*&#@EkjLXS8D1U(hrgD3^f-9 z@f8;i6#@1a6Xo|?K;=x$g7Gm03Hzy@G%kM1Z2T4l3LVb$AwGK+fZn&QzU0Aw&nJ0j zHHCf%oF&yzQSErM&cu)Y3YRFl4Iq3Zm6{=cUU81>3ZGl5aaNRxogo=aOG;gdEkf8U zjpRFm?Wlx;)7OS{-w(5TE0q5*Iqh1qH;|9Apm(;)@Z1@(??(*oId3*D=b%Fr_xVPx zbeMa!UD+0ln@`+Y&(zoyEelxSaDQ%V!#uJbF`}lp1eiMfK4Tova)>Rm6TJ^fiVOp1_TxN_2j78lVVP9@y4|RwlE-Y1FE&q zAFfcyf!Pg8~rjjW71eIG;btZm+aFa7)+;KTI5Kn&>@hV}Xy*cmLOxHjy5V z`dJZ04&;o1*lA&4VPKrmtH`bMtD;~>r2R}seIG^=GMXSvGEAwU{Pr}3FtQhAc~Q=r z*2>BW%q-9ZJMKe?#^+l$6$le)jA+2%ZD&<|&LWdb8dX8~X7iGrsm?q(atTyif2!5h zuH5+0$Jril-J9>&;&rEdfAsHa@t}m%m?(7egoCy++K`YeqcK0i5Cq5Jdh6yn#|>=H zEF(YzSlypFkvtVP%J49LkFnb;Ot$79O!dt6&S^nd!U`dMUhX@CgUTofm@ zJduB4mZG0j?=|yIEeo^vs)v2x%h(rX#t-PT@vBLzKb%Sf|NSueX87Yo+%)sQ1qZV? zUBw8Iw)cLEelAmgwKvyXe{sS4Hg|mQfBmcTq#i_H`D^n5BxHEW&$NdbJ%{182S>c0J!Sz&4v{IPT#35Bt?9OQoyaNWPDy;dnC1AjqpQC)?H_*a$mA61x#MuT^va!xv`uDhg zR-dB}yApnOUYY#_Y-x414k9d>s8R?~3D>mt68q3s9MGfpD4|@Y(2(BTd}27IuhkYm zK5F)}=>8+v%N6Cz%P|-`(nL8V_@SCAz=*=errKu|C;lz|vhA zWMJyh@91MxN|!3jGO{dkn3Ouc^<7*rtMGPP(-%niNr9z%PLI6f(?0bYA0`D>-1c$S zcY1eylkU{rQHlzzbS}UztvQ=Q!RE>rG}J57j!tjtJ3x(OIK&| z0$zXlUTjT3m7oPT(!$IcDuA?vZ(F!!tLw=Thugxil&#(upzYPnAT0Q?oCRv|O$_B* z=$zSNHygC62?M6-s4aUfsn-%q}wKqmh>=8T3B^@!ETfBp!)`3j*bKqMH8RcRxg?Ae3N z4y>yP@(B6?P^zPq!gv)gHGL$I_GT(@>Qz{gc5@h@kpJ#N&4fH+P$xZj3a^Zi_II{` zS=9|0`gbF^ch$e3@>dRIzQvXFCn$UPySt^-E6`V$Qtdnpd)7md|OxuU6wFyWzH-2`W@3Al}%rA>Sb^iu|=D@Tw)d@wfVh7T^s z;CsOgu1vITq=_1xYw%r=^}9)D(P($*tLp57tb3Gu6e>m&qEZRI;dv5EGHR@RO!!ON z+udRIB3+?6ug3pgX=QmCw2C_yfe+bNX-X#Tqn|iJlMrd&6430_$55Xk3oY_uC&*;*&4;+V1UFu{-8X6a4>@NT4~dNE=fYfPtkJ4Lj-`S=dGO5_Rp@3e<}a9wC; zgVOczWLTA`gjEjCAgkV>@-KS6bX$wVL=%ON^N*~LPL)(1j0fIwmX%dzc%yu&+|Z|? zwNQCJ7+`=j2Zt=1?+iV=v>-AR@d1NAQ~IAb*Dmg$@PfgJEcX_6y*<;ONctUjKIv!t z=R!&p&md9E+;Z}&R1~{-jWg-+%ETTj3yu$k=Y`F`A(AZbWdm6Qf%`<7M1{X55gw^H z=(aSvq4sD!BiO%{0h#@)aYP?ed-YRW;WF7HoZqsRi>$E$0BYWRUUh*b^iSgB!DpDDnQ2lGu&CwRNi&geZ?^4@9S> z0aU}G(S`MqTQlFanLU|do!2B*Z0 zy6{v8ct1-~E-R*qVIlU4@G|=x!>i&%k!7-wG-k+WqC>J+0!4DE=c{(R5?-g`U0gkR zwzNt2zur^+F5I-l6$>;pa(Z!G+^L}+;td-)*E{O~A{9xrvXSNf2@pQzq6XfO{WDPvETNmA0N%}wO#x5;C8cUBbTCy^*xd%}O_pJ~?6 zj~!DfBH&8?v=I|Aoa?brBSC1t=I=)QC%tIzXI*!RCNert>wx<1OJox4+~XZoU5)ZfKtW?(k{d ztY^I>)2A1En|M2Y{6=E35aZ&0RnC%h-Tu`{;*TnRe2(9Q^Rb@& za7U5OkL&7eOr_sgF1tg|npTfWD!jZV_DgDxj&f|w%=G8`I`gu0F2h-7aR)MXaB+nk zfxt=|8=H9~APR&94gacF2p7NSq9%`yOd5i8nm9EBHY!jhL_t`NKU5euqr4Gg#e4lY z@wfA8I6z~Cw8NN1o`2|(b?Bcgg-p}t)h8LGbhm})FE@$P*O=5bj*NrvvnWY^Dr z0V5!8JSc=FI{fnn2^BPO&6?jG&+N^@8#=L&Q)X2)oS7@7$q>k4uj_*9xPsa;;!Q>7 z#U*2tgAp!|uy<$m4M7J2&dYq8uC3%iY1mFT1c83H9h@V91nb+c9^iLg)qx5w`%e>r&NXyq?ODYF{L{Q0Fb0qFRf(fw9sX*}|c?IQ(3{880S9l}LN6{tECm9iS<88OAzx?k)P2E9fL zOYr&qr)po4sbVRa4?jT)-s8gkY%UJh<|}I*UrIDp-3#SG<=rv)mITEoJCOHI<+e)}r-TTZ)vq1(wR%jOKnzY54wk6o4k!lnThq~9? zxV%F5(`u!MEYAy99#2avEvqt` zM2Mcg`lyP^AWl`KW-2$eFxL7BrcP~{=PeT z^LB*yn{e6-plQR)q{U$qvOATd>j9rMvB8F-$Rrs)TJR4BM%0Bg(04O|m)gMMwN=Aw zT_xS&3NG`Vx{H}xsjS#4v~1M1%+tc$I8UN~Ef4c${L}`)xza!BJBT-45SKg9 z#@74f%LceD=rL%YzxJ!7jb^$4< zP-2Jp*6sMdp%grILAIH$T29@v*Z+pn&Pj_+zWq{%0vQ*ogjS{5^QzSTFjlf+UO1;!APqW-nrVKH6X!h*G%RVD%?TIr%OEhn?_v^RxP{RD+CV}1& zVgKSVIO8{O-dSTuctb0p-*}eQ7%EcsqI}OrjBqb!DBSpz=cbRwAgkO1*>I3X>?gA4 zx1!=P=Tw>Qsl*7ZYYX;D>Mh}S@fYQG+OEO}f?U=$1e55JmM-r)>J4Rj*-fh6<$JTX zKm-|g2z<=2)&hne3+lF-yjO{D7OPNdrBY!h1y3Gz#x~-S)M>lD*%TR2W8(`6Ir9*Q19r^LCwu#9MZ{}q#mK_Q>Y zFWluP78uvcQjuyeq^=S}Ub)ynMTcjxlSI_k^maW)av6evTiu^)1XP{IS~;RhZ{lSO zet*seTv?)_;$pVAnq=rg%DH4-54egK2ll_C`vx;4TUV5N6-qXy{jG0(qK|j`jqpWI z*Dt{X5bpU@yV5l@;0NuOROW-*zwK7gtB5WRnAC^D=kL-Tist`~EG>CDZZ@??=lpQA z+m?s$VEp&@dX|ejsdj!1*7eI08-ngQW!g@kp)ZzNOt}E-hfS|Gb`GfH|65DSck!zU z-ZuKR^SeT@_&s?TfdI3lxST{{hwFP=3Fb|JpJW`KWnWg zV|r_4gum-@X`@bn2=QhP4{Gz`P3*HdR}G!BZK%x7-C)zU(fm#aLr|kOuQs_I?Sc>b zHUmuuhPUa#2VbhfWR~ihJ(QgJi1$=R=Idq@T zKUBPC4f%X3rU7+c5K=7zVzREunGwS}I`T%+bPyWSVq(W)%2+6#hjx4A_c(pCXfl@U zufA80%{08M8ML+x_I+j$o&7_iV)r_g#oij~A*pF{?W+N+rD>VuyEDJg2Wzuw#hX-i)GWh^ zjki#0koH_y6vD#eW{p=ZP)Ng#BUyPb%9#H&#;U$936uZG38ve7dhiT?@IBNfGWdL& zp!hSQee@%_{C@r5TWTE_I3c^F@M1Jya?>Dj4Ym(5u%d3I=lU(C?1h5$q-)qOz<8Y) z0F}4q7=~R@*#)%;EugH#GTIKe#DN>Nt5ID`%4kgZoogY(k=YwSDo6(YS3{jjMe?yN<3og@z;$9!cX^$ z-Rd-tC$iTJS7g|_fq4`P#QwHkE^nv8s*)3XLGpNE|vLB(3`W9U`@%gx7pex zULLP-%!{t=gba-(vILU*vV=LUcUZOi*EKPC#N5WPSnT9Z`SlvFI3S2;v02e8f`cDGAc` zwf}zU7mF_<%>p>GyW0A)hp$DnOiDuHk!T{{m33$BfAIJp;X4K%GHW8 zjVEkmTYHBb%rXQfYvv!avo|M*#s-iRUaq^5WY09wzg_$qr<2FmoaL+Psw2@zSOVh! zrwMV=kh}7QJY=fhhzd-9ub^h=#(FQaQv7;kB;qjZ&B9BL6>~$@&_gyVwBp12>2pqG zc};7(F=_4`G$swK>&k3FJV3=g_z^Q)_=$_D*I(MK$7RGVbO8&Tb@^T3rVOucOmuDY z&7UY|bpKs!-ut(){1D{HPx`$mE947ZZ;^c_G{YT3xOAC{G)dzU?r{*5ds#(6U`{hf zVZj>g%#7;^cGvV>2|UkrPfM8j?86ux%b>jt`nV2#;A~_F>t)zyt3wHY9t#61zYI)_ zOjeCwMOUaXY-gUd*;9l#!(Yx(l6d^GoVFMW$i2{DZ$6#|iCS2)IZ}haD@LG9d4;lB zv$W(8O9V6j5~@8H{TfV~wcxc+u@QIvG9|r%|B(#=2X)NLh&=5pN`80=YVi0?sK2lN zI3*(;qrfETVf?PKi%&e%1c_>mt>mG3ii|jac-ammLts~AtAGM9 zLMSgBnNS={fsB>!Z8nNox>?dF7M8@KDP7y$DXFtMYw?@2>8p( zJO7&sX|30gqN;Gk4MP}-JmEHOZ<8`!r zA8WYW&cM*Rzl^Oov$+1}!w{ZF__#GD`}E7BpZWLox8>AGb;yKov1&eR*vx2ae3#;K z9!BX!z(+FiKyyk)Ut7(#hGb7gJgO(5wtrjGq4+k`M&ciCe%;E4d}WYFcJzw@hj<$6 z>wl2+I-38)TKqwZClm`f@gXE%hC8K66FZNsg)8gXc<3**tb}T3O zM$i94-T)1i2(z%B!$o*X}IL-LCihXPs=`CwyrRO9`L9UFfxV@XG>@6H^QE0DX8 zj$T25!~`UmQ@GW=)u*SZgjeTz>7X#%ikzMtuc?Tx-Z()Yj3xZ~6?Z>9)`qWDqoC|^IB@9eoLZ=3ON8uQ z%s@6?H!0`udEM0T*w{+lIXX?`ZkTFswo?E#h$K}KzR{IeJT_7S9k~>dRt6vS5uB*o z_($2bsaM(tGd)VewLC5xCbW|!W-X7+F~|y1EBl_;qKlr7adi=lID1sV5-cAyzl2@zhs`}a zv`a{0V~GvojU&+nQ9&r3)Ef&7Hv#PBiiYlGdN%?m@Fo(ljq3!(lX8274_dXE(Tre6 zB`n|_*Gh;v_KjYvy|H_)p3;;k`+7p0A^=|Z!js@(awk{`_t{~Jkt$=qjS$fNI;7ar znWI5L0Wxy=zF4)`ByL)zjvT3RMRCVxQ#p@p=*EppPBX5c!#z;_wo%0^5=-v0P!9S5 z>A&aGgPp`$%#$8@ioY_hgI|i$bUS9UdA9x{#5^I41{cT`CrB_ zhS@O>Qq4@0ER1eRfU`(3Q4M9yFm$I{3h{c||NO~qbf?K^co@VY+Do4W>;k^mz58rr z(0G9j?Zd>jt0PM+lJ>)jvNzvSg{9n68obKeO87gGYv_R!&HMMime*;=!_L*=&E^M+ zoSZ?tUxITDPNP3nx9ta-n%seh_;UhVrEFz5g*hjVaAM!m{R)T#t>g zWHqU-#yS2?V)M33GS4obh)vek009$-u6V5uuJK1f=|gwc^UN^o^of~}0E+e&W~W8y zD_1s5HX^qv0Q=C@8`ScNx3dj!t$4GwG$ctQG9(Klm4wN!a%L9K)-m2k!|bpo5^~2Lq|TBwEqXdR)&sh7Nq?rO$;BoLIMeMlQdxTR)C{y2*Xn`?A^&1Wvf@ z6vw<>)fN9*IM5ytlCYD2pP8u}g(t0lJdPa_8pUjl@Ds)&v}Ccst>m1@3biVLBA2qy zYKH}yAJ<`^iox4zYP}=WuFmw%lCKC|<+R*v-TlQKj7+t4q%EvXEXY(IG{<~q0Z%C3 z4^+B|=4ivWoT8nnx@qusz%e#8YRBD+_&G)F%OjnK8WmF3vD~(mCcyyc3c%A3B zHT%~@13#gm@C?Zf2X|&$Yj!Q0xJR#ZE2)adUZgYKdK^aI*(@|pX>L@kyX7?CbOOQT%P;GU1<598gljjjdY5UeHk~8%rL=<6gkd z_wTB+rhVPG&HpIfbM5ofRoi7rb};$>h0x3Yxh(^qzveH^BZ{XR8oNS`^Ap6#H^Jg> zZ|I?25)@wW4#|nV zlWsUD|D*H-{xg1F5)FU>pT#^noOYJP)PF6SE-F(muFO|4b)C&Psl#LH3$kep&J7;FPSZ zw?#Orv`3vyh7vA1pK?D{7JWh-W2Z_hmV;PUep5RBVs{&L#x+pt*8AAn_@x9{#y>Um zI7I;@3>03fPIYB|W#XaBFefYZbA{2%z(a;1NGAC8aUEy7?@a;%y*oA*zDBuMT&-U) zvg~lyJ-=dne>FS#v2y_?^NLgkKuu7f(Aqa=Z~vl6^RKE;F&!XRW?Toa4|vH;4^EuM ztp+?Sl-fEmbFkNz+-Yd)mRd;wac15%fQGBDHMyFxP}(7 z_e%bVFP&XE2Gz(2B+)5-?X3%yrz*GQH5mY=G~t^^_$Aj++g~aYCQ(af!my6qqPHoUkP*jcRWVLGLzXr{&&+q&!k_IMY~U>+a6s0821lKNE(h zxUl&3^5Rzx=pJcWxG_^5|9M$B|9=3eKv%zVjve=%W?k)U$BuoigJ~yg_}a~pUti)dMgVn>f^l1!n&g^Jed|O z5GI3*SOSjD?lQa(W>Y?bdzGU;*xR{p3y_7y#kBnYXYW6o8_lvjPwt1}@3i%_*y`>QsYPVy2oIOkBq*Rk66F4W z{|mU&J={G!GDJpJ;krKr@QC|daqcHF&b3 z_7*jt6bt32vQeE|j%u zL-8T8;8b#1y?kRWUVHUr3yC*2Htki4K%71o5iIM#ixPzw2O%!!gsW>hh=2orNFFUc zjdxFYT5Bwq)wNmS2bA#jsLe0w-7^k7NPcw;Etpr}25%P>*W`OdxnpIg#uvo|dF4cP zV(t3%c*cWWR%;a)uGDH)Rsq91 z+dHwfwPk!+5dEvorJR%~hmb3fZ?JK25PLg2mh(Wb2;pi)h2RQh2J{bkIr5KWWUamn z-=OfpBL=vj{ahpT?C=7mQWD_LOy{&dG)}@NCE>eLZAE<+-V#89H=z;Wkz^FWT%q(L z;?SDz7im3nqkeM&;kzeEFHl*;XpA;;C;+F zN;eF_!P(F}3f`x9k^w__KaqzM&m_ErHHC&_UDTaJzXv=CJt&ms+y)eow8uH)EWaTn zF3NbkZ8M%nXi=U}h2m$<)F;-s->bgDD^LfXr_dd6*i2sZRWu5v3Lc~2v%c0LG#roN zQhCns23(@-icp>8I_nUwlN2YXrmKYXwNVTT8qF_CFME%vFBcj&axkJW0mhR@E`}2N zE_{UCD|Maq#e!lC(lzJ@Fp9wj=b&+fzyt^5{l`(RF6q7Eb@YC`?g6N2!PnFj%6Sx+ z1LH81c#H$N)(D9U{UYyS;!&U}YM1Nu1c;(z`;ZvAsKcwr|EMp`9|vQ|r(fmr=-Q*>pK^Ixf1h=X ziy(fY_?nbS`8o>AYJQy@Un|~pB_Tn&2KI7j10iv|j6k3uH5dsLV-PAfuMqBJtqG&d zIT2YQXEs|stkzl`|7NqxLdN0+B1|11 z>M&z7QfNVB`0j9r`jNsHq~9p8%;1RtT3M#L^vCyco_0`R1XFwT+$qW~2w!5#AdnDh z;KN>h5P!i5_fQgo)^zZ!>Lf43M<09`@4ov%G>%TvJvzSQ(={oRGAWbtO_y&^@%86_ z{_nuMk00P_HXi!^ltX{{^YDX{NvZYdo+l6PrQW9&UmxB0j05_i7WwlVJyMH)FGa8a z-1}(}=bk)%=c0!n)$s(i^~q7~{(xW8SN(a~F}}#SJ-v)?;G&6<_5_@}hyCLWq`lr(`%pv1RV` zjCm~-Y4FGhEf82?X^S!f{uu#8rCN^p`NgQuFGXFvGDp^R_~!JA>1{6%Gha5GcX(9Ubn+&en$8hF2BJ zH1p+Wrxv^}kdLTZcUw{LA*3c8n=Quavv^BJW$b<8PxYC8A>4i#2}1m%g`54Z1@L%e zImc3UF32&1Fgz*zayF>K>j|k?p@5eSUMmP8FXQCo#GVnQ*?i2Q1XQ~aLZx+qq6MK} z3Mqv^Gx5S|pZ6|(jlrqz!MZu|-ea#6!adSf3)K)7S=oYxGks1W-REixu|Q}rweumE zs9X$NR<1C&vqc2E2$FJfX`vA9V*c|MwoR#hTMs_-7*^*HeAf*NtXg>aez&i^7CBwY zdJjTz1pd5?d^_9G*x&NJGWYNP_8oist*l;CT}x^|?IyfY-(!qdkCl)*Qckmr*x%cU zfBeV)5gQNgsNp*2y@B?32nDeq&(Epbj5YK@aC(VQx2^XzQwTz}4G)Hyd`0&V1`A;( z1$f8PU?#Gf4!nN0w>LcRwYj;-sBH-Sw8gN6JIWoxrjuU;Wekx&Xg6V@%4O{n3CpB5 zC9x2NabzK4sE2?ttIK#7)V$Z6x;WDwvKjqeQ?M_H%xI;acjLIRCHTGq=mr!+ow&y8 z#R6g1y3y2}5SorPgy$84QVbjMl(Yv;ZbooIh_2*4hv3_kQe%!1k9^sLD<#hg3I)8* z2op&@xt_)guTL#l{`;V@tnHoMO|@yu>joTRg}30?`$w%;6bT5#F?c1MXkG{NLhc_t zGP1c*E}=qQzssKgUYGnbM2HbSVSe@L&|jgw4FrE~=C@4|FoE&b(gZrPwx!|on zzoP3ID=KI=`^`$VqIITu(>qwFjs2aNLAg?0Q2lws0m6OY!1iC}9t zT5XgEjE#q2G;3d18P_%bq@U0N^;73q|0wI~wMxAD^0j#B#x*OA%H^`~MAdkgwMAYk za285GJU#(qJp90SC=yYGRVy_;Q`3B-c+nWLhBWU?Ew~@$2g)ofIRszeYLsVqNZFfD zHx9v<8XuGuc;y09cn%RtmIyn9HJqDY(42#7)i&Wql&^+I&3#Ar?(c8wT^LHtsU5lK z2(FtgLR4PZgN;ygR)h%XP_&WntD^p91<#C<KcvWLC;T&OBgd|xLh6JVBl3;Z~@T2u&58rg)xr)ck z!s4=(UeFP8G!pKW{y@j57ll5Pg3^XuQ8qNtZz~#vXu$#Gs3W)HG+|q<=uPl{Iv}T7 zSNA~w@cJcvh3Kf(_B8lOa{!=RoPl!$H~NiXfNIoOof$u)I72CYen##!j9>b!B((<| zOM42MqZ5x8G~G{ww{?$k#|RH#6jD?_F>Ii2WJ;`8D^7${$j?Q%;GsUbm$f&Y0Vj(- z&xrQu-FTZ>aavsr@&Ez@z&Uua-)+TFV^1)J@khbRQtDW+w&Wd-N$!Yyz zK%(;~RQaS%jB@Nb2tC(%@FZ$@lutG`xx}yu9*#ER^;OWl1uNh%`k1=JNJ4O_`DTo9 zI!Jj&QI-k+3+8}F^7#>l7`nH-a$RdKYlHU`;VIE6#(@5Fc-(x9%hm6b@7X$(3k zWa8MO76u9e^Ia{3i|A{U`uZDhnxTZbV1y=z2_lJ%%IDf-Ub zz=a?<0S;iK2`yL(o^VGxFQ&rDD^yiyDo_g||Js$Qk z{eE;QjZ6A5zR4HHA5TAc=9z^XM3;5r=l@-q!!grDWzRVL%wyjl9jS~ij>^^RR}bE# zZ|P3`{@n45!j*JOy6>@i(=Cq`-~Ytn!t>+8cRx=(4}U)O_#=$l4FUmeDg6|o((LM;iC{p_4^2%lE4g}7)BOF2G1s=BC}K~V{fo&3l7IZJ3^`< zBusgh2={anco@C<%FD67zHUqYluwAzItWhkBS9wum#H9<1HumkX~#!@@kZ;bqi`z=q2)=6fFp6-@w2yHVC6EaGOGzLW2K(;!njR zCgn#G5Yu0TLU>5wErKAn)9nOd+;(@j^;|FN_4!y`y&m&Rgx0FtgNKk)2v?|yJ|R$K z>!GiD-Z)yMt`A7+KNZzVMRh0P zCA>JRWCrOPhuery5Cs?SNEX=nym)W5ll=jq_7GShnuEB&cu{-8DWZS$ z+!s7srn4yV5VQ&|rqVtM<=yeofyOv_CejYzm%Ryf&de}&X`EC2>^b_n)YH55PKU`F zD?ZNz>*TpRimcWFbB6~OIcT=GHe!2c$LkY?0g4#%6rqs7FcIN8>l=%E)+TF={*!;2 zy)J@7Ji?9+@El{_1eY2Egt(Ww508VT<&~(_>gspa@XPGmJ4Jgd1dMoN;kiXPy7l!N zF;|<{wXEPo)m>6w)&gmVsm$S-koWpSDU63EifVGH4NkRBWdG8B4sofvS)<BfPiA0vBcnkrr5aF$C=(k&h%X?vQShY(?P+OyekpL zPkU|PF$%7N)*x@#+uzgtlQ#)v6S9S#jRWkVC;ZUX8o)~u`clz4f?naJd7$SG8^TS4 zQ!6Jb!d>NRO?73gn74OWliZ0H#^K;tyd*JxsL#&_-a_C#WE>a=I42>YW`%3W1rK~P z=HORo5nf@)QSgdFQ8Ny$M|jq(=qRD?z*D8#Ld@2d>^-B$J!kZZJb&O{6v-$v=ucT~ zPVk3u!iC4$axd0~@UwYk;~NfSIT(PneclRWjTy=iby4pw#S}`1X{{qoB+4^aYt z-bK4n*b-iqb=x6N)(N=lSnG=S3expn=qC%Zr};#tgTi`R_;IN9fl|`S7j+C+0oG>J zXYy*PrJA>)_5xjzzsYC5)y-$fwK*zy5 zC|!nXD<1ABaqv9stIvcxY_$$;bitUz2PB$~cN>NpDD^a3qWSG{SWMOL{9WKFaK{Wv zIN$@=YewsMSGZ|E2EDe%R6K+3gD0568_jft16r+@Y3vwW3}Nh5Hbe%eD{3>|(cn^t z78Jjf6|PM3JLV34PoLlm(FpnsPl90-#snx)QS7m1%})Wh;^V;mi6<1_q4@&F)dO8G zm>w921qaS4rmqfHt9lq)!{JDwj`0A^$1|C614fXuB9~nGTy&h_^p03SH{bqFXpNL8600!#`ghn6UEo0 zOv=|$wC?IFczi88%pfsp*?gu=xKN;w9n5o5x(tnkVN4*PtXYUAOBZDcjHS;Db+XCr z3Hi0LYCAbHlEexN#@Nc7)3m9<$_)k%kFWXy?(<7#mc|yPgmPfhjHg#$3?YQrgaYaY zidG#E^zUM^2i4hmy#2#Jj_WsWh-is$tIZG)!pT5jP+nmjbt+1!hk} z>B4woaaSm6;{&l46Nb2wcALFmzX1VhEZ}doiQc35=|HkF> z<9qe4@xO;xHKan%Kq}~gO72!dWqui`g8Sof#S!WIL3dUS3dWQ z-uJnuo@~$Po~y^h;uHGwtmDfR-H!k%{nJnWiAPF&(M8Nvv7%oT50$KY5%?uRXS$za zrHObu&LNON5QsvFyjc83NI*D2=XJG#)R}6+I|;)xynotO6cLUP%Xow@2pq`Wg@*^i z^Towg3rvQ(pO8B?ViS+Jzqb`1fACIhZ9K5j%lRU(&eyxm_w!Ep$zIp*tj{k7;SBMv zLeN9|P~3qt;6WX}OS~=pC3N0wft*k|ojVn8sP^TnsGG>-Py8 zg;FQuca+rDd}&TUfe*@A95puL{r7$o2m9N$3a``_wWnIr+%H7AG^>46M$I^P&a&OD z`;pOW@C?Mm0URYe1uV>zm zyLWC0KFQ|vzwY9cU9;q(#CBN)~ORM!~`XcVxA@b*~q zb!ONjtP)Bo>OxQo>}!-F%lM)6xYWLBaFmpPy=F`cz?}CL+wBHoSJXr zO4TtuBYzxTOBXS(zAk7l%DxA0vz^^t@0;-W1NITT4+ZnUMYlVMlarRCo8aL^I5>p& zj15-sH*dZc%d0n{tg)lbz*_PunbUYCSjN)^uNQ>W90*@)mAd*l?|Q}_W$ejNc45(v z@{f^Zk2gdaptXdcHJ{U((AaZtF3&TpPa=4Xgx{*0e$CCzIiC{?FzxZvKGL+GdRd!n z2nCPKo)t&a{MO#I*VaJ@u7t0kCn&iv-~@b8?t-V>pXRZ~Gzpq9aAgb-Xvalg@WDP) z{nI&=EX+ewKgMU;I`!5C|GsKxr8$i2;Es>O^OiiwXt`ZPZH z@DsH`aNxS=9o^PF;~&3M8CS%A>f%Q_2WID+5C55tT;@W!ka@fm%;1gJ@kP8o@o*aB zRbU$$LHk+ngq1@8h1$Ge75x`qH(%s1h$Gton> zD=UhG4}k@g8_0d|T4i118R?a&bI`7y4%*232&+h&&P0n)5_iaHH5_PtYJN0sG{fQQ zG#5jA9pM>8J2WnWAJ%m88Wq0K8fGnn8yvb%2QY*I0%3~@xym!NpS4Bh@CtYjqWHvM zqNj1;JVpWF4gK-`$c56lbv2ipaVgx5r&l3gb^jO-lxHo`z2tF~_#Dge)J8med4B;# zzUTmBIaHrfn%fXRhxas!FZD@n#N&vuIy)6?_Kux56GIe%ua#cF0|+|tNXWn1R-yvu z(3^2?D=UYf8=koo_V7e>^!Rwkv==(e{4qZ$hEW1RM^fQA3bb9g&|X$Wy%U2b6vu>1 z6#T2rcn*T&z_;*vC@TqF%$PyrJf_Tv+D;BS6p&W%sg2A93aw18Y6T)jAy!shrqGtj z5kYedZd4uTJTF{`0Tag%FE7D`m021~hf*zWxb`g|!Jj6VpVSK&JLg6EkP!5(JpazJmnc3uPE)1Pivh5p3AgOUw$4fIaq9OrZ3Yc4Do& zv$GrTyz@@%?H~L4q)f`BOv zz4TGrzPUqx)Z!~`|6LFMyg>1LdE)BBSBigf`CQ z_ot6%AEUPFtLx_*|KXGL8@_9D z9B-F9cW%YW$+3kagrO>HZ$V!XxWg|Zut(^HFq4pY4z;A`;W-f~!T%x{C!89dEah_5 zUMH}&j45M{;0_CZgr9^Uq#X!*cXu{oe}BtX@d%Xg2C#MX3^_WIvJvqC7WN1^QFa_3 zH`Isoz=JN6Lja1v4}sQnWTsN+D)Y=2B=Sc{IJCmb-UVWXQ)2&u4cF*X8G*gSLLpG2 zE{fhcm8{NVNT2aUy7b)U@*1B~U1MJH_#kk_`(k+7)iNP;Qpyd2u+*M$rCOA0%Q2l@ zP#t)~&?oWp8ehDO;JwezhE}LpsZ}a#d_(X<2tuN6^xML5mKl2;pqO*Ujd@}J z#Qq26M`0E(3_R>O-?GOEdrar1(fuB#i*B@zcC;UD=zYoSk$n=d!!wLMp)OOXG(!7L zX)gNOgHl(5Cp>3}Y{7G_7HhAm=lbgBsn^GuLvLoIR$q!6FTJL{-*v-3-bujc-p;n+ zsa!54#Xzy(HQMcTwT5P*ib6~W9&i8{%3?gM2>S=DQ`jq_@E-5iJkEM;+SZNsa9R_r zTSDWp4%vIMf2S>Tb9F0OQm9Sv3(7M*|5#TQ!!To<3?>n-Y7c2a=$Xd#Fpe4rh93~H zr3E86MNo^77Nsi+Ir99Vh{50!MOG$9pK_XqQwwMDZpmk-qoy|EDFn_dXujCXc2TnE zS-cWY`^VZ3w_{4}1V1JvreJ`4NP;PpM66+yD$SEap`&4BGnaAuvs>}^|L~L8+}LuP zQm8RCmu>QB@0tMP(Z`o7dPwWo=wJ0c+z7PPCeY$Bcs{h+qID@b8qA00%M60!Kua`FSB#E9~yu_oiK@nU|YoN zY+Z1z_Zc?MM0d1qSWn0;P+aANzvt_7`pg<$fp5GESJ&6<^~j*%kp^ABqm%WqFuxef zD{ES_!owO$V2Hl6hU@hO!!br91+5uir7s!=4Z+J4!98#fKBl0AMp1`1*sQ}~f_pSB z&=~;$hSV*=3PvaNk5GZog$(ONcoBsO9^8aqwfCX$F5a{K!MXa<*7L_&aOAo}fq+p3 z3K6_}ga=S+YJE;?-O>?zWr2jj<)XdEM~9m8fzMk33p%6*)kD8f;`YfECHl;~WDBJz z7P2}&G|ncsR=N*`lW1|FY{f)o`aoLk2w91t$HVZenlErT^K;nP*ZVKL_VCaL zAL+&*>??{b?!V9&(q5hL`z#R?{?k{VxAGB>D!s$XW7UfhIXk6u(Gu2LCP&EOORYDI z+(jeR51zM@QR@Lbh2qLyx9}#0F}+9aBqS}$)(lEKjg5vlji>1W-n&VGX=SI{1@6bd zg883LV^40_K0Ga9qH}@)@Kfug z8SlOSp5~yfXOoeP$5;iLY8j$ho5sqgT|ACH5)b{)r9A5Q^AARGqWGGWN%^`843{<* zWig^TK8V;l=)bO5EMo_|Y$zNCW|Fq;M%F*VaID07IWP zc>@tNl#B>12oZucs2C&|3m7XEd($y*Vp_4PMR{hzt+8=_F}>deQizm|x`h!UY_=NG zn8Mh=95c@*T3ASF{wXjRdQ5c*M$|8!WiBc7Gcn^GTW-Dg-bZnCj3vmVOvvD(f6-dzIqKWR{S2d_gQ`7(4XgC=b)w+VK*M# z&lBn2xNv%WJXyxiQ26$+o~PaXWbp%|!yMK4tuOHGxP0Nexc2D!_}AlSDOX47@hi`} zc6HpIRlYR4H|o>#YgO@W>HRNqxFLLs6>^RaPKY;JUaG~P{PFjqRwazwAhtF);^^o= z{M3bcXoN?U1BG4>Xs^S+B#-PZ-;EnK#Weeo-@Je|` zP||Vz-2KLan0y{6Xzty+9Y==^3!unF#{K|H{C2mabET-)7cE%B3cK5D*~^1EZ6&St zBS^W7WSxwcRi#RPE4^3$u$*RJz+z|HQm9V$}Aolk*SeW!K|$>lVq_8-N`$#!I>hMJ2L3&x0mut4a= z+Cq>!1UPV%47~$I0t$iY3<5uZBMG5VPz^e}(QGziCRd31g2sDpU3D$#a#Cs#wh4uS z!#MStwz6hFh5#2ORc&r5re?6T9xL)j@D@4E{X$&3_L3DugwsPwfL9yJz2oMQ=V@VK zRbxjkv?TCjj1h_^B^?TU zem#~~*Hx#+UGRmH6@fNm<9TonCd4<42lJNIe0QyQLP(pu3zPLaW7X?4oYUm^Xjd?p zkGa~S<|u^4-AaKWH(tBHhL%XGMJZVNt=YU1_N5k{W=yVB7g+hVcQ>D26(yQ^> z8*l0JwOCxarm@XMw~fcnPHf!29h)2Xv`%`ypD{yViT55`&j5~7#yrb~Kw2^%y$|~N+eR$$AmNWKJ zK#7eKwxBkl04b?Hl;k|q*FD-75*AG3esY*R6$|-{4m=hFH<~-bxnaafI}n-^mE}~h z2h4zfW;I7s8RiJ@7WSZ8|LtSVE%Bd3Gmy|Y2m%sHQu0IX$g;o zsT^9%2y3-hZJq23Rt(~Bn}Q5x(CHV&hv}1o;d?YCuLRoOy8ehjPD;S zkLW9KK`{wX@s-i-Y{5I-v)FI6Vtel>4jRqa*=xkc#zyRHZ^TJsSL^gpuz4hW)3I_D z#U!Bs8Bg~92M2_~#5+-I5SZHEj;5Z$U;-RS_&?S*d5tg_AYXb?7J=*FX#@!<-&LIY zKFQgQeA#xOU^Z--)sdJlO9xtvtcg_?1^)7w)J}E(+`r?KJ<+aAlq!VGO!+LyTZWHKsMGPKz|jKjlSj~al!owIL02e6wfjPz+nF`)PiAnM}9W&YzkcoK1bQ8xzj(^3AGl4 z$5L)Ly!OcXrgjN;CYnYBCZ0vnguIQOt8?&ns+V&pWyz&R#3n+sqG+Q3&`5jGsy?1W zo`)d_MgU2vHBvsAe;H`N`W|QU)uD)EP6@NiToF}^s9mH>f%ihmIab7}vHG8L%9xg5 zl(wRPLovm@D9DicF-JMU7kJ1fEVEQs5Bn2@}pe|cCiHU0+9ouv3T*#gR;+q!3 zPl%Fots3>^Wo-~v#h3`u3c15*A2)DwKhkD@JN7m=(#E$y5xwRQhZF+E5X3VhIZE9oPI5-q@ z)Ut&p8yJ|!W=jmB#&IxKWI<^3$vt!#W))!tgg?!X<_YEkMqk%q9M~`-uy}O9FeBK2 zIY!Bq=GCs?Sgb%WnP&)-KbdnKqjQf++BCofoiv+b=C|U*4?cFB@=2MLNtu*Md04(R z#n)f|#g882lcBxiO$O-uiw^$yAK#x+sK<4VzW<>dFTx%?qstG=xX=3YSlv$^Pb;6h z&tv@g;|m+{0_9;n59{^Ubp8d(xGj$zqid<+rx)(yGI#jv!{^7p(|xJow%Zt@ONrmSN0%xpyv97hy#r%{$EbxGjz7#)) zrTv9@Ff7qgh#em7$HCsVg$lK~x(^GM`yIc}7V;|ad4!}}T3itih_F8b3tohU8hUtD{II{hTxPv4Z?Phwdb7qLZCIUzzT!3#4n4F z9%v3UPbs_;Ic>HqphxI_eB6xvgNEjEM)NRdp(7qg%oljlHeA>p%tDQ zuVh5Wo)Cd+ve-vSg(poegSCAU!sd${vq>mCqdsv@o?Ks8tn(BleP(BXeT}(blRb~B zcZf=IuH>=^(@+TaHJ3%tBQTE8mQZdC1KutkXKF;b$>;Q0_+cD+ba<$_ z&7>SD?jx4>cm|;O+IJXJ)*gnV+uAqYyZf0HO?YzwlPFu+^P#jrflS?p+GDmmDa=}z zlmj~0AL1p#8gjT)jU@_Dgw$y*WsNg{U-pWO0pUwgDBuN0E*F$mtli`_wjBA{CBOS@ zK&ZTIROgm7?lq0s(8}nfv`y=j95jR#1I`g_pADLE@6Kn@I6Blj$Q!8hdIPvJSIF5b zZmx#+-K@?E{sl|44@G^_Pygm9exR8$hT2-HY9fa*|=0&>C51Zd^tp`0pAQfUt3!{u_ZWr z@L<#4x>}k+7(?(ra8AGcTjOK6+TMu0y}f8@pA9}{u6QrTs*E|gt}2zX;Q~Agz#AR} zPc!!37-)#6inoA68X*ZrDd%HVY!bJR;ahNmUhPCwI z{(Zfxt9r}Am4v5F2DQ|MqKaIT%r!W-R+)=>y>0^vXvdu30Xm1L7vUf2b4&H2hz1W? zai{)5AHhF(wmLkfU<}1<^LWqiDHib<7A{i1rhzZKe5MJ(dMVu6GK?m#7-TSK8gTL@ zC3y_^+(y4f;LOE^MP>@v=%QqU=c$K>MTINL^l)8yR=vAiQpXLXB&Kv z6p7$QU;txg-jzZh;yD9uB8A0Ja4*`RH3_KUv4gUMwj`wmJOngYFeV(nuesP0uYl6o zxHm^wJFO3ty}EZs&#>l^sU4Goq)*5^J+FCYZfEisC#c<*DJ1Tm@D`DTP;x@oQMLit zz*xSJjoE_mP9B+2-Ub=jd|7i=iG`)bkw+lL>guyPM1C_XoXBS-n1Y7T9}0@l#5<8I zo=~X5QQ}n`3CS`n=nIM-lw!gqQx}2(6jf(_H)8=MV=kc?tQqDVx`9ls**X!dKu`8lwnkForJV#zJwVPN;n-^EC3J^ZKE&$BXV< zeFC>>{E&&NEzCC)m!f3}_sz`ebK1NGVI0vz!^^?@af}TUP+DWmfnt+9UIXFunGDJ_ z6u&6=cz0UUtRKb-C9w0%0Vg_7J$cOm22>c+6LJ)&Z$o!6msMp(!4Ft=%-ws$Vd_ySp2|`t`3w-vonWn&MezC=$+0_><$w zGCu#bYu`*6^X}io@pTp;ZKC*^lu7xT3JRlAeJ<8-T(^Z#O8Uq~hwvUKvyw6lL~8`D zPn0wq6p$hcCxl>Jhgdo0vNjIK`v+EhL3lv~AV3b{STC<%i&Y(LxT%Yzt}QW6BnNKn z>_lTv8<8eqKk!}>Apwt=0TA*OVuw+Ni6Hz0h#N)&Vr3=U7}I_S3Pc#I-R;dyZF&!4 zYhyF++`cUa_r4W`r-L)QW}lo8;~ge8C5J_kL^m{aW@;hqgc`BSx6eZ?Q+#DC#Hh!L zNr0e0!2_c6_rO*c?CP#oE9nV`BZeNvc< z^vUM+T>WTileifle{xHVs^)!CCS_74Wm3lF+w=JP%O^a(zGQ)7BwYWDV|3piTv6LC zRpRq0hkG{u{T(Z`=&5s|Lx0juPc42jeH|4)H~Rji%J_YW^gpw>c6Q;TU+H*M9<_aB zNW<|&d34X`uRX8$ZC9SX`uvkMJ$c{NdtbD8Gykw=zN7rY;u_DcVH`9_zMk^BVEKyx z5J7~!FvR;Z1_+7>FXQ|jIuM4Po~LL42zFMl!7pF8mkx$Y?e?)g&n-l=5tMkzY7GG* zVes@`wF$3&6iWySv*PjGMoo#6`l}sSMsM7|8$05+35!*&Rm~4lELarpnuKe3Tp?)0 z>K?(d_)DF|;0h~g!cCz-s8y?R{l?2NKfi3j$Y-B^8u#wqkF&ub<`Ha)SEn5*vVg_` z-jn@>m`(bE^}EMoR5wZj=EL3|dIsSt??%{!0ETgb_hipO=qs*~yNK{qXXglj%dxb2 zBgl{8X}vtv*qrGY>RFV4gyCw6_dfPJ5%{G3U5cO8ex%h9(RYTZ^&|Ecp>$nc3Fi zkcd+V*boq>aFOIU!$U7ws1G&X82+8>9?bxKA-TTS8T*37m*WL9L%2vihd>k$o%#Aw zOk2@b)Hq(m;lWPq?cCFTYeW04Ms#%SY~FUhuD$)8$ZJnk6FfNtp$3ofN6BjMnru?+ zIV2KeHR!0Hr$N}q6ygaXDc)E5PQMWPvB3xu;v;0Fy(rPxH?p79UQ=UQ)4b(0eh7@G zGlVHC>mVdwPOv%%^37aa3@nUeUxk(VaF{I8@yI(H9L0cKFYICPa3Ft=Jv9z-2z0vVe zL+v?_H^2YA_|cF4D!%vT52LDaW-c&VMCgjZ9snJ~%_-{&rHo)rZOr86G<0EqQoT#0I@WR7^>U&<#(}GK%m_m+Giyk<$Gj1Kq}W>)?~)MN7JOREIxNPP>=-m)79b+Bl10@K^!Gf%j3NP_e?s zIopQ5%Zj<9MkDriw_<;P+g?#9LZ`G3XYH*Bj!2!r8ra+4i^hT0Zi`TL7{L;r5X{Wj zpbShNsAEMuQDoXE!|}=z%rQSGKO8zvutQ<35n>PT8`dWRe1zoGk5UI&1^6D?1q)*wL8bIRhRqmP@8fglC5i;MU2J6&%J3Iv7JdsR=te=pG4<4xAGb*a56D${xp(je_1W24O$B*Z@@e7HQ+DmL~&J{TU7h-a8~{LO-M=k~5i|ifPX<1kCE-e* zMJZ;lD!mx~1Rg5!SKv(XMQ14_q+YDLrVRt+A4!CR?G zo&oxUVG70qz!9OA@ifO17%yDB`G$gP42tZzCcXfLTCda9*q+^Ao^^at(G*V5ZYTkw*&TX`zLFW4Yt&LbA?VrA;qNtH$1L z^xJJSEv)TJHacQzDs%OC>GjuRacNnEWhe%3KaRz~wGNN;DMY`E!mMjT0h*+ZSV^Wh z$jO?fq)mEdj+p3GA!C?{Vhn}!yIov?h1I`v<Z<3==j*e3Yb+}S(yRM`+#{)RxnucKpe%WXf7O@Mg%5V;3B9X&UA{qD?UN@LgWwz z`?oCyd}CuXKK=BwXt%rR z+N4a%q)f`BP`=erhoi4AR)ovPOn5p*=f6t%T%BM4p+BRSeQ`0}qCDr3admt=?R^~j zlWuy!^0{ZPK0ZG8MA6-ku08J<6@Sz3^q$f0hlO8{pZUt=;b11d% z@I>+XuhNHc-QPe--jt&sblLnF`B=q|c6zbBBc5+}KhAZYJV?da+2{|t7Wh#R+#r~- z6}RfanjV1*(H3lJE4~}cTogqJGVrc)ZVmCg3kxgyM9>SbPA(e+Lo==i#TQ0p2x{iA zRM&eD79rF_z`D1)9l!m}uj9_0yB;6-al+iecOnp>JPgBVK^gB5n}G+LHWJm*PB ze{vEfwJ+tfomC%Bt&l<>grYB5s3(IuJka1J=?`JE*mqR)UU*XW8|){J#RC%-3c-={ zOX(Bu1sm6$5nbRg+RhC!ZT_E-cZ65MlMRIp!pMcil_=NO)i*qjX7oygZb*DEjzjo^ z(D2;tV;@me9fWgY%n`1CcKcI}b3bn0d{yJOV2?NygCvZ%74>o@_N5??zB99gdthDE0{828V zK()2DSaGbu5hSCAM8M=ex*#|cENHH#qZiYcr$S!Btgm19T1HsPdHMlfnV(Pjjj-z9cyK>9Hy>CCnFOXO zQV7b8v4R>QF8QB;Z+rXbCU8ql>(ZVt8gAwQ?*i^cF@82cX^f>m2Bq3xYi!fHtHx|~ zP48hmd(jY#%w)9pMgS{V1J6+GEd$H}e?A1CLHj_)c;S2>&78q-tl1prJ^S;LrMPgQK2+z%q;BRkdQ*g(aBc!Gc zY2Dntb1Q!Gv!7`lqeMpzL0z<3w~TQ%F!=EM7njHB2;X`B@d{W2oEx9@d-a>uO}ji+ zml`F_ojt%b2gp)N#e(Lg9fyZ|f<^L3F&{IdInKn|`n6bIS+x;?jS;}j`h*^!R0nQ= zO^j+=ZNZu75BLJlAC$BRwaFJrXvKs5v|jKsPH7m(H;I8m3Uvz%u{KbS0%uOipzroU zRa^4;yzwm_#B|@@n1W5h(=M;z;kzg}LP?Nl+VRn`;f_3JDZiW`L2YxI1mQK-AD+oQ z(GEP0p;cDYs*lK)z3Ry28{}IfDpmLmzR1!q2w-we@*9A2VSyMmp#9uzO-&7 zFbW+E2*4|NX))dj-n1$iKaDF2J(L5ih3P3gVzoX6t0*h+Iy%>U1KT$A*4TjOz@I2U zpj9ZO$?pfMr=XPNJ2Ev44wx76j@9uD7p{Q@+Vf0!7sHrywE>)zlsBP!i;*v(Sk9OR z5Q=ep9$bO99&m=Y6M&3DzSC_AZnoot_kSB7eej;%k70`Fv-$#TFpeBdomE^^VcYKM zPN|{0q@}w-LPC-5k?tP4hL9GKl1}N6cBr8nq`O0E7`oZK-}~+T+Xri%t;6*^cU;&1 zIzt(V!rc}I5xH`?t`bST&$s6@?w&*~JpB?EZ;1-y!KsG}G!lZV|FYbN4ggd=Y;SjK zOQi_!4W8ZvTIOii$}A5V97>o`aK!nrF^|~{o3K1@Qi+hYlS-rDZ+l-YchI8Js+thn z>ZV&?28|VVX>POl#ofFUmH*(-Xss}>{ia|Bn4_IpZ++S0QG<1P0Sy4lc zwfJ&DbhOiDIZ9D(OeRQxY74+P4BoQ|F-ZPg-2p&}EEImfHOhWo}CTfkP@y=O|J>e0JRJhhmSFwCxdHbZvUjJipzoX%V8J5|ZM2y`b zWG2fTB-?3&DjeS3dK>1AW0F=~!G(j}cf=4FSm1j7Pw%;mY;WIp;57&H)wS$JN?&MP zw$U~XV0X0bweoEmx+RgSrDm6tAL^q^T+>_y2iu7`?$1p zycAwTh~v&tteV?N|5!`VQ=9M>x@Af8>3ZVc=C@O_x)m3FIvMeWFZGKkZqs-{7kB^; zxer~pwHAG1c5DnX(Y?;!39t)00$J7UsT63p8atcG{wy;^uO;~3oc8VYBfkoJ*OF?# zfrsQ55Vjrm6fZ)oI7s8!-Z+&N<0V#o%*y(>jaA><##nPfKpjntgSv@B)$wurNTjFD zy4OB3dLInVFrvdm`Y+0d2t8!MLJ!jWf?QNTmPRCImfQi zr+}w1v*%qPjhPuJF2`Rd$9*DAQt2w-d(?~6$?Akio@s8)?vyNfuvCR>p!!XRqYA9` zZwXv9Ft}ar=clyFw-#&8E`jRd7X?W21~!y>nw$4 z48T;Fv+p18$k?l=&8n|IqwnXinRz}9K_%A~j&j!v_isP2b!sR-x}xKANl-xPv-b7| zeZEU%o#CiNevyYev5~pU9ynJn4}FdBA%%_+!T*A#d$fj-DB@qTs(EVG8uSR{oH<`^ zFc%|>>q&HxFZx%a-XM3o{q`*?Ec0Kk``t(a>wKstF=Nv=4caA%;tLP%4NJSG!;l3C z>IUp?QfvEtW&N-@`+g(gCiC`m>hR;u6ZLLy)*3c`V&0n^qD^w$f1tZO40(DbkT^I6 z!+FCFbJo+{otSkXiiYym@X+#ggeZQbR1s(!N*2T4j~PMamF`1AYxH)$z|bt(G2xLD zqb!N^{Hs;~3kEFeX7J8e(g9hH7sG2n9Z0Z;p8$)Uywqb!nlYHhnK zmeCk`nEQmc{fV9EnLsUw7!~7|G2z-}puas)Kx3LuxRdJQ;^-R>R|WUdj}(MNJd{dS zK3ka4S^rUp49>FFWZsV4d);bIr4Id@n-uZ%r+J+XRByM0e0mEu!XI?JPWGCfbO0ve zqU$fOv+3LL_1+iw%Tw^c1FXHUgWwdarYc8rog!-IkNvVk$hI+zX&vXWGr~$^IB_dn z%AV72%r-~B(#2)uE@*+)veG7hQOC;DOk)6a3}>=%$%jpg@uV}o;I65F=x_;T3W$l~ z#HoJl4T$OsjK5|A1jq5yAlmpfP0^*4+fK>76-J8_)=L zh&I8KALGa#Os}2Fq0vc3)ajx!{IQilat-7gFY(!o0 z3AH&4nAxu>yR&mbW<{row3?D-`gEEpwrgD-vO3%Oawm$2S=yNzhp8Mb{Tp1n0P zd!Z?vV~FAcM8?>GRVViBFNnvooSBdfbW$H`0cZN&%WUhE5pVxUt5Iweql|d;tgPg; z8?8@3@bCmNWvxzKsEi|ZAS8T?sI0~)wavkFS(LCdY>__5RRX@y37txx*+u?*~|fS`v*FEFrNYvrI%CX8gvudL9es>nO)jqih+T}#(<&c}{KG4<>KIXo|m zjtb+j=AjC%p^a{uh%Ht}1iE`$!=jsSJ-EK47uazYGUJBK#7dU2_o3_U{xHv7VqJ2#mC6RY3>A znc}yU{!ZlkzsRADU1Vr-pyqIs>zn4@eQLiIcf;k=@I&Z(6lR7Pp*SnvUkJjJX0})X zr9F&W+N?`>ILR(JsALX=2Hb0LgQ%ZqZG&%vmJG^XbHB~%jIZZxnr9Ovn@xg0(ms{- zJgKD7Y|czIy41zF-3z+~WLy33U>$oj*s7yCz5qbNM*<#4F3cpTTeKpooPb+eGmZ-b zmjfycb#G#}tqUd_rsb@%MMlq|pePQ$ zzu~7=RI~FcDPQ*g$oF4o>eVSOf-{>34sYr1c-+qNdCYp?AJR(OFGSH_Ry%EI@A=za z7W>{Nz}qJzl!QBNeeJ2K{+)kX%(OWZlXxff3#ija6cLpRIj{83Wt#xOfL1FAaQw0Z z^uO=MB?F!#)~g5jl+__ny z`a6Q{NAdt#>M2GeVSpHV+Mz5#;yW}%>40~4O0`Nb&*iO~@ubX*o8kQt?XpoL!U#H? z!m_9S9FPQrnKLylZOo@0FPWY= zwQHz?4xXt%I2arJMUze{D-iLiQ^Kc{a1GvvlxEx=wkRj%lCM*yj==?v*3T2IsKJ)c#dk}t%F63KQE?=F%fjfcGjZ{n(db6=+U=UZ#F6tGk6;kRgMD4~`iS0?`M1T`S1gyII z(C;`(^gw~qiP5Y|0wo&NmhFrnC1(aL^`p7Y*(%id@g$ z(6_mvuab0pDPN@3#kI92#L@p6>o|CENa+iMS&^^bk`(06K+=>qLy}SOk@{IqUI^|> zjKjJ}EEu&#!u7O<7yrnd4XwS~MBe0%zi+*M#*l$ynSa>2>R&1Rl^5Kab*N-s@xW8Bliq-yxu^7`V}&L@{(TIpvv54HD*5@fBp#Fw{femaHEGpM)# zE95lF>tp8xyo{%CouXk1R3fhJvppL*Flb!G3Gin(ZEGcUaEPsIYhuWJ{ou^s2WB+% z=T&b*NqNI%CJWc9(g9l7^|gdu;XHN(T##&5X7<<8{zp$F?sIyu)-*3-`UyhWifl1D zhZ3&Fadf@n{;b$ddemQ!NV0LFbMZb%1V76#D`og!h|n3OAtH{Y#26hx450z4NOAx$ z8nMDN6v{hI!zne(efi((B()tF=sQm-5`yuHe340=jvdU;~?s?67 zrQ@oO5f?vod39z3oglL{q(h@C`&(ru1`5;g)zW214kxH zTx~+8Szq%v+i3kxft+?IQtgpj?v&vNdMwRV=edK0@2tKH<)PDdr+L&0QVgsVuA8nt z@>LG5kbXeT$GyQE2tym&%y>k&K@Gb?)miac-(!Nu)*YG1huq&`KUIC_cq0R1uA)l? z=-m9!a#|bsG_0H#TSw~)#`w!!D)n<`MRpX^v}r8kLjQt;5bzs*xP^`970KScgLGAh zb^|;X#g<4-J6QFXVot{V>)c*)aQnKSMqTu7DY9nlg>-_ACe+KSyry^{UfL<;q+hZ; zm9EZ%-b105 zMGB%PxprCK<2-rklz}|#r3b&4`V1L(n74;PAN7(i>QeJt4|6xri`i(tunm0WRy@_X zWs5@Bm5wo_9Q|QcXIO~zW_`j{?h{r)AGRTKr|*8V>@SBiYF??JM8BjBU3^z9nx{QO zvE1>%-vh!1IoBPf)I1-%`v2Dpu3uZ9MaWlS*YmCr_cw_FFQuFuLD!dAe#@|kKQhOh zdPX=0ru&&&U{XFxgsse6Dw_Tb3?3W~OGJX5$G-(VWwmZBv@_x8HVsP3l&6qfoO5G6Lm^rR(jb z>GIZq%Zj8<=j|q#DFd*DK=?i}baK6C*W03ie5P~y9qiQ4s|&M{@M%q##e19o-GI}i z{)eBY7kmd(=k!ePeolT-XUft0INN!%9h-UgrFCgw|7rV$ELEE_$LpZR#eWLAswsZ^ zvnAs4rtbVUUX$x|f`8;wbs404Ozwa_K~dp01jQ{X)}0iQnR16 zt-eHG!=OhR&c0L`xZ@GYY(+FSx~% zjx#6fe&4xHO1t8E@HWL-7-LMYM)}WbLi z&b`Ynog`puH93Fya|W?pcK}0R3kEy`WU|Xir`+YDZeDPlnmKO2(V|fIA?S?Xi%0*7bd~TD=i%_EE76CaXeTI{Xu~7g}jh`ug6rY zAp-eX48E{K&A5dM>`M2%k~*i%f0UscZOKci)tY-spSoonRl;;7eY%$Qgx`xE_4U~e zY&H|%1f35lkMHjJ4v_)fET*8&Q1DdKZt<&`$gJVrUjLY$XLfBG+xZ)uNzMHQKF%rK zB}w9A>g8eT9^u3Ot)E&3qqy$`&wmtm81zct@0kCX4C0&&<$(Bl>iWx^7m--+H`u8A zh9@MzcSM@IezdEYJ;`l`)kofCbJ-?>Ej4m4QJI-y$T_@G(kxK3mc)xCKPJ=~lZ`ty zcQ#kpSU2K*%wdM0rjImT7l@1dyZvfsUJu%WGZ z{}enQZCwgu{W1R!M{dEL7$tWnUUnuLA;l*}YXh@76t?&-CqZ#LraKRaD3T8i5jCe4 z89-(^xzoxVRZs~uHl7RM;x-yI{Va)5Iiy^=EK$ma9%?7IC)wh|+SDZ6Zps&gQgYJ0 zeU0#^a)=z;NBbN;bWBIZ(!1oDbvO_*1aGs#kA@;4a(Qh%g<9-5+G)Hdkd4DtWwnMo zrgQ8lz7wCn0nM5Uc#s+yu~|t?XVELv{Cc*lsR@6g4y5h>dv5s36q(77F%2y9TGbN& zN)G}K7raGuUs)I7fd7&Z0tndE&<-K7V@H}h2sq_jN&>#)Mnl=dV%{KT-VMbNRM zlhZ&rI=+CWWIVkpnE3iT)yIurZD-G8X=X94cWujc9GPABZkJ@#$NzW)Y#*&(kq9m>kH@mb7eSIoaF5v*9QAKPUG99I<=L{4 zezH40J;mVB16o-bIFvcGg%V-9|Y{c_;^J*KeQ(7rC2#< zdkP7^e_qRuoB65$1IX6+EZHW~rsl{pZ$r~)6)PxTdN42f-J1YZE}1(kW_nZm!)h7b zZM|rNsW$c06`KMwvcSeVtCkRrRNe#jf>D;vz#d<`{0I4X4mGqEv=VZXGx`%?000RG zG3eoEZXZuDJP{6$f-M4{=2&wVc#)W;R5R+f@NStjKjWer`^s+XstTyPo)Y{lsJSFx zi>nLOl?ev;OTf}?&QGqys+fd7Sx6?E5d&!tl`&DNCT;o)v~u*8i8Mn3aEbvQJt%n~ z^d>FvU){O(T~Ik0Bt8_y;@#)EaqJtcfqb?Im$%Vqe1{;v>|8`LwqP%l?UYbjtv}0S zJB#l>iQ1AmxW4ZYxe_gGRMZf0TfBxT zm>qD1i15U-aM@nDhCQ-)@zTfgi#%Hp+1}M3!&+WRN2-2^P?>|nQBw$iVP%~SjbnES zUa7B2FH|9REWS#yH3}C`UFW0aD+v<9)Q#rFH=rVeATMMM75EdxGFzT@3y}ihd(;Hy z_!*hnsd0qidvhCt-LIPHfEpyfYG^Pn^_d8X=I~i`2o+*%;j*XJs zj@5{3of2SrFVqXvQ>$x(5MX=BHPP2j80m*>pyV?{ZsD69s2OK|JFQ|8OU+4P5|WLr zs24tb5?=2fdiry2*NHgZ6C_tvnkDYeQf{3LUQ9L?OUF>BH)0E-=O>}Eqq^s%0A(S& zhf9W)W=8nuA>I6cDWkOHG0Gn{@d+pBy1G0nv<8mJGFUZoUH7GhQY^*n3PyUcJtnh`Bwx^M_Q?RmQNCap)hZ~_hy5)u zEK|}5aQM9#J>eV($PK*Dm&c-iZ>3JeQ+Z=6@wYcGAV15_%!6WQh=CR}h8Z#k2u8`< z`AR>52K_`#=sUa58-GaVWb;UnVq$9?{n715sdY_{&(c@nv4Frei1@J>lA@8SgE5gg zQ~q115MGWVeGJ3D9k7;$vMwk6jv^qQAl;_@hN4@~PxrUCXf(RdT4L_g4om?3&(^=j z7deVDJ>C+IiVC-jezm&#`aPgq(9oT^^9qRBwC&Dt6z(4+nyM8xO9pKE^%S`jeK0c2 z4MQf}n9}SglHIA^;MtumPqAB$YnRk`DCH}B;MxF=ndKb%5_bZ3$#NT{*}1jO>v9M8 zhop@Y%c%URp-y88y2xoGd?jRVo)FprRyLubzOVv}8Z-!&7Yyf2Oqb<5|67B8|KK8D zS&T7#dWBP=#N&M3oY{v4nh-a0!kYe`p6{UA)+!&tS!k@jzHzkl^R#rGGE+>=tMi(w z26C>t0`cxq)q+ki>Srnb(_=F_%jmgCy!xISuhxicr6YTUoZe_o%n`7PjAJek&6^{* zVQiP_5Q%}vaJNl>k~Y#vhe95Ma2>vbQ-MX6cZHNxHZAI+YVaSf*AikV0JCXZ!br6k(RJlI&5+jgThB(BfZE0?Lj7 z)broq2A}G}z$XrN&W%}*G_pe8x<$xF0p-hG=cCEvF&V5s+kbiL(404<02k3COo;4? zen=Sbd#V%<8$|o(x{rBw!|+ml>E}`6#92q(-&p>CN~hZwP@h}!lYBy3AAjU+_^5!k zGs<#i@EPIuXaIw237#uc3?i}E@iJjG@DbbjZJZo#J)WQp4XfPG&AzYuRqL2slhRG+ z$IC+_2?akMPcWv*dHQhys5SCD`UBT~PR(4)7V(9~)}u)_)68=Bh&F5~`ef`_V+|80 zr_Ki7La2aFfhH%M_a-w#OVYXza9f4wgn7KRj4oyi9C$%rAyFX?B_1I1QmXqP)OM^i z_m!3WxF-z%H;|i&wgzz{Z_RTXw24HUfh$&rN^2newm z@Uac4<30pfNkVS?8r_IaJg! zfDpO#9(G}(F1FuW309FF^AImvIB2KnVIcT+`8KNa<)yD(+{eSk-HalTKD z)9+OK?5`BgL8!Q`7DGX9zpeV&mE@mF}aKPkh zaq;?ph1T|fbsOgCyv)rDY>wMmZi})jEzDPx=)$=AzpI>yQg_LrwM<^D6r0pud^MEr#u4jFvAtDD<&3A!+aJe)=uqMK~u-9n0P zEuF7kJo@%)9+90{cC|x2GX9HL8E2sKK)f(u7c1j)8(n16=VM^HnQW8o#fYu>@+6av z49%4>o-RRT!Bx{DrUQ$G7=-H+f2JjU&vY2k&G?FfUvn0~Kf{`ieBXO;Kf=@J<-{iQ zs%kZ=>ue+n*I+23yL1!(zRQlQp-!P5a@H19dL*@R5GV06iJhZER_FcX2f06VsC!%D zMr!dDu#gp9%*CFbJGJU~ZV_qWTGyb4!^zkEJ%SJ=wlzFdKC~~(ZCo8Kmqj(x=Vh++ ztwyKUhfWivPn$joW|f-J6hG-IRiz&{7@g$)|E01{z|$@;zV0m+k?J7Fffa>=(jaPmdeW2NGq;$D=w9z+iG}ywthQ0ow!f74o7X4hU}Lq za!oc0`26F~ehPy=71n5`DtnnoiU|8zKB~w@zvF&ZZQu6Ls}B5nzVN5RGC#G(nCJxF zsSPJX`KgkGQA0ttubuldcHXp|e10x1j7pV#XTxq|7LkA1P7vs0WAr%v71e)?#Z=vh zbc6m@!TdcNAGE6*h>vDNdT)8hVXc{~&t;~c5gzqstZRvSQzT$JJxZBwIFz?cmywf# z^lFH|KXu?p_O=%DjW+)p{|-@;25Jlc3G+H(9{do#zf^WF zdx_z$o1G;f*x%OF;uz}GDgiqSBP?`{VlxkOl`q9(R%~HLISquO*d5o74rEf~^S8=p zHOomfdu-TJ5$H2?^*w~TDabC)Wm(jX1Ae^q;QRF6Vl}2Xh9q0DUkyeNrbJpRV@Ih3 zYloH6xR{D0YmIIG(D+VAuuHdwk8weu#T;66>lbf!uJnF_jzaW^y1ypq*#{1Lk$$PM zZA<`KdGV?G;Sc9qmQnF^o=3|2e|w43(os`$fS-@l45;yR9tPMR&k{^d3CYRDw?i-z z`-I{kvH_N(@1I#e6dX!TiDV5>(YWsJEP8l*=Qo+@C&i>ie#TlVGBB_5)v%;eU234G zW2rRzGduT;ifCgB>}_v*WfD&;YMp5Sp0-7(@wn2Dy&l}ETix-vHYR}b9r+$tFTK#6 z!91$>rdUgZB|fH}z)2_j7XhMO)kWT4u}coju#u{hlNOJCQ!4Dp)?lYV=I6(WmxvyU zxqUKJY{7lF%27!X7AC;?}1|hv2Av#F!5- zuSRb|{d3-!IAh%-4`JRF;idRX}`Y<=ckuzl@Y@p_Ov09x6WJ^$(mV$_x(^3Jq5bi=D35W)Mz6H!AhcS580m?N$1a-Yb76hsvG{ zqr+OeNY4ZxwfN|=I7d{OFXE6G(PgPd3BxDrxOeR|TtrI3^^%nMIF6$w?kw}z;CH6< zk|l7A9lErMx=6Ct%`fX^|3qk2v}(29O8ZLlcMCY1vYB%9!bMj>n8>tPs|tEW(LVq5 zK7dGz>OeMkS#wuLhAyAr;TQjoZZF<)g<+*j)hS&Kb!7H@{+GL4h%9l!azJhxnEy-{ za9XaZp#G1ZQoA#hWDcdZVsHPb+(XPSkT{tQ$i4kuWOu`S-8F82IA2T~t#&@QLicK= zz`U^p{=tG_=v#lw_g669&UeHw5Z;!JyhN9$4K7Oe4Y=ARy#!bHIs_Y_6HySzMmBzRCC~=F zn52WOgM=Nv@hK)me0;08VW&7O|2{JjdtEbnhPcgJ_r`WjC((NL$sV)BXsk)n(N_8# z;O>_l!%}#gS6j_yusP4ZFE=wxU?NK%H7|VoZpi6lhj$9&q)G~5oR`uqA<&BWX8~Yp zc4hNQ6q##QI>n6t3|pe~daF#~{TFuwZ5|rSN#-?qDUNfiEhq7COVg9t?dw}rG^!yr z75wsG!?FALD0~PKeQZ7-+xIScycdj>cXMg`1-{GI5{hNf&7v`mkfm|74^=PJi7D^-pN|8(`b%^*ED(P6%N;HajPQ2OzEFyXwj+(@cA z?JzU+x?0K2SYVDI~GQ_Q97QsVl`sLg$!IR0H zkpQ+!)EdAz%m7cX(GMX;ztrIkuFW?j_=LeqrN8 zC;|z&Q^o~UrBW0v_l^n=y5!34#wKByKw-6m#umFA0unfMV0eJ-=F;2(@X70oeBN&u(vc(y+!}TicIQ_Q zUO=@z`Jrc)D7@~+@v7ogp%moIZ^)lPL!_701txAFS~@zgn|Q?e^U0mDO&d>>orZq1 zK!~qYyrrugrJi5>760`+*T>Jf6Y;0WXi5S1wphQS{Be<_G`X8rv)gYs!V?|2{x5SB zf26te*8P`!AUW+bAn*?AzMEh3QKv6GK%PT{CKV2=*bgeT)DACKdHI_G&($XHR33j_3o7R<@V*vopEkwUJE|Yx!;ZO>iy#~ z?W)By6j+32^4YI74mQ2%pJUR0Wh|M)i9aE|yA+$Ee09j5eV>h;WV=Zx{W_nHrhhNU zdgM=RvFlDxdbrC*>OtB-OG~JMZo#NB|LGJTT5_(0R2KfJ_ZLt z6a6n%M|@R2N`r3f*BsPlmXyD6c)p~7#%zwp5!EepHQF36A zX#xos)7O@82abnwdaXlfHp0*L1Q0}V>pQn3R>j_ezhV{qL9LaQ#)*B!4u?J;U}Ev@ z?YJD6F2=#4Ykm)!+xPLWaxjxx^W*@170<3vEmlmaAvKf{qbe?2s(%4h#W|KGk}ESLl7R+e88X^;gXtE&BO4>Zl3?f!&_ z?<#PC8V7c&H%L5Spqt7}jB{45_li*edaKIW`@iiNf`nq?6PYB*m&%1-BF23i5`DJ5 z;|CKh8{s?VceK@4`j-~?EXCH}w|GB!jYag=>+7z@3DQur>yQZ2xk^a)T{!27s>~-h zD}QuHG-KEMFok4sA1#CDYQ8QzPMN~H$f??I7nMCcHYb2Xazz4T*^`z`+e6By!5YUl zit!OFAr&bX#Jiby>JO1{%m#M%lx?CN-L{H?Z?K>7Bp5vvWn2)ASa{OAj>-v&-{#+t zdeJ&C7S^4XwX>GP=KL@2Ow)%v#A^I-k5N%{r^$ zGNKpn`5ZQ@$=VKE6o!(oRf$uSNKMP7ud`?u7d9KEZb8u@AP$qq({H5`{Vf}}1V%q#hF{L@HR$M!zAe36~cv(bU zbM`Sngr=EtgTnwDu*3Cs`;F9V{QM(Z&~vQWz(nxf^1_lR0u9^bmRecBJe{iSYhfhgWNaC1xgwE5j%^p~oze_~Z+ zUXqx-_jcYCo+l%?rt0&Eb``?B0Y@W^6v>|a4Sbrw~4~8UY zCT#EAGGT=gozq#$gq%}Y;nM@)G4z#7*Vo=z0zV@^N3|1YU6{skzb(MUIM;4FfniBg zz(Q%cxp?IM$)8q6y6%S_V0k8vBW;t;RY(HRbl!q~ZD^Z(eLXb!Q&Up|@LO{M_HtVV z#K;L4)asoYjUAd19%t`*jeM&k=T+a~C^;({k;5)zg~xdn09$4JuCEfwHwl89erLBb z9&!7L8(Ci5`t@;2M>rTg7pYeXbr?$AlTr{hc0d|IH7QkJrWh^WWp$l0BYi}uZ`HgV zq)I@jfOW@3OqwKT&VLa0zL&|C_io}?RH^SU){Vgd&kEB2rjN`5eL?}4S2q)zMs{?+ zh17??;A=SV5B&}fe$BD#PuIl6S1$_$M&Mut*a}~Uk(Jb@KodoY9}b(>h74VVZz>Vw zR1(jzt*Eg~Y|(x1@;oLL%&`)S)fz`)m_MtgE6)+B_6N|gXQP0omZk^CR z@&?_qO2?#`1*_GH(%yYE5qazD`k^A8FQNcfQ}morXr?rD50gTSam9;e?T{%_OjySZ z{#Y^rklkoZAjCT1-YC;04*0cN8VDu3wp6{LJ7Q92@>MP)Yl(~s9|)5wtZbiw$giV^ z(Sy))ET}eO-?e7;V*rb)`)`b&h&mWqGu?PZbZ%vN)x?u;1X?Zm7zo>m0=k0D^TOW{ zAtT~2=gkj397mfMdnRv}VM&jCN!CRZ`69WAYrUqm9Y;pqFEL4XMkczlD^EE4DSKWL+DO-0mj=k?<+r7iTYBD zJtyH30DFMX;XmvDyrXP7HV;pUS|nurx;5#xfJ|K4i}!Z$z;v#3d)RBw;R! zt{o`~bf&X*#1@zg3Ef}0;hhjuZqK>+SH(9@u}lAoOf(+bEbQGq_{cvv0S~*AHh4TGV>rKKib~`M>*>BiM zGYinzTRJcXf`}G&-;Srb^(af{8g!gRx>TO+Rd_r%v<92{o;va9qce{QncY%N@F0Dt z`@Ln89lKjew!3Jo(>G%18umsFLf)D-_#-SVc2W|9hd_)zy$}y2??i*u+q-G|@zHo< z!oW5w<>Pb{@!HZ-^md^|1EDDq+u+rZu3Lca&ii*YhaaNwnZaZnQ>=M-Y3JzgQ3%6OQ zKUjIECv!Nj#X`!HF77v3pH32XY~2KzO*pS2_>=s5rL|P!ptnu50i?=NQFTR4*D4z9ShA5cAJ<|Olc z|1G#9m5{^>+gs1VCOI&VoR%n1)~e}!%dcc^J{wn9o7926d3C(dkE1G#VgdqhdPR4w^pr_8Y9>^E zk)@BFJXKZ#LSgBt}^yT3=JK85)q+G^<=0jGtdou`!?heY2D0 zu{UXv{v}(axt>;%7}aAp?H$H05seRcCOlbuxJl&v_f#D#LMwp!ht2+H*i=Hqux?Uq z%@iO{OBU4H+E^^uRNUqP?|0xCpnaO6^@T;~DM*=3`AtGFPmd)T@=(wgkPYChfCf6F zm%*W4Kg1>jvuQC)!-2sE*SCJAFQ9ZSt%P`w+kE}}>btxDq<%1NI*1M*n&sCQiN4SA zjJsQ8A2x;%VBji0S6t9h(QWPmq_Mw5_{U_5Ls&xD=kiIo?J0p>-OpKd6j3Em4xHk5 z%dRQr4HNW>5~V6hIrIU=8wgh2BCt1`^}q1(B_VG^l~X85<-T{?9!dmVR0PLqO8E&_ zSJm`2I?NZCnnkNRb+7SY>}fY-<=|d*gl$955KSL<$OTRP`;-kb5_}J zkq*3nIoLpd_f7k^(oK2J)X3e5PiqyZlR)WQz%aW*%FFh{W=2>P?BAkQRs;H!vx8$J zn*EQDGiS$!`n;!WWTvl9N<2BMYXzROVaq_|G?15wGBGe+K9XSS@4XlS&A@Ujl1BgU zaIaBA$D~v_P|~%bij4x?CrO>>S)Ft9RdRuUBE7Lqn>k52QKjo@$SIsFtjhqX>F%hK>$*F=(knc{Oimt+fF8yQ|*pimxdF{7Nq(As%3m6N%9^Nzvq!THyPRI^A8?h#Tz zb3BNiLfQrN0?gYWXK;0>5hX;Obv=W>`NXiM2>9248s*f8pM^GRI9Uq(RX0T5sV?tQ z%I6+ZQs%-I0rucyYn3;#mnBV}Xl{x|DB zoETGZ6D9q)efwSdj?C?8R=7~#h*-beghCmIs|1I#Aw2vQW&)o9S{Emor#EeoW5N1B zc`a7$lWT4*|6c8K;18npnFId11luRhZR`@t>B_|IjrYkGSyzahg~ljo-BAF66Gs@} zW*mEc7k>R0gfPJlv3N)PcT8+xAy1#k@oYJgbn*u_$M^1vQSsZRVxb=XVj=rS1I==x zME;bDu2(NYy4bv#@+b za15-nva}NK6ZGKxc%0T5m;3sLuRT;wCG1_wCH4RhblWqooEElXb3UL)tf#I#4-vS#X*GJ7cHf#+Y90^f4baW>^Z#t%W0-D5hSm;{oa=7qyt(~swl9w zPVn<2_GlMJO((ev1a4hfS)GpYv-R%^-AYLG(nT!HGAOx=k-f7LWxH8QJ1jIvG+B<5 zPir)Bs{VQ5PvX6KL4S+kc5X*05gYxd(9Nk}YR9uIlJRkPme#!T6y$8nKAN;+DaejF8(4=~mXfM~OmqxWYA-rk*%#h)K6&wuVXz3=e5Gc-i`evxGf`e3F6 zn>GvHY@H%E32&DBC1aawX~FXLGeo>Lg}ZlU&=hPg)gkHH3rmG-o&)`Ml6kZsMWR9)3EK9aC@FWh@P(Vf5-`7OaO@8kNFAi zwWMKX<6MR<-hOj>?KZN{HF38VC@N)VUo8}@x zo^*P!NoUX}|03V3J7}w|5Y0+Fy4cydvO*))yAF#v)Sx-inrJaZ?d;-<_nt7;1zjx0@2rlFkG^WSg7LQ0WdsO;Y)LH)B z4a#B3`$|K%NyJMj>EerFa<8TbDNZSy>7#>*K=^u8x~NRT!#?>5SZ#1ME#u1J8C2$wVi6+~k7uv9_5_C+d_8NJ%L|1AUdX-N+pTGMa zU7d}t5~ ztcxAGpC|=-t^P-HjYR&`Lw@-xVd4?)ke3{ z9sqz1pIT=!WMmH3Ehpqg%!@|lgEs_8>K z6X(Gr(q>@A>GGs$0*DkC@bhc(S~#KdIaZi%QGgK$SvGv|BpPX435`Phocany{4(*( zixUm^ZlRGLQ! zsZN)9gr>-== zwVW32?vZ&?n3Cq_$}AF8%UyNZ4l5cR`XznYJ(6C_YElwnlYABwA|CPc z!O4Hv3;dv&aHEimrlNE}s)fFe0x#%B?#2QkuVBRY^CF>gdvfPa=yyjZr#607Hr4i! zeXp021QxO828hprC373E;ebN?4GJ8Gw<8YFfgxnl8exgbv+55X@T1zGbr#asZIh;)2DCkv8{UyljL>u&jHiI(+hI4Z1;(M zCoiQAuwaPF9<=DLn@LHB$br_7u9It&xh&(YlhRge95_}#FKVJ|KM`mOIR{ye16sjb z0>DY(z}_S2{?|VX*syJ{*X8Evn=YdT5N#SGXm;Pr*{LsUyZ@ZCUG4sv$x0;2fW!38 zlsFaaYK^O2sMRj<>E$MS94uk_>f(HqhrCR2!6^Vg@^<`tT|(!NzmUx!4ze(*uWfoGY#JmwH$T_c>j}JgeiB)6 zh%Q5%Dt*VyB>8Dnxr1}>i!b|}O9yeq{9HlFHHl}nmgOhy+H+Jnui9oZqZ?XOVsegmfe2wz9t8_O(UIh(mbzYW6A z-0`f}2MunD#=f1-`T#uka8kwsj`*m9w&fL^k%pvA_Cw0-sHpqVVePd354h|6|1Ua| zypN1+1sx!jf5Cy8>AIU!N_Btq!eeNkdGd+LaycGGX{l3#TE>~_;JuUi_{fD?S za#o!Fnc&$cYz4dL)42?>rLzTJs;(Z_iV|<4d7ZC2)v5+-?XdDfIPdo?h2lkb<4$<} zp;_Zuq7TEUQZ(XdH<@K!ViyYX+sbcsNGwGJuoAj-unSYl8(-#H3T1k?+Gdhw=?5m~ z)%%4oF9{dYLu}p3Gfw&{g6hg@lh`yfU&Y+{!pM5m&{1-FZ-Suc+=)0a_m&`+`b`eK zK@g)rHx_lVUPlAVvrwt`!Rj*D@u@5tx1L2)R-eJHbb{ZYnzoRRO48+a@l-@(b4zp(eh}YFT7Z%mpXd=S6i37I$ zHR~8yC77Xt;MQ`p3%{Fd*19@3Jy;h9S|}aR3{S$tS_?^EM!~;d@kmD6V{v3~OdVB~ z8s$%WkT6=NP30eL5M6DB0_xHGu7=%AP@>%vrOpzcnZMaSCJc;@%nStPOT<5$~#o zuX=qX;SiDYS6AnjpMFtx^cBrrI$yu&mS$m9`iEtQ-V6$0YM{A5!_SzMm)>6}JcxDE z*~bee>K!mJWXoxOSi-^(FS>i9T&$_HVwJ$k_-;^a&P~#ik&Vt6=gN1_pj#e8mRsfH zjD;*$EYEt{gfGV>m2dEy!3(*I#4ud6_r`}IzA$FeWjA+E7K7d;u82tH%l%7F#j9`5 zd6X5qq3aAB5UlUJ&04Jk50_=8Pe6o|wkNG>E-M`ORGqDeGp&SR6}PB2McxUdOSC5m z+g{but!Zv6*@H8wfE>!v?~BMKA43-3>IJ-IgR*lpPxfUWzZ8e(N>8;xPY%_QZ-&41@(W=;-u>5^ryheCxsGiJ@`@ z%(^>Z_Yqdsu)jx;)@V$DY(j;<)^cS>BaFATc$L}mVpSo%!n}x@ot{}H&dVf9cRxw~ zB(rdk75Y0)NbWG56siwzlKZDODc-Y$p@@AdclY6eUsy&ARq8W@;Dnx*MwFK#mJK?m z`M81PxwWHjX}8mo)9Ohd{9H@lk8#>T?e8x!7+&XQCN?{S4Pz9^iYkxnUtBJ@*cD^p zqbmyYcRv(6{k}Nj8J23m4%Q#TWTW@v^BaRmqs9X&j&@?W6mQ8`Ud5oie2$lXTX0C> zn`K9%sV$2Vsn;N1i%=RQRTt`re><1gbW7h&-b+)36U4f>bB%4+J!5mw@C;GFMs93B zn&QYhfIjQ|_Xi?#Aw>(?iXP$Y#5ZwtSW?z$3Z$4oq5y&Z+!1tFUyUoxLJNB|cw)^ZONii9->7dQFL;Yrtz=`oCmI68Y^$>9d(6sii>O4Lw zZWoZ4Q3#)d1!hedN!jSgC0NZAB8%MDHIk>sC@i#UK(HR0R@gT~>at(9m`3=<>Y^)L z^w>_|jm193)uLl5LG6|O2scmP`IQ4dZ)A}PG5=rmQ#DMIKKx89$g9`gP`95>!{+pzwKrX>5ImdhQ; zWh(>klw{g%Q4%s~bXVJJN=l{}(1Lg?ua$oG{Hu5>Z1U4%I>HMtQz&iItzhy0qS$VC zZJg~g3w(cJOV3}&r1b)P1D*_(7h9mVlgFkeFt3M)t&R`jIX=Ij@BEb-r8@rWe9>|r z)JYRg5pEn_(?Br~Dp#-|FVQDi2Yc91al24G2Zrw(9i+2!VB zH6i!;l09eb`%IAmf{Cem%YFV#P=u0itR273ACa0EqU&E#!z$??)c|Wp=tmyxr!>9F zl>$Sny;R2-BNPK0m-Ojp@HmUXV`f=7HWL8^k}SUU^+L~(#O{GA76Vv#+@p49Tu<#k znKMN&I|(bm#(G9MB@A#yFjCV#!HGAn1EM?61)ugj%#_5%foSNCeCe<-25T{ALqDMI zLu@%yRce~5_XFl2g!0kZIg9e47Zd7gwMDO4BIt*05!mZSJaywBaQsCMI`P ztnNs@ZKNVEq_8|*|6bS<$Vhq`ew7Rr(O36h?ziF!QG+H2C3Wcs-%@0&-@r9QOxkkK z;f7LAUY_*Qo{5cjt%+xuci-c6(g_!nmUoyU0T_afRJ2z&Z;i4qMD6Te+omJiU^ai9 z%(LyJCgObqb=Q1z?CjEiz5By;PYo`qgPg4{syuT%ABEeH?*1-Qr&zDMKilr=Znd6H3ls68DB6`+{giToNQ%6!$ zR(Qd%En^+^F7oaMKA%Bxr!1g7TtB8HBE-~;--2_oFsjwDJp4FXtSvoP2AV-7B|dps z3~Ggo7Wm8?%o{k}*T<(W_K7!zzIF7OH_oLA2>?qO@cF&uo}0XN@Q<<$n|hi6OCA2Yn+UVyUDuGio*hitMX0yuJQI$ z&D)X*MAduC=If2xUZY~i>!~4b_iN6yib|)SKy8F&4k9y=1$KhKiFmW@I~XyQ#*&4d zo>!TvJ^o~!x)9qsTS~I-q!AR?=A85^az&gDkN{0O%&qc5%8aUmVk*~l#RZc>!!cNMAtnm{^vbbMW0kJ&*~1!h%&)Z_GP6R~ z-BW%7z`R#dv(MRxMTOIs=aMu0m)kf*Eg0W~H&uv*NZF6@AHiEGJj_i4;XGUV^=Dem zu`881!5{y61t4Be19TKc|7pLgix&AVj0C7fjH3Ns)r5VH zAfSiQk@X-`ZHX&j%VD}jy86^>LA1;*k%>PLshON`es@o?*Cj+J3a}JQCuJgI_70YZ zM15ctI*{y32XIesEpqbqkLsHy^nEAgKUmBnW%L^?v{OO^ig5(o6u$LkXYXg%(QnL3 z!?mZ`wv>a<^v`COqzQT=y<#XhHr60vee(xVZRZp?gbbL?ZH+QN?mt(SUlN_k0z&$- zZM60n-i=sl$9AdlRb^<<#?xb_Vz)KVx>T|zb$s>uS#_vmOSuSBDx5lit@!(VFnIr0 z;{Wf5L5Woz&t<_FenIE&Om8opIy~f!z zhcJvGz@_vxxR>EEov^Cku}gWA)^!UuTmx-7XrQO1e`vb<%XzkYgBcic{+gG<-N%+b zw5a1A2xahn(L7ZHvOJbbc8nxj7n)?~&<}l`6i^=;zZ>~T;+_sjndXg3Rgrt%Sa?q( zBFxRw{gxhy<*EQ8dlmtIZDn8;#9DmZhMKHm+ZYO4|A>2R_vK>eR}Ha`b8y}kv#~(3 zG=$H=VA43BugI-IixPUB5>Yz3B~ShRt3&jef?+hg@+U%}l{tI6cd=dh_dyF__c*{F zxwkC(Sr@5CE`fE3hpWww8iWF&mNSS7i>r~5(Sv1vSgWaATUnWwDziFmr%d1+FC5sq zyZHKtDAZN)SoUlH%7hCGN4f=IIq%vF;RIDxRbe#i!G$|}dUB#N##s~!okp4#!@}fU zJ59d2pmJ;)=9;)5DpI*vwT;u{zaHiY+ED2+e6T`B-*i%VJg6vg4$opz9W{2peWb7 zi;5i*^Pa)s-|x8ll4on{0f+E8^qW_W%ZMSw`_n1SpLSzd^eU^2>tuc8PTg^ARe=Id z8@?pDQ+RIas~(g9(sa%PtDMMgZVnd;Y&qB$H^rFhdf&CXnzEHFcOc5S@YNKW;{{E-FZi|LIu7bTZ=H?pJ25F!&HG1eOSz4RZ> z2E-kDzId}aDzZirpubs|B!w_}M(z>b)_euXqtH!;ZZdKJqwJ~4JL~SJ>$DyyOdpoN zcT>3jJpCv2qEb>xq7D=n3)=lnG}<@RG#Oav4`?@yTH9NTKA)n?eW<~oc=cN%URgLY zHJu_$1IwGaPC@X+zWGGf5X;$0eeeYh@6VnKlsE7wo zzOwSfwpp?lvh=r6cJL$M93FN<5S=--IPir}U^b0Xu|46RIHjv9I#@&rvwn}3KP}QQ zZvQzUzQr?%`AcP_93Ur37Hf?@UQ58$(69nvy#fJ89i zp|K@1pUzVYyD14x7-!4DL;3#n>#qKrt%SKX&&;z`1*F)$(d%85y^Ee<0)s*8!5agu zB}1D6_ORog@a*~dCUWH{4Dnp|olqP&&9L>?xP+92ZnRGF2}@sW2U4r1@luK#{!EH^ zd?9@*W7jXUxLZm6PHdcuHdfL~Oxq|kRC8&D=~$~>nu>wSVwOc&u#YZNl7J4%t?lm$ zzf2CsV!hq*8L7_Tf3$VBK7-{r3WU5uwI5KIrzUTL2*#S&@5A~9l`!K2?Ro2TDAcY( zlsio+cDcB?9iDg;YP9tqB2G~?!ljg`XX9Z`e8@Q#qwSEi+L z2T{AKFJtQY;V5m#-JV~g4JnlKf7!=MJI1;6a8@v+4UsA`d(jIfmdH8*H4L=O!oGaR zKUs69lO~yEo&4xe#k{7dRUx(deB}L@`f_i&#V&oP__&*mZ|Ts=xSX8w3#R;=82Alt zB7W-(6wWcurB6L;KHE!ApaBNimX>RWz_9D@$#=z`?^`~gXC^IC~m6Y4*9>2k7)76G| z%x@7@iq_@1i!`mA{%NNpzH!x0HB%pzfsfN-b4406E;=99GeRf`Vo#&r9rS=PcK3SW z38Sp0Me~Qqx+d~T5BnTgIhL}|^fCBRC@MU0Kiw4PW;W&ejfBL=G$^c}t}+IP2=6hi zBjjBF`!>(H-?Ts9uO)oB-ReIr4WM=j`sxG5Y~P3dzZ2EJYp>ly@%Y&<<2g$FRnpK* z#a++l=pzo$30(wAlVy|B57Xb+0Iwq+Y`ew%;gbvm=6jP%sZX-f&Aie8fvzc(j znOyV-u;lOVMVjHOyE`9}B8u>i*^GevdT&J2927onlUJ_SJBA)=nPqV=3u-V5ZPuTG%8 z>Z{q;cs6A17NW|nM^8&|>;O|<{3KZ*Ej{-$1+mQGK8TwFZHc6+`a z)Y{I1P_QkATo5p1z&!FTYQE%_%nJDQi*nfv+t0~MfLoAlZn)1xo&4KxsM5wPxSz%9 zBc%R;P<6Ho#Kcz{|AtH$-z~&uR5tvQwy)kTDs{_>vH#@cS;=<~VIasCnMgH5Qw@L? z6Z{gV$uYxVW%Q7vC_(6$D!^N#r~b>rbij%B*Aah<%%iYahyQ-vASw|CA-{**(&$^D8KV0I=(pU8i_nM+U z0P-}{6S-titqt%M*g5Q$wRz}|zrJ0)n)gqrsnKo-@%dX9MC=_e$;CJx!V8Jr=I(h2 zZ+B<-qvByd5Olh=F@y^mVPjpHge0zwS!vblqlWfGvnJ107~2! z^9vk+!Q6pt`v`~!+&=&a`lcxwnAm>zPN>@YWV4}l68Mm+7Z^MxG zd(m!5@fR*cY3&pI5+M&xkPz+Lw~>2;`yp=V>U<<-Yl-^gf*AN_Cn%`}TzwN^9*@N% zTeRNC8MFSnhXusOOPOu~;9tT&;ZBe`<~f71sn~+ufJ$MTaO_>_q@$8AK$QGAz^~R7 zy{uUD{4Y#g+}I*5xJUBznh^T9hS%d`6}THxDR+SLGglZjwzyw_r(*>EVe^b5rnkRe zl8k~Y4qaH}q;R!k)m(!zrAmW*pqvN%q$?z>-bKTtVlu~-dUXbp8KKV2Q$eAw^(fPE zrpa6)9_!XkcB577s{WL~0S}v9`!W#{*h8j-2EgGHmZ|9!N7pwVtZEIk<>}H9Xj$8M z<3%ruR)~VjMj=5GwQa2M?Ec%$m*sSF0xMT$YB5`WgXrA%2UAqPtJIFZe0rpI{8gff zjS_yoV`cR0^g*2P{j0T0beqUbZ8R4ilBxA3zV@}IVD^T_0gss^do=tv@C2jMntlnp z5dGR!a}?^p@iN+}40bqEUfj9Znc}*@mF!{q#1NM>=d@;GB2*rYWm4Sk{@El{{PHov z?BgXzLh6C_qY1xCEu(JBD#WL27zGL0Cp=01*n#>)6VHuohYpb}$RXUZHT$=?< zdLgQYg5J>|@W2a)VYjXNISX^&L32WzVOAHutLk);`4#?i2)`{Ieg6r}n&$W@T7%bAMv>VJ{sravXf~s<68cC#MW8&4!-BB z_E{#jcQ4%2XGl{qd6U6j=(3?;y|dOv?%kr`58XNHvb^AL&6%5c2jxUuL)t$Jnc^#^ZmmUrHA)hh^i*Y(^z>@Z|z$Y`o_=5 z`(D-90QEr$3>=#%FjYM@vjijxT=)4*s`@X|t%64G#Di0z^z%~dHval(a;xNpN^y8X!=5FA}0U36I=l*rZB8nGE5*n%uWYcmjth;o{ z4l!gGZ*<(yR-5F3#26e*(Uq6XY@KKwojTd$s@Dg*+)0~2UKz;`MG92-2B6SC*XI1oRHRQiSLqG6>WEtXc)hsKg zN$d+egD)_>1@R!qL!aZcrrVP=J-0EDytP0~xV^@m$U?`&h6G0f14so*2kSJ4VW%m| zxe)Mn=bvYThpumnNpnKj$7nda;ZG8EA z$qo697)yxV7k%(9*T{}eg(rOz?@D?sZ(?FU&P^*t66^hXqb7St^B8wa&NG(6Z6yjX zK1teu)zK9=@h#D*Oa=c{@`X{mTTp(DL~FEqFa>+Xl&I(t41}WSC&AGW1!>LvBNq$w z)=kl7h08475dZmm{MX>E2-vSaVmQ)>lWgQLk3tHvrd6GF?GN*qpo1p=!yh+C{luMG z?%K^6Ym=|s$*S^Ifcn$ASNbj$R1ej31C4_M10!FvD>Iqq6JR$lYWow*Dg9wCJX){U zK2WgP#Yg9&nQ}B4WfHhey-w8K{vjQ-n^zL%Gm8z6SsqfUS%kU{WWmgpEPs2y_A}D$ zrY-@LoQ?7HJwCc~P3vd-eEAYIp#rB>dE3*vi)lq|u4x1Dm|C0$|NFE@C7tp%$KrY4 z+16ZEkR`MKo#I8Y8>){sJvJjyapvO`@h)|W1-|px)>jBdMNjO(Xhs|dFj8w96O_RY zVOgCqQZvUIvU#Um*wnIXspF>Yjh3%tM{ii&jP=R{a&5O zPQJU9qt1F2K_$LNF=cV&BP6`ZF;Nw&G>|#?w%hWDxS_~iSflzww4qK1?C?j;zvBBD zy?v%FeDznRub9Cnlj=~_d}BB_bQv^uuP)s=$9-OH_f_m?p)Gx^c(=5VztdaR1?< zYc41xiHtak)9Q8Up;9s*cu)wI_w`N?Bu0Q699Ly89p5dOXkn;*V0x2^H)Vlt_^w${ zKc?@h-oVH>#*p6z?EArH>M2iq10?X)x>uokUWT5YuJ0r~!Iqw;7;irZN|AvOXZ{)` zX5upx4oyw=>h`G*VVMf;+}s_m>U+5ge$L&xnlrsHV5P}eOcG*Z4-g^0EpUsn>;D~d z7gF70X8yhp#=|kF8Tk*7kQXxz=W4(8(CsRQP-BJ-&4|dvRr>P>ky5+^w-NuG8CmDX zwv{$;-s=H`^0yWE_rFGT&Ek%|@Rmv|ft<(m`ni7yhk$TDMLO3FSZ=8>m7^PwS!o)0 zZP%|eEWrEd0nk_4rDnQcL+3r4z6+%51l9+%7g=__!U!M@AaS%E*V~%X;$ZI0#ryW< zLey7ls3^AWaU-7)xnR3{lNJdX*$Q{0WiwEtSHiMB5$W&MA+H!N>0Ka!!bY~@1tF^C zPQnCXzWU}df$Nv8-yF|iqf?eBZ63^1*u%yGVS64!D2B3(FL=H>j{G~)8!Jk^sHkQf^xvp|43UU=)s_5ZCCS^}p7{(!Z>d1c-txaN_PY)Fgt>m-`$v4^ zVRlq4zPggVMt4)(rwvHpK)aO*Zq3@A29u;WJ2v=+PSv7)|&lF|PxdFc$rD4od zm9shV_@$QMFQxIW(pfMYMb)45Dqox1xHPVjJdo+-HA3ijzEDwaPg6T4pAeFQmPOJs zJ$PHlwO=}xC`n&D_`yn+ArMG=mD*fz3J$U5f#5H)|qj4G!7NUwr3TJf8Cn{w6baz`z27}I4Nb?xq4g{$;wDizWq zan}At66i27Bwt@PBbE4Yb7DV+&Tm|hQ$9xo;=$u6ZD&gBL&3-w%9kT-Al@YyfA2qx zl|*X8iM$oNC}Nq<>ENy8(d#}#w#=vSi38UPwiWmWs{D)FeTD#*D9I8_dM-fNlK91} zGm~`2k9{>65Lv2YW*^Wi*Wa!^H@+A@UYWkc8GJH~ zcR1v%DeynM@T$1kZdSO}bj{*Z%wQM(`!91fb1dPdnDdQzu4`*B@bPofsK7}3`0d^0 zpqOiLi+Abup(cB$&AKY|v!-aGG^NWdDaa7)PY???aKOPYA(k6CnCd@!|0VeAX+OeP zGSVQmRMX)@fG^x&=|Q~n^&V5yeyocSv%4!DWIPi)>nD5h9m;Ko6YIB)S(nVOG$t>B z)z_d*SJ}fXeKF)v)o(0)YYsg>FVm|0SSK9SqSP+cz5M|T6haMEN0k5^dWNh~y1@tLdrG=dnK@LVRwsK zzUW!ILS;lvy=!6um7w#4Q8sgGDybEC$}T}?U&NtTP~oD>C{)TdyFNQUIo}k_AKKb= z)vY>`3q$jb+xuD%R0F}*1&SRI=G&9{8)vrDGi5y#ZiX8&Z1I#LK!!kzbGU~YS;o&C zM&6!7!Ay2umS*8D#dWt0eaX0PM>}8E*{YT4`HzxS@%VJ|MF)StNZM(?0^<{AMLm$- zsEN8zlo+{8;Na^1it`=AN_;D}ftP>*vKt|6O7vulX22+EF%|5#W8{KX?u5TuPEYLCHFa@X$;z~iNs4>5=7%@4r>@GCYdY&He3xfYfD3#?;@i*2H z%$c_QTQ=hp)#aj8d^hdRAMB`2^!K@v4D&A{g`@X4+Hs%xKXVhI*&DuDD#<67XPyq( zcue9ZG~~|_DX@^c>H^iQaBjg%W9cd1_L74De6?2|T`sFuO7Gb3wtrU1ucx6ryCogk zSPlw}Mx^PbohKxW&Mz;LWNB{vXFrsFIM*238s1(P>z_H_KIPQ~eSye4RJOkihRf+{ z21@1UYS2x0DN5z|#ODSdZHs(d4!q5-GN7A9?0t4r@MoK-Kgni<7rC+T(Z4`wq~F6KB=pNHR=8zL)ONm zmOw+pwWUickZ6!7`+yifD&pMWHln)4hWC4yA+{n!lZOLs*TT+sW>uwb#JqoSCUg(4 zyB#z_`=5oQWd_#!8rJmaH%zyLYie}F8C1=+E1;!8M z!`>nNF;z!>=*M+x(?`B#rv&(QJ!notcaquh$p92%?_>yUU#x2QmY4g*_=rE&7x*F4 zk6l|HCh0a($Gcs398CmeQO#k(CQgK^lb=?geATH|10e|p^*1t3tV$7m)ua1D!+;M~EJ1#?FlY}4tg2Vo z4wh8e@x3Ch3gd`Es3n2>jRh?LDSmh9-@BR6%?_H5YO?$f|+G#22hmo(d><&7v zIgnOOHM8$C-BOueeO=88IMCc#-_y*lQ~gBtxW1lZ(tpH^;#<;su7p8f8$6CqPy3!% zK{Q7qkD0EufNG=TL>O&Ewp7I7UGHI|W!0C;!m2OqWfG!O{PA0}hDS#tTV2-74L*2V z`#-5AC+QF)sZb~^txMr7Lc4d~ZJGQ@RjIP`hm3Eu4>lcVpMjxa(p5e6*b{n?QnM!* zOhX_1XczD}Sb-=!Wbrif;lx$?t^!5`u=k(l02ZF1Zpu_IY}mM6l%B90Iq@X7i?K0v zK|E@`faGw@9SX}tCRCFJpt|L(o!2sGQBKO2v*ZdtEfjshRza}u2GfV20dI$_4zns9 zAwzkHe~bGl!0Z?PhdxbOY=QVmZ6jC!p!kv9GOC}mE*4L0FQHxOaUw3}!1lILo+XRBJ ze=K4Q7OITTI(Q&l>JHsHRT9b!uHln7=7eW|iaG!TaKKLBz>9%0V9elVqHCKm!tJ%v z#k%#j&bk7v-h_ydlw{O zriAI|bGR+qAjp249C-F#?1oa&TOHh{$;Rc%c3*Hv?$<$!JuMbb&BZ)(L!wP_XFcVa zamLKTjs2b_s9XSyvc7Hr?Fv1SJ&PqGj1U?Udg7}>5A=txH>|gllWttN2VUhDP-;x5 zPUb%NoWNe5J6@!>Y@{DPJRazu_OCoF6`)aBtXdiJt_jf$5bE-RQ@yfWv)Vo6Fx*!> zc{Z?Lu5Io!+XLy8rH*gqd3pc%_ImCaRxbmDAFVh>kx-gHyTp~ z&sB$s#Bst)23Ip6#n#b`+Hz=W{| zufS5S;LhXYg!vW1wE*v30_~YMSW6{G_2HxauTNL3c}A?rJ3$)w%!!mtCIN2TODW6S2E!$ko* zd`k^Zoak>%OadPHdxXvcss2H{$l~$$-;h(h8AK%$bY{FNAK(Q@j^~PUos3+HO+$~R zS9{?0Um!t2bhg+~6^z)QlQ+Y%COJOg(9z{6IZk93RQI;J-ooJWnuC6(eBui#e^U+Q zzT~YoQTJbL5U<4^JI9ivm7i_I=J%I$=jrRRlXi```d}ozy76wE?v05{F1Zc&qRKY? z4>JV>vUw%p8uWIL-0*1%;sz`YPGBRpeR9OCA2nZ5oSzT&oYJk(^*6NLfJpBREg0R` zXl9N%GGzTEZaG~XmGt1%lDoO(f+Yq|K>ja8-C%8e-?&oajwLI37lD}@t&c6|bDmIB z#YnT^*-+4uW;r_I%cA!&^9MSqQ zOWRiU6H$2~>W0?uHUdzu0DAhXup>3RDiT)=2X6YiBVR|y)y8ip33D#JrY|$Ouygkn zY~~d4Iu{?GIqV-rMa>9naD1jnB?1-N_Vf8`55D4lx)n*?%*%e&l1U} z{CrIIisb2n4kpMI!<{-IA1|J601YO(RTJh`OLc^@{6VUhTEvupOg>$q^-Q7lX(9V| zFe#X-<8i0;Y@uSQrn#B&!N1kbwffW_aQ&NR#%^4p4F?SXa`Z3onV<&s&2QS(*49!d z!19AV=pxV}XP}uT-vPg3Xgp(R-aD~jP+rDdg&)PphFgb}94(aivUqZUF&>#l3cTjs z_Qin#hSZ&sD(qlL_|xe8LVFqiUwd z%z;$2AXnR24-zFfGcEoh9Jh}W^s}6{{?mmbp7^RM$DD~x7`|;vv6A4cEcutbEwL*x zUwelf&Fg*rxFkS!g-*mZ`&B!@Ut+`Ff`jlnPvd~A--DNF!yUa8}4hHHFpMVw?t zB-p!kJQADoQ2DcXnu#+KtFmnqr_1oWFzfCPS%GW~-D95t#RL?=6GT`q7GLU?LF#$C z_V(X+FtguW%rl3IN__ zDOuBx{}yV(F=?j8F+~oCTAzNEG{k)oEiGJ3!Z2#qBTNR(_%oO>O)-IJ))KxEfZN&$ z5c@pAWWm=Z!Blaoss|P5d`}|DKVru-QbKOcP3CcX0t}Ff&urp_EDBry@yrp&Y}&m{ znWULc3AxKppmS3ACSEuKE^)`TbXqJwD*a%6{>=|0O>S>)w(27v>HM$v{i#M`$_r93 zXLxI>`o3;-=l_n=i;Qczp^T~u7t>0UKyFXz?>3hPPq&-aQck@fs7L#SBJ7a*&B)B$ z^>tJaA6+tgztu<2`wg}gWUD65`khVSP*FfR*CtX#J|%Q`hB?waFBoSl?%6ZbGjyn*rbLwYYeH839Y*-e=7= zO^Temnkd!e`B-5ldpe&2x+h78uMiS|1UcXL<19OvtNf|k^7+|RrYUGNsXgAfvyRQ&q{V;h3&gS z`0q=*z)8^JqnJpUQ$cnA*9pwNS+@A2oA{?X)VzL^`fHAqRW`ItuIQn*_5!{Z85th; zUGuFKdOQrMQ@{`Tm?ORXAgwSF5@O6fpt`N{N6zZV>P92uiPc13`Sk%I1u+`^4i7W8 zB$+cH=GUmsT*)0cuA=D>XWyxJ3F)?HPs=LV^CErm-ak{3v4?)Q#MJLFPa`k8^n{_? zK)WYG4k!;uv^@ACSl-(%9uiQDQB!YzPpKo?&^eeoO3Mws0 zem}Xose9Ru)mvjqD)kpz5Bas38Ly3F^t%OAQ&uEPcB#BYR{R%FK#^2Cb?tWKEFBH& zs%&FWJ*pA%ruZ@T!+~Gl^v|BU;UT)>JN;_;)>0IjuygLJHZccsGDN?m5jVFa_-Ha zoUeJb!0AK$f+_$OBOU9WsZOycq)Jrw3ttCQhq#z7lA0V4* z_c4SKO&D6#-&-_0=yWC- zrv5@je06|Tt=lgi_SWcVXs*mT3WB1Ahhkd|lrtPO`NDhdelpd_qikw!C0<7@{9nwE z;3`TRLKy8cP}xZOp@~joJ@7hOlvddOy`~2^z;`6E=Vi|C5`HON?NI4Zlj+XIy@#h3%9aiDP;CM4{*I zQ+te@T8PI8((rUQ-(isdq8*ok7a$f|DV9V|GsNG;`iNnUL+L{DWxj2lvOM!j@rhu< zY+ByCO$*9N-~o_)td)o+-JE7Z}$3JO=CMm5d9vuni9 z=EMaN%py~;X0b)eJ$d&t%3L%Xa^@diDMk&zl5b9qm)uUrxFtOpL6%)0P;F7m9$^l8 z(La}<2hd~5%VXo&uxUGSZa^eb_&U;JLA_ZsBTCOcI7BIMw!aA|*gN<7kvdovUo+?N zr^(av71{Wji032Ej@{KGPgHT>f6iaMSPC?`*PB9$;MdTfG#7>+dwu{c0Q2t(pET4= zU}Od10_D19^D;3;bxg}>ge#sWa=moDzg1ft71JnC$F{gp&jt&!h}=4LX&rQc2_ugC zQY2!_hy;!91UX7wM;o#6jRFPYQfli_N`Q0dP*dGNHFKXO46u01kO=)4j~2+7`zoIk zj?Sz$Qb!T{S+}oPl)tv)RPJ#*_>T8Q96|l%?q5?{_-@b#(IoE4LS?tk6B3px@mGWP zvtVtPuJMeJ&e0JGolJH~;^JpfC{la1<{SpW!U=1NNIg!QwFAKoAc zp~(w!bleb6cNCpgPuDV0ER}5q&0c`IP&l2Di$irJ!?uhCgASJn|E~HFbYj_$F#Q4- z1Qm?k@Xo<1zSB91!-H*I#~WlAc%ES?O+FHY+!jb#6cCZmP3v6qabHVC(imUd*!s7NA~hz{O~www-DU6-EKlHqMY2_ z*^K}AAO3y((`@dA#2Iwgko}dPT!Iui{$nw%n-a`k&W;Q1p&f+a%-UM zaeo93@ac>JN&`YuPHVq4J6nm2#*emR!Hu^~L352&H=(MWvx<5RD z(>usLf%dFFk*FW?hJ9ff@f0`Q^7ns8>!Bc5NG z9Q(Mk_c?@(MDfLb4dp6=Pv-|yvrtS91Ve-iV-H05Gz9ZjL~0&Wh%DN#qGwox+SyoG z%Vpk&M-_s|vi6|lfSQ|Mh~#sK1@9nu2cDV# zG%x3;&1fF)33iTkM-m285IQ3iE>}x}%YoMLj>e^{b$hP1ke3F}ndEuNTo(!@!`klN zmc6p@_`|Cdfj?pAdY!HnzKl(obO`qJt6355d^n9=d;YNQ5xff^)jB-g@_Jtye?n%0 zJEjQLbwWPqDJ$=1G6l_7Qj$*#u1ckf+E%u(-OB5!8Qs~76O9ug+;}(M30BZBub0gG zsoGYES6^C>*WY*}^5u1nK{f`x6e148T0GtGMns4`HV&w2U6SAIq;FSGk4Joi2~gJ}Ry&J;pD8_uiT>KC6-NcfKYAVb9YyRA^)W>@pfh zeZksktgbAG7A$*i36qAx)sc9}@29aqF_k<(G;Ewfc`pDurp(n!214UIJz- z?jzx2p`jRY;~kCC9ECAB2E~4_-PAja_97!9ks}s?yEG28nfi|!+YUL1QlX%}WKdKw zm0JINkd}jdTPV2fol2gjY({W=B0AUhd|N+^%qvd_Ug0~fm*H72di|uxM-GQ#1~}f^ zPRd4rhzLRT`f}74*46*A4bw43!DA4f0OfG5fLAs75TV0;^$+}$qAgkRg*Ov<5w#{V zq7Nw4@PvgAfrqHo341!{Hk}DSU^s!1h>g<0gI3g@d#zCy;Z>nwR`hbfqhx2bgoU&8 zPUdl_xq$9~!#xI5Lo1=-9iU6C=Aq}HUPGZbr*>lU4nL67JctJpU1A;67vKX0VYhv3 zg&ZD%#aWb_v&L8OAoeWdoyfq1gRFQ1LLeR^e5o&L2RNR!sIPjKJ|XXdPf4j?m|OKn z{mW(v^;{4=*4WGts#%vbcF@wYU}je9hdIB5k5C&?>fyzWw;Ud|7zYu0lJx|B1E%nT zo0^%@Jaz>84Z#3;BY`74#RMb*W?<>^GGlM|g_Uc1kKjTuP8&%b1FryDgonr#MZ?vH zL-BnZT6@3x^>5>E|NGy^`yYIwHQ9|m`S`$}yqiwDsLjA63>}KEbZT^r?->_lkLmOA z^60l$fu2h^@WqbrO8I@ZMYA$dd`-%vd}~FRtXwTeL7N{GPeV~V$M-YOB-h3A3k&2)nUqPHlz--BqWHR6Oh@zw8uArOqDe1MzTj0{=15KZf=ZvL zE8YE~4S7_)@Cmi!5v6`g`LeGZ^~=rw%40tsv8(0t4f2^6o}@2-|CcTv)8~{gx;`r0 z^RV|GOZcMn_3H8Hrg5#DNZ$$Dg|cIPeJS34>*ZKmsfk|}KYe)`&6ATj5g&yx1mVW3 zue}+syz*u&F0DCo0fuSf#se!}F>U6pvE-(DghvQhQm7yCWi#-7;;+TW^93U{Jhc!8 zAt=KTjQmVIOK2gi^lKGzUoAzk0RMSmf#lKgu`Tj>24z{LQZpajYM#W-_PuDgj?CL@ zJ77T)LKuXJwmP@)ln4(Igi=BPi2%uA)d+hee!t)AJDePmAqsh{=%=*TxU>=g1qLiQ zhIR=4@f<-(*K$6urt5}x#VWk0{X?z3pm*z?D0>i8B`#S9N(T;oR~-}-D@lnmrMk$I zGYTiAHZrd8vQ(~ z6k|#8<*krmfx9s9)0#z~FBkz%XUmnSRZ|E+a#oQuuRgyRggz@fFUpMPhVeWa%k+&k1*BN*~Ulad+G;*aFjt6y}uSGN1O5MU;cgU?`}t4 zYlm?Dj1415$g+UdVj(l3IE`gh4PO6A|2LVKd(7LsciVTu%Z%NLf#sL@`Q3N+Oq@r zqo3fEUi3SMZXff6@}D*nI+OyAtIaPsrx(Ir3$-;iDBsxsS5+tYh&AbGHTn)5pfJIc za(Ay0@4ov{Z0``-RqImM*ndA1gab1io*RzQISsh4bIzC2eGjkeu(FK8AdP6iqeA^@ zUu|Pzt+`~}ilW-Jrn~&?*IO9U@7x9>xwIKy400nBHnDg3Z{4q=b z*Wnq742bywSEBqv2?kuDK;v-eTfrpo&=!t9Iy{QKy#tN&uD!sJ5fMJM-9{1AjiW{* zwzhWkyQ6j#9b%Uds*E9uxuwMg;nS>P^`Nou@Rh(0awF&&3OneAJ&grp;9noYcND_s zGXE%Upo2^eW6T&pSD?+{7?e&ZahI0Yqg<_P-BgX6p_6zPVJy+>;7z%qHt*~G8Q}*) zB``h&-2PW_pl85tM|KYeLq>#>*W-^;U1I{>HBJ!BpPfSEXjfXR7)+oX z!XvI&Ag?BCHjNKnpoHaPEzJr)fJ4aD*A$(jFVG5m8AB8pRCNwR5Rf$M(Mlz)M-)^j zy&YC_GzTakQDkEjgO?!hz!P<4^@d<_LHI=dp%bbM*n+=ceG@{~`9S*}k1w!Bh+{%2 z;^pj6hI;oo^Dn&3+QpMwjq~?}Tl7oMUI>19Me?l0ph!msqXojx3WuS<_c~6V)q;3+ z5gMa4sy^dM2P~ruTUc0%`6b|HK2EeI_Vy3dKj9(X34MgN&Lq$If%vOa!7?F=8GptJ zP86jcxC{OZo{i;CuCoFje0ra{Cb-GydRzAr!Z(+U{)JmH41%xGXnDQ;$N%#`$4`Iu z>-hCM@5Svq_qA@t-{`8n&qf7IL+>798KzMGeAWZQ)z24XvSU2=tizRkiSo2Mo_Bnc z}6gzZ(Dc-~L~;xxS&z1fe3+ zyHMDTJ+V9u8f%RpSM-}hW25$^O@>DokDAmH>ocp?X|$(KQdvX59QHy+fam z|8Y(S3z*ZBV^7aRG~c|;%e>6Xf8a7Ve7&%I^wrO`eC(^>f1j{CU6-@Xmw0ws{E3fw zF5Kf^KZi1{Xv(9XF8umf@O+@W=&8@v*wEk4t;5fhS*;&c`zMy^o~q12=`fvrK6iLQ zy3)w09`SP;QOSN1i&b z+r}Gyq$^p_GJz_X1q)2nMzP{yN^C-noHq~nfdakc}$Phs^fI8-#MGlR4DncTE zFi_!dc5mOxujr=0uUTP0f(ZH$SVDq zwueIdv|iG<(l->57#N78Al(*9=7h#0nbvz3!2y(2ZgqL;KrTlqN#C;ijTb*K?AhM- zJv%sfXsHBI3VQctSZmQPqFzucrrZFT@piRN5A5XRz;TJS*iwY`1%@ixIfJF}PVnb& zW1GgaT3xqFWz|Y$a4X}HA4F)e7K_AkyiRxqjL-ENj8!wG8<97H_pswB)4*wr9?@io z^a=grFW&T8yXjph#EF^!@6`#xly@Zc9YaXU66~3xarEWO6uzLPH^S#9@FKbbgAA9$ z+7-M5H%S`>9!-RIIRD`QigA;al)YZtjbCA(9pHc=Z(^f<-Hs2~W9rn#!X)OYQdKmS+XAEqq)%4LO*f-PwW9S^!q>$U5ei=<&= zZ4Dl4T+m0V4z?#C+JF>-R7vKPSd{3CU=$(^YQ0voQYmj&u3QVoDa|=>c68QrD27kglHe0CN8!(YdyM^{TeG%civb1NbD{M;QE5>k zR=kZU=}}O}yxz;nP<0W(7|~nVGwn>{7NQIpV+`^bOrZUIN8w$owQYCzNc6SmxF52h zV2lXxnXw7l7)TteUw!!5>3PO_THJ`ijec_|JTd#nfBsJ_avNr0;d2BF~BX6De2z4;G*|v9*~ZasL%7Ua6JL7XOBeoS346NH3xJL=|34)TDKJC zI{bjNhm4QtCShs9V`w9FEG%aHe)eV@i!L$HZg|%xG+32*yKuH3jUy}%dcfX=tya^G z*VGjeY}rE#Tp~>~#u%cya)pXTQ#f!$eT*GXp!I?!^BbIF{BWoMADE)R&7FLlA3_|V z3wp8e3&#N8n@w=UAgan7hjC7T#!^3c0WG{?to%V_F=}h<(BFN}7#!`6q&h{hCqp{VS9s9-4e`A05cmLhq zdH25L%f99^x?AS5ps4QCXD35yD72LlXp=XVA1ZXxzdTdIS)Es(X2t2|uj?S( z7(oD`6X7ZB_Z5s@c%YI$8is}7Co1g16W@bCH6^%u9}5sD_37b}J$mvV92wa34$#3a*mV1*To+ezImwB0&dHD}o{)7x)Q|9rZ$IBIe;sXo-<=^z{CoUg+;H9eg$fm0% zDpR9AQ4hIk`pBo~$RDq`U=Rx5W(R-Z?=RPr$4@_1K0Pe{kg%N9{i$mY75G=mtiDO{8+W^b~9CeS=Krsl?AnT_jnVNT*KA z>a|l>76;FA)pT+0ibj<4r2O02d1MbBJg`=~W27|00~t?u*bwZ`OD!Cbj7zPQV&?c&% zs1=E#$nvgmQa^NH7%3L3lGoY4E3IenP)FXEq^`9A1{tEc_V#vM35t^y?P<5`*6lTo zXfO7uVo%&caoMAEkUfdiB02?SIz|dMnHL20JjNEm++mOMJ1D?IK~RpUEy-yLx3rJP zXf)CHoZwX!4AT}(vgZ)jE`9GC6l&~c<$Kk*EFACx#TDrzS5`KyfbuSuu#v`wF`P`a zUJ`twuJxxas^=2rFdpYb^9W`O7z4sySEPU=l8QPVjTkQV8-;#Qum@aHqjYYlZy5Se z+M%d3jcL>Fz4wmo@9(NDMN13r;0neEA{$VYvTq9eF{@c>L*Jv-4i2^*H;DW|q3i}4 z_0jZUZ*A8IO_{9*43nv>Sv6#MgV6Qh2>n_vCd zcDEl|MtI1+X`~c8IX<*zz2^Jdc*L1{;`;D_bAZmv6r}Qx%Puf5@N_#Opp_~`8`0ERK#Cy)o1Vg*|u_l&}~_*>ep8wi`Q9_Mi8(X731xHLk+p3ylW`K8%c{ zO@z*1+$ZX_-6XmT<5h?xfo_mSpHzpWo?|YO(rm$_0)3z#AMCf(@1mH-FbjRW^k^ft zWQYoO>>ozkfA`y8ISh$%N~g8{&*rVJwd?-=wymvJbS@soP_#@C(4iph-o@n6{$kJPLVNylY-^FXQ5=D}^u^ z>^tqY!=qFxiB=cfp%~*ADGU39k)76>8Y}o7!;6Z=qFuYTW$Wu}nwJ^} z&XZk8Fv5@(A}}wVcBRu9y_fy?0v~9!n$9=C9qOhHsBPG53cPW8L-b54ul^BP8gYI@ zlrA)dw6vtKJ=3`GY>ZTc`eg26&?mYLJqWl|5)WEkS#dZvnhn2(zQi-~K;|*f2p&RV z;ZjIRJP}JK);`eZ~umfBGPZkz1=!t(~d=-5IJ{b2&CFs#)>@%oq7_@+)vlB3o z_c~$F|4ZtE*FgiB#DOl&qOwTKhv5gK-@ti!TVp-edGv3>ZPgtdN;Edm9JQ6mI5#w5 z*c0AhtaKRbEzDP54ecbQAbiTB?lfLFf_c=M1~}+2O@n{Y52B_Pab&Qh zzl)TUAuT5DTC|bVVIns*KZJvEk9u1YPLLLOtam}9)n89(2u09*Vhlv%NY#r$ov~zJ z!h!e~2GYP^hyX^W(i3VY2E7Z>a~wQKkKC>w+VSC@)#|4%uhD3XcOG3w%G+d4auv~O zz*S=rO*(F7Mbk0Zbvs>`i!i8Oo}(+faHpGiI_A>*>={P-&yDqU(eA26 zC5I4s##lA#$9i|d^5s?aE8{%oVE@2=@{^z0Pk#1Gd+_MMe*fM>``O#Swr0Dhw!&l4 z+X-{QJ&o~9*B9iXY0-DbNlpn@plRWsUkaZ((E0g4-Sc#LrYMHSI8LZXvm{-h1buz|LSGXg0BB&6_MOzhkjPPd+~@_z?{h`j_}^? zkW)B#4;>vG_~Hd`qDH-G9WiJa6^vr6{<0wTuwo*>R0*jX7Q`&$ELOB&j(C`{_@p-> zwByC)g9I~`E!eld^=vtxqrhF*ST4-0;tt7Vv=)@yWprfp~^Cgimh` zm-x_qeqEIzz|D+SZqRyMC+ARDgmbg&EZq6@D75K2#N+)F!IcO((x}vGTBJyL{wOHS z%e>6Xy!<;ZeTmYoosSG95+z z34Gg+X|G?dH;-$2s(i49*}Fbb;lA1Nc@{P6ll1Mw-}*fM@>|mFw4Jl&ei%ADeLBns zzDTxGL79kw2Zyk;!N6LQXZyXrr<|%(Dn{xdJiReW@jh3SUXYFngV&;!iljQika6Mn zx$Z`SGL=`xODmv0aSXHauhRsjhXq>;Xdr8j4c9?K{?N9@*jHBOUujdbR4xhT2!s z8icfZ3zFO0YWIh!l|cD!8FsYP;9DEB$bZ^Fh?O3bqSsH$PDm zqKqWcE*ekkI&v_I!?=X|i{Kru=keIb2tk@5=~MrQ-PABCUVgJMtXkMr}M zvA0?`#YQ&lHytJ@^)Ys0h{SL>)EM@OB6+L~2;c+#sly!75NDV&H7J9K5XM+stJT4HUawU+P~C&M^J!*3qLu!?y3gW1Z%yt*@kpRW5Xu!DZ#yiFs@R zI{hKSgMIm8!h7b?$;pu&>_61JC*w+1>v{}bMZNw~bYQ6O?Bl~;gHPiYxJ0?oebB?M z@Mh8V53FaGV(hV#P+yZq1Zun4w0n1dZ)>Y7f_KSbSt=F1?L_c>^P69>E1MfY*BXsk zWSDT9SLhGxVFrow`tNkl|LK!ddl+g+;mV#ygMQx)F&rrUyPb|`EC&(3O+PTWH5v_T z)*GVXL|^H1dJaP%+XqZ|(I2o-dw+Ooho^nbo{7Eo+8w)j>!$i0xBdN7`^k@gWpDrd z_i7UnNKuQ4*0^p(_>XSIBZ!k2liB+ZdfjxR*v7_&70X4xM&vL&uGbsd(Q#elkI^RL zkzRv7@WQFUjJ@_US@w$xnPe~;VC)JJPQif4+;roIXavSFj9>6X@Se{V_UIFDVr-$! zq%=*F%C}e*zgo3YW!-Y+Rn66m4Kz0F`v`x7hT=eRbbRPI9vnT!j`Ps_)zwYgx_Zl_ za6OZekQPHXEDBD;Sd-^+WOS zL)F{XGYf9iCo(F~H`Q~|7b_s`Dmu7?r}raT34;kyoX}@@FS?pYJfk+`ylozdsyPk% zV!VnaqLM*G18WD?X&-5xVr<4J1{cJsgZk0`X|63@+F7rr`a>GXg-BY@=LP$$+A`MI zVDt}qBj>NvDTxe&K@A#${DMI=8Y2QZ7zl$ieK3T(yfEd%j4xP;(ah7gif=;edz#zu zLf#Q!53?oGwu-0dxzTXsG{}uaE?cM{^hIs*$SpT24KMbB;xY8+QgV-I0MTFUZ5Gor=)#D+ zM4+-7iLZ28QWR=Am42%T>i;tcb=OPUrwoiefQU~53?qR0i7}N+E z$E$-15f*p`!5hZP{$2+UcWnQ`witBq+RT&+cID5vep?ccleO~5eUgqULMETP(dii^{CF7uEXtmJc5{WTa=yN4Lb~tWQ#q+nz(@ z$G`PS`X%-D;>pSz-x z^iU{IP!2X~l8;+;SJLb)qmPft&by~@(r zys>u+G9!^k{m!xKKCqVR?&u(bq>#&5xm2`xBI<^-Uaw_4+YjvU@W2X%l1El8VBnzR zYAZ%Rysl1UV~ zQHSYl%uqhjUJN=!4n*R4tvL$DK1i2DCrR$j$9&7ir*{OZdtapqHBx3X+9|ki3A{}Bd|k>$^L67*fE|GO-H)TN=45k zFiuX53mEG>av&l&KqoG=PGBy8OJQB8FNP5fqXug)l;Oc>$R%)(ck08}K>p>aGI9e6 z9{98?oylq)nH7vN@?gBeUP|Xom*}_TwM_$o}nr{EJ6=5lxrZJiW4YRde=L zTU*=Iye&DNv*(yQp=wN0Y0dj&K^3z`1g`3<`g1uRczc&u*R8aAMeiy)Znx`uc6{(a zYsCxCaKbzopI-`>LX;cPEv3@38zaDXjMNw{Fg#+Ifi7X(W-L)QlO7NQ4s(}?OQL+( zlZz-nvVAbeCK$E)>?yV=d=;GZPVj9km}5}i*?s87wTaqsaiJLuy%5eiHt0P>I`ldX zTV7fA{RU%kqC$oD*^(6t7?Y_Nydc^OBj*f{#(MtD$AoAIqFtevD3yVGB85ScJ)lH) zwLVR!6ILo$^jvUQjVEG)bn#erMH(@UP(@$reLoIO4g?bGjY)I_K1eqbzVi{5s+!h6xIo}M3wFK`SsKZ!aT z3x~hRRdgo4U~j#C-M;y)w`^slESQ=-e7I--_M>0h?;iE-;r6ke9_~6GSF6ib6pbcI zxYcUA@d{XgLxaJfPmD8+Bb`ToL^KZVNvHBY$1=q==X(>;TyPq?11#1yHZ4;s3-_1Q z|DZoYPs0`;=x#i!Ncg-M3F-YXm=V1MZN@l*eP(>t6_4BVbd9tH9UJ`#M&%_t7j11f zkBxmL(aXSR+$lqJ58g%e>6z*!S`mCDGR>pJL<2B<^)xrpr@@ zL^6>|FgUW~bP%G$n!9Ps1Veaz}9UtmAPi^ceUG+nJfqtNeTTq{! zKDr4(4HVti4LXF(dXPwajHOIzbdWgdKo5}yQsOxa{!aBp_YxiN&M29*Z;6r-4^K-b zn~aItybw)E2o~)3c_w^lNvJ7KcIG-(H!#vk zFBtKHL(~4=w%_CXvuPYq!!at*PsV)E>)X$M_H+Ah|LyPXo%ilrr$=9KilOJ|@Kn@M z#>KM)=o7sppy0cgDQ)9lSOK874cEEFKOf)mSR)96<+6x0gdML076B0QK+a|%)fhMM+;Yz@2`CUr(nhclU{MFz>ucc)lTNBG zh%SN(%34=F_uyjeK9k;uPaIOFX~m?x(-(OtEZ6RYd9aeC^E7X<-cBNt+7mwG22J*2eI zlg^ytX$etUBvjYe?CQ;%wt4NU7$G6faf^u=5_+A;EK2*Z{ zpKFDFhTcrei=KV%a9;IXH6K;{))(@(4_5xnZJa_FdhQ;0aF89II;ZF0qt1h$y5azQ ze1v;G&=!79ug?y5J`%5Xd4qT9912f9XYclExULU>u@_FhxIB*!A6J5W^U=?IoZJxb z`RU?~4qsnT!t0*Du9MTYIQ*U}Pn!4P?F4Sr__#kh!tZcxc8(~9(d5#GXBRqM=c+$ntGmLAJYeNdCpd_K*kRc%`+gzEYe;A4ywIerrq4YuFOPVy4 zPZ(VA>?ZoDP^?&%bZTllGB1iw+D%pk_903nla@#kd9mb*@>cW6-hcPkcK_~sc6_vJ zM+e((>|rf{ViV;Y{l^f8(){$~)XI7Xay5}*i@p!gxy~P2v)Q&>uI#A>t1DNmvb}3>E_R+tv|Hx7-t8qmkk5Pj4hThd_A}UKRE?7K?hxSY<7t^{b?3t2?p*S16a`0?4 z&^kge*L#R`!w`V{T`VnIv9h6OO8z`Jw8SR+=L5BQUoh)<{X`~3Vi~O~G9E31H~PW? z(G!b?r+Y*A!d_D#WE^EMMo7VzgS8mSwoFQ5_S{^Z}h??Wu{WZ|=dbdFBdVkJwW`dnn60!bOzx7*B$75->Rx(ikx} zFr-D|IUSnI!o~faNA`Dr_kY=se*9za@8-suUAunGZrr$Sn_D-mq;aPIDUD53_mgT2 zV^18VYy_A9kJ(sUsCyv|A<l4+ zG1n6gF{jAJLaI(un3Db!1wD9JZ`R!KTrRKJ`ubH%=QJ=x18QC_U_2GBkv?*feTeiN(S$gvMg@zO=7*>6 z)EX9J1Wv3Qn`@%YL%VJ6(^|g2uXW zOt1(39_@?a4D|n!m0Wz$zWw#<_Vusdu}mr=+H&S?_q1t0e`wv2`k{6o*GWBjB7BS6 zl`HES)=N7&Ja*a)oySN7J}xgW3s=g*i-v7)?--G8eZlVV@Wc)dPX$LJ3@3v7*cy$I zb$Wg0Ehz4B`~a`AxvcLIR;ez#eq`&~4e`1a$1k?1z&XRWs7R%R+v0V?Rh%C%SYeQ5 zUpn+Nq-=%PVYGp^V*FVY4d`|2_Wpanwf(&Zj^h})(0_q<7|qbffTI{_*-wecXg9EF z!gt#ZJ=1c1Rw|S8Il36l2v3uO2`Pg~_j%!whm1dbhITA0VC=;h#$IYewFQTOkop#b zDs;G5D0#FlQEl)a=qR)k=Y(eSM5CoX>OR+(F$D~oCCVV4&AyNr+I@xyzNCyL@(F`H zQDN`_BHUt{PtjCS^G)|B0-ev~N|qGQT+p2H2+%Xqn1=d^Cc`lTy%Ka$-O{`DezgT! z%bs)yrp=ako*IR5k$DD;aC!kxh~h?mLFPba!0BKtc$4Zjq?2s>JJ2_Vu~NGvM`-fs zdG#TcSKo@FF>$BGq;wn)YoZ&w)@s*%ykc?o_9N{fduRvR08J{r? zLpC`9$cz0}$gF z-WDw85Df9;fvJR4Amn?7X$7+B3l|Y=3|6g1(@qecj_Up{Zpc&%wz_r2^YgPzp&bxz z>W?F^uuy@6sE}5sC86x}^wb(BC+^|MCgE&uiRUFL9f{;}Zx$^S^eB`}j7tnei$?Yk ztE{iuwVOBWiWVvC#g)xvTv5TIlEu7xiR$-QeLT}5ukS+Gg~d{&IDt`Xfvc7Zj4JeU z(JEqSKm3ay+SkAF4bO*-cMtEKDckf_2XNrifAFxw2PQ{!o)b(z6D~Z-z59fis$qVQ zE3y23F2kxg$7L3YdfpDq=KnP5M6QuqvtfAmwB0&dHMHO{$%#}nsJNIQp5^AP+qRy!0)EtKELv$ z+ApNI!t+B5PGsa#tLuy3|mBKxJS8U{F!nOScq9|b7-V$z+(B{2K2R8(P|lQ#1xv&h?f7`t zcD5gS)C8&3Fw~)xV;`elujP>|ufO&ct5%3qA)?P3!!w2^?4nsF41&?jujA9-v;1Imk@8}XraUvjy zyy|N>7J}kjV@O0DDUzZ|U_Pr~?>q0iGIBEPs$Yv%EU#HAzp83UTZzIDjpYpQw01iu zYNzIrUyOsN|H|a`Y|NE`-~h@q(q}QgEcMh{tp#T7rG)u{@rrBILt3aLsp*nQJx|n2 z*rSQ{9uWtmnPY8;!jQ-z6s8`DTAqx zdIGOtHMD>Gmw&eZ_TT=y@bJ{u*Vpap)vF%a1uj;q81z)JZjWsYN7h zZnYcUpK_^eE3504Ev*Z0OPU)|t?M!D#a$Oby028GD7+=|OmjhXjRcQwPvb6p%?cK& zR9@|Tf~ynZ14c@WZAHN=TUho!dPM2PM0B9(d*~1$MKoDDO{6B{t9}ZW!NAQp3KtwN zRPQBDrTQxT5R?Spk-qC5(XGj#>-)E{{-3RRxp^rPQm5q#RUh|c3Zt*;6D%-Nw?uc? zLk>e&u8_0MtqogUUbXG*U3>fIztDAz(L^S8-I;*B6kDRfL~OQ2yL)}%%Q$4a`BN*` z*9-RNKm5Agy0tD`!>NIJw`e;%NA}LUqWx#*78Mw^d>6f)XpZ%4xgz?ZdDHEY0+aM{ zUFSJ&fDzp$nsocow%xsZUp%eh(QUO_)0z#@ED>XL1voh{PQl3`=21KOT-H`stG0Dz z)7IA4tg>7U(T~C%r|IGg+=~H)Ei%x-g#EwR_lkYEE}f5g1|f~V%VjA4H7=wV#(@K8 z0h|knWUki^J>m%3556VESKu#h@DN>RZ@9%p^jFMb@f-0lQuC5Bba*z_`)Lyqw>S#~ zgF{sB^C(ZEy!722q2amujxpEM9xh^xA-WGE8BP{v>6G{yMsL+eyKxv`UM8oJSj;!@ zmK32xk1>CS-KJ0&=M&Mq7={|M?;uy;%uPx~bw5h`%=yx2)K}Zm)3m8kjk4yjXje!H z3V+kwbw$;M=px3osUwKm?{vC(s&*_0E?M!5v>OT8`eZ>oEYSXh>d){}=S|2QX^j(( zJQ%)W;$_g=sKy;UNs1=1=OlYOGF<@#kzc@S0e#v)JXxPafGsRxOh?zI{)z6K;4pKv zBisrGZH!mYG7Lu;wH(gk{TTBYhYPjOw=EIR!)T4slkq1)7-t^(g^|$;aXs)JMPi{jnV!9@|fT^0xi`KmN1*>Q}$DM~{dOYzha1u9bR` zF&;axL-*8Y%8VkpzV7ky+;9I!`EdF*yZ7n(^f&yNm(N_Fx^u(Vyv)lVp-jZ2G19DU zZnzNxBIld1O28(RdB}A!M$c~zw-)h(!5}E$4TG_Y#X5oji$^DpBET$^SP)ZRUyC3Y zVqnm!7Y4|8m_7SQ`6jPi8;$Lhv;mKHt>5f;`y$zdRj+K=^2VA+V!4q2j|L`wJ9#86>@qeD5waD-I$UePHd2u~Y!|cOe_0%2Hn?B^m zY5CyQXynBq-iCS?9@IgGU$wsT^>9ODS}qIe&x z?QOxkX@l;uEB+a8HyZkN6sCCe2j@3;=u_o*s7K<=F^o9OZ`FgcOCx}1J}H+*f?qry zB5}YOJoRxLMB%C7nZAEwX9M;Cs;P?$f?-kPTUFn4y2f*qfvT>1J3}-9(LtgC`eYwu z6mO)0!!87>MxseKNM!RRm*Yn$(^QM^p~8zb1{hmr`$`Q4ZC8S_XB6u!@Q8h>NOevM zsZEBZwXI2!>vnPu0zqZKUK7Abn-7lE2 zcvxVqiP1LV=b&HFXv&RE5w(@~gy^%LuHg`gfqB6riW;?=J1XXjDDBy6C8aS-Y3+vM z^<4Nqb_F*^CL+sX!ePj5w+Bu~T$#;&F*y36Jod=CrGlD;!dY}tYr=4i$ceCa?)Mtj z?>6lCaM%9N|MUNCzyJMj?Dn0T_QN0iz^-4v8q6>!Yga2RfhJWzX~-w}b#_v|aNcO3i12!mYF4t-j( z3zWWErvux34#lnToOFTa|(*(~#tJ+n~Z z36KEaKp?+@Kam_5vlka8!c)CJ&OSWs+ZNGyX`X1T*n^I;y1J$J6g9T&+bw!D9tp=u zr;kyOu?PQkU<7kDp$fP)>R7*dYNLVZ-C4_ef;rKKDC{wkVLYRN=aC3|17%d_g{Q3J z9YmgB(6|&_ip7H3S@Z~>Qn{#l&h7no-?#VPyDPffvq6u&@`91HCmKsSS9A=|@`*o< z!W_>DoNv6kVPAdgj#bNyf67Y5veR#LJ*Tw;PqVkNlC$euWy@!lES-vqZj0_{t?zt9 zV~GLPqXxxqNaJ{TbmXZFYqgf>s^Ha!K0sg3MH}K)Mc1Oap3C7doAIMiV6V%ft*@`x zm8}iE11ATJtc>5e8-XyeV&wAq0BsfE!Dq%0L%eUbfv!sD7=NS{^dh9SBk~xBXN)X3 zcYvQ5%7;WA_C+srFTAo`UA9yv?*=A}#zJ=2WkFYEn=JcI;8FVY~E9hDxjjinNgn3*zO1jj3Iuv$kM4v3L@LACadxiik!EMmPb$SAY}7 zduR~GFZLmeh;N0oh&V=|buuGTkTk#;?&ur)fJK2D{79_}m@D~2W672zj8mboV(DDT zjb@~jg{C2Ecv?is14KyIkJ-zz;dByX8Ij(n$NRz!BD~dS$tmnZit&)W)EcLUwzGZT zj*s@#28}CYk<41QShYB`U*oKby*bcL-!qYDSC0(VSZMqvf=i=*;B*GZ1Bbol)`I9I zymCQwF~Yu+Q=G(z8dp1r676))?04@xv|s-EJ^StN?%LbG_>H~y?nA5ByBbF#o-x=7 z6kec@=mhyxgE(lIpA+2uc>4SEzo(Dz)Z=r{9#5C&f4@w5zTS^J{-YE)+T8FpFZ1%p zD83lFu%d(x1l1)mD5ACSWP+KTjb=gzA;A$bEiqLWM8(Jv0AUbQL(o_P0`>k=#r|) z)5SY`df~;%LXY;6bGq4RSWk;-3Ze0&ax7J8Jh##>RiX&p!D}VW~4c?!aWyqBrox?_1RPa6SCv6u-IS$!`~wxMy0|L?0swb^|Sjj0KbWpO6q;&^WR1N|Opw zaKy;x5q5Dcd=g>52NupOvJi&Iq3^$iD>TF5F)#BnFZ1%JQNB3C*LOZc#21A83oi&4 z{{JOQc*2`J*Gn43c3T)6Ye{m4)H z2*B_o@L_#JldU5>g?xg85)maq@yFf4h=eD-Y0-=`6G~OT?AJmo!`~0^-lt(dg+K3p z?ygT+R158YVVRu|@BjGseG;ibcRap{dZ&GRzP#u(@ScA4@QCyr+rSX`zQGSG$58T&N#BsYf$3h;w{e~55dBAsEW zs(NDj-LUuXzGwH|zvuN{zj4corHW^J;Qe?y$K&j4l+bs*XDMpij~?2;{_Edcy?$){ zZrhd2)P>?^Z+FLj^Xp&Q;laLjTP`wlfD_f~ z>W2EnUMQ?DP##hQOfM+QP~b@(m+X(h#5efY8pZdJvbe>PIV(v{MLCC(zgR3uMlTqf z_|FU*vuKlxN!!}3BWtxt&$eg7L0jhqLk;SZ@7cmyBq>=}>jjJ3ZkA@+F4+SlT6FlN`IlUWidcl?X$aT^&A){kJM5%Uh(YHqJ#J%CO>Aa; z(haKL3n=%fo79X$PnpHqifA#8(U`q(P*755*o%&6x)242A&_+-Mj^h3luu5_I0RQ$ zg6bXg)6-AsAd+u5AVpfsyB3KNg@NHF7#7)Mi-<-HI2pA+sdX0yU{ZsDW1VhYZ6Gp) zJ)SUPCM-#Ni2~F(p}Yk@XNCP_h_C~eD817}C25{PQ!)CY&?Q=deW#)^_Qv8_U_w8L zLSSq)c?JJSl)k4NWEYc;k;3!j^uXSE=hv3cXYFtQ_HXPj|MEX;-rTWrbcH@dLR;^;#4x0}IvV$FsBvjDTE0HR zkrN}wndk-44j2eh*{arW^dXG914Zu}^jd05*ZZ+_sWr6lg*0UF9*ld7OXtFwqE)Nw zs)y8|8P$X0JY*B`etV=PdIn(5XD||wda|i`_-OmC@UkYlqpP}%aTnbJ1`ue{`8XJ9 z)j@xb^p_9szwdi;xuRM341~j;CQoAxJ!B^2wQfB*Ib(u)pGF(CL3-pb7 zYaT5v8H?}2TO7XO1#WN?-Qv4msn;!trjW{$xgGZZx>TFNDQGFY8~W@9dR=8tEyiOB zV-yik>O-${YR97I7*>c}LKc9QEii9Hci|rxSV*sUa#(=Be%NysKu6BtIksmoqm6PKef$T)^IKL_y;m;89qD?ReN0 z|LOSH;y6T9yGP_DG44Z);XybT1(^qD33s}ICO83!sILRz>OD^bS*@;Wyn(0g5snZo zh9PuG{EYXIN;O70W$~ql_aE9n{nL-^M?d+c-MzbQ2ZuGygTCOP*G~B-IHtF#edx-V zhr%Fza%Oh;Isbh2{Onpd!kJH6LY*&PX78JoC-490o{y-qTgN%irhv9KapHnvI3IJ!koPYWmeRr)( zIM0Lrsl^Ca`TaOd+UxRLc`AGd3H&;OBX=;q5<@h`DV6XT;jYe+!D049h?$RPK! zgaUnH3?u5RQmuM4SP8GOvILh((aLL8{VrKSV_VeuOetpx3B{3=7ODvhVQK}&L0(7+ z&6}5bnU{I_GLktes& zY8`qPatP(=Dng$^kNo@ekF(*&C0uo0%z4#=hb-SiYPyM7GX^fA?$2}%14z`Cm&IQT z8Ox;EpJF6AS~Tp{x@Q zosCeg1O*}uViWbjU}VLT}Nm!nHyeCj}NWg!Wpfny7uk8-~ZmWAKiCZ8d-RBHnMuNp=*2g@FDwq z)m0aj2ZuP|j68mNQqwvkrFNm@#~WU2kthmE%FOTu-T`@y0|t}xfey)~u2kpVprps6 zKAU21n21N*mz%-@9kW$EO+-BC3{rtVsXm3NKO}MMHK4 zyu9PdyiTWmu=^UTljA+DP1qL*1#V4qc|r3}a&M+6Ss6z-ly>L7mm6sUQMAV5>=l;M zHTC5(tVvjlIlRwNUJA$5X67$Se4D{FFBhoCPeo=TA5Xx%pgo2W?;D(!_4SOxE?Qob>y~6L1 z@{v`JV~qb#X5zLWxD#E45eGvNxXykwq+g6gF{mVTui!Fi+0otut7)wfk1bh2a9hNY zQg9g!ySBTx?P(X6t3&~;=oyS+I3Egjp%J2UIl(dPXG1DRl*Q3FhUB7fNbq2-fx+)$ z?Cab_A|;pz4%4Wk%S)~KMlJQ?%)bwNL@6|c8zZ#|ya5IywWp~*5s9QR)SC76*S})l z{`Pn5>b2XJDpV|2EL$p5R^3FxQ8!QoE@Mr1y<2!dYRX05_YBpT*2u%Yw}*83?0o}$ zfnKxsSp?WGs-MxKP0pJ3tDpayZEtUTI#lj!G)}Cq=ZR=a3#Y&z)~!VAG&LuQ_+&lH z-fZ1w-P$^j0i@A9(dR&|6Q9VJwU#Ri=Ps?+Yw8@)Tm_G;412TD&TtU97Fl9{thTZ3 zfRDSTB+-XM)mvA4h{R#u=W;~i#cUDy=^yriu(ukx$-!J^PdL@%&bAz9M!Li<#&oSW zbEMnPk(nj0cV~1iV*S48-b6f3up!EpXBIApc6_kyktS?45MY53m&m^}H{xL6%4n_b z`%yJWDL3*x4@p)+OTNfLtJ4}E2k0x2yr(B8HqyK<c zP3S%`6v1UAxNE+4+QNO|%^4As=tVH}2Sa@@c55z8brm8~ns>}CVa+5&DPr)zh=F5l zR&Bw^(P^)h# z9Ce9Ua!2q4x-!y~F8X{QYA&h!dKZRejD+XjCUh84(I9xE03p~g?}^$RInTt&gs3oh z1#?qG#UpK@i$o+7#f_nsd543DM}cde5*dmkHvMDYc~YQaU}0`EKlb)^Y-eX%ymFxV zKzc|bsWe7<7im#3W|5wec|}w?MmFbRv_-f>IzC7fvI9=;_2YdzIea7-AE{kE^-oU< zuJEmk2@W01GY-1i#QCTznDkT~X&KLizwEasdVGGNd9f(^)3QeGK;tYN7aeD8XfM&? zIJ#iO1@AE?VaR73*{drd{<5^B^TKy`%+^CVU3iMu_KD zRVreT62|l{m@R^>dtvEiETCHwcIx%I79DIFDWO_|3@I+~XiBEkA73y^j3>fK3=U5~ zn14iq5Da7_VFP0r3;`hu??L*BP)0v7Zk?;mVmVW0$A-=mJ7eLag)YJq{qS@Fr#0K( z-Bw=?B~bTm>*{s;+rRlQcJt;f_cn3wO1Q9IpuYjO2pW9n=k#At^>~x~9+;@#>sP~h zzox>yj28?xoDAdi_$ENjb@jl{hi}ts(>LlnsV7}<eKKGf5 zs(7}R51e@E;_dnbbv$nW(;w4*zUXo1zy2p&oed4jBYwC+MW2Bui%%nT=rec`leTQp zs>?;&++4M4rKrX8k|h&McH{cGz469veQw&u28-^ArPDF{vp@T$ed8NnvFkd&vQm^x zl(hA=s$IRhZdJ)vw1RXq$Wwvi^Il#W%B&C1^yR5>q>WF0@ojdfxIprP!t*b{g;{YJ z_+Jxo4 zw&7qTJd3GKS6p#}!y1M*p4-^GYF~Nt8~VH^xjv-5B08wkX}B`zlJtIy5y^X!(C z3K(JY9sx2Mk~XPn@BaQ>PjiT&3c=kS7XlX6y;~BEw6j9}`(e^b!)TAfvGX z_85fx_d-xsv9C&}gA#th;xUw|XgHa(muf$XJpIKWPm~Llx3Gz5m{C?C9`7;}qB0=#(2Z1P|b8!gJDClIqDWhN}5e zYb@4>DYbcIt>&TEv%axqsVw_`VMx+TG=|;gw*Bhuf3t(V`<70|Ek$}h;H7sG9ddZM zD?Ax_ddzsTq-Pmtjfr68xRc0e%_mrrs!Qik)H)q;FMi%3I9zmX&~3RVe%R}VXg7@~ zFc-YWXLV~e4qU-IQ9nEFhUQ8~_Yhsdj2dZ9p4jox{#1dyB-*-c8$OR#94Fj}=7u!h zOB=yC!9!ypKngyjxD2=lT-8Ir&U%rkt_3%S0aL+U@b$gE)V~l_7qhc&%^uxz5FEk~t1GEYMr>DV7ankh2n~jJ9}as zAMSXx2Zl7FJ=6%j8@!=RDc!=z&IB7ATfuQsqxyPUFemjIhA(&x`+%{s#4wHF2?Ium z9-%5CcQh|2q`nl4Q7(gjiuB^&9r*-~YOO{cEpSwUiZ1&qO~+C919q7jQ%-y6WiQ&`u7I1*5V0Ov+kl z6H!4L3gM;eLB^Vk-M+EM*O~5fb%_RxJ)0Oecj$Gx8~8Ny$g}h4I&>ZSMS4Rb7tyDn zAIjy#*VJna>9v!F9jG0oN@V^{CKy`#Zmo#4vZ} zI-q*}RQQL{_QK}?DH6jxR@<0g7{bNBa)pv-{&B;-P#64TONNjRRD4!EvDX$}iq4Sc z^W^x*TJ;k*nk+41Xu>d0L=TZkI3Hl}?t7#!IxlxjP{kNn-9RRIpAErh@g?E+WF-D3 z7_xWPf=7XoUXXdCdC0s_uZal4Fx~5uZWlviFvbz}2ED{M4XiWhxG+hLiu8~;81+Tl;=nwEOrZW~(8p&J*A-Gf5oEu8=RNz~JNK;J z5`L&2_G5&u23Q2c7w;5es83To_PO?KnVsYFf*C~8w zLrDlUkxrx`ggId-!+Qk}7&k28StADI%rzbuHp1`G-oCX?YT|WBRc492nAO^fRn;!i zEs!pST)G&|5ZqX>lA3~zv|%6!S}-#5QRnh`7mi7Z!MhN=5r7cT+$)p!ig{sBA*VBP zE$s=)hq!xt(D#wrOuz6jWwGyq5&|`nu;2lMM|dYC%+daV9Xxtu$B*`GBmt4|_#gi8 zFFeQl^769Yk1&bw6<`<&Mkp59s*XQm*4}vuivo)uGldWAFo;tOj;{Ir+{=gm3C~Us zU(C9I%Fi%r{>cfh>G$Jn(@*{JfBdHq#TP>H&CbNsk84NvVCRwT9Uo{x(6ciHEiIgB zJ8)u=!=efAV=t0&7&8o#q=h8<4lf@Jt)xOk_{`{&{n3aJD;5ftFBP>gDOi!uV%~D4 zyroGe69eBQIIvh}z~*IM=4D>~c;!#V@CE(;yvobf_3YgXvx^>n5?EBxcZ+!htyL0D;8?lJy zx~=n9HrH%zwW@O~;;~6jF?99nrsc&u(`nLsC2VD-VjCN49(`V}l=O6ys-GC z#}9e&KDkzbACLcd;oFm6DlcsJ>{)&4I(PV8eE0iN#}Tia59D>}dA3SZ_p5ekeU#uQR>c?u>Bbqk@d zo@GL9WZVaXrW?K(zm(wQYmsqZ?>N>PXsAB*HJ=ZBTv7I|tZdk-#*S#e!7xO_P}eM) z?MyHNc0@e+dcoHptmhE0QJ~`a&)f&b0Y@263^OP_`@%asobgl^nrtE zKvXJqg7*t3j-$f)cu}~L7Yxl>t&T0PUbScfgWr@6U9{|Q@4o%!x4*KzgB>?g_6BFV z#GJyI%UW|mYlfngN-MS$2?|W!bH;vI>SxrQ8#yOj^VF2kRSZjNl%Bmf?^v_8ZwCk4 zYQw4C86rr6($O~Y`*9QMCMIA!Mn7E9R+1Lid4pe{smgTpn01R{VCe=%BGc8u4?Y(v}D8BnovKo zuHX%deWG%Xyw9xRh-ASCM^s-Z;FRXj8PSJbz2{PMyx=rzK`_CPTPWr%lZp#JQ23JK zEGW2%ZtzvG+Bi`ETFoQTB=!Q+IB6UlhTtE2ccJunC%LH${cFSJXd46BrTKDH}>$$a+vgX&K+OE0U zB}E|Vjza_%hLL_x^y2W))8K*A=`@kxNjF%b1A!j6EaLM;|Me`WgDxemiAz)!#&PBg zQAi%Or0-6jQlwqQ`64O)v1(uW%4?!Wt4^EH_xKzZkL$F1c6`zh-8!{;vn{?vgzLm< z2{f7LB#%&vYTVQa@R)J*2u9&SaHbCFd%NA9wc0Ifw>!r685pwA4MA&z6GzD0qYHXJ zdL*L$hQe=M6JAmRFVLJ(rHmN{rhE7A+M|c}#XmEGPh5DY`7HhitzTTi@J9sdQ12WF zKQ9D3bVh2c_@^xry(C`Q>*!tmu)T!ZOQS(+#4e(EF~XuxN|H)6L)yiha4+hzA1QzX z518%|DOxlcUplWO+mPdt`huf(CSMgT-Lkdis;yKd4~n-ID$7n^*tZTofpHCZ5;YuE z+s_8#Q?*l{(@Eb?pMB~%BzHuRO9sA2*5Tp4;|B5t*vt4}Fr2_&giAOh0B;|om|z2a zkc`RulIeuVA5IjaDS{s~34{AUG@Y><2{t(6Ag_2tmGE{fo{n=3DH7wFFoSN*9^U_* z?d@(mt-`T~s9WZ7A_l!(5*@GE?(Rc9!&vhk;iG6V<3yT8#t7pp^cZ-<&vlc}2MobP z)ivrTuEWIm$krz4?w}K-_ATTqmM>NX8ypx^W^#q-75dCvzAWBMbeiC+ej=+3!(Zq}ka^*~)U8AB3H*ZJA1utLa4+AV zz31b8zo>A}^T&ssfBKl+^QT-stWTfU0sojAzUF0K{>UYs(V|z2kdy?KMG1fKBj}XW4juj?2^xBppI;P^ zoq6efEX+cibkH7{pw3hLG5z5=esKr?ILU&<@8UUb;uiwg^z-pK?)7v2%MDjEqI@}h z4}M21V9tdH^tZ0X{ezu{wtJ*;k`O1+OJgk(ng{h zqF>;Xw+AJKzG5hoh#~=j1v8=UQBQ@CE#%!0Rw`or(qdVQIfTdyArJU8j{=*Qd6}0# zQu&iGd_i-+cq*wkhX3LFXDKgu{F50^KD_wTFImTvyY=nE9(Dd23g4bT9>3S`6Yuk{ z;R<}86Ua)ekCO=$$4gp}k6l?&spjmv-+9Y!-n?o=2qhB{EymezG@{=z{YHt0H?Mf4 z7U5h+=|q$e`|{v9OOybM^N<3_tlMqa-oE6PF6j<~Ocz=jinr{e;Pg~~L!nR8`*q2m z4_|fYpMG#1hnm@Ms_=Bp+^Y|dz~PGyzPsFsEEMjT-W#sFaN#u}x9K~l9=9pHHJp6D z_>KOL|6bMeg_GVm>fj@MQl8vDle4IC_Bp$#+I7v}!2>#wSCCn`1%(kCw3G6ilte_5 zpl~5-1SJiTTqsTOfJPBbiY`3Z@!GG~PINEc?Oj*sp+G`rMbRAgpukuboVQSvqwvE^ zJDEyLKF+9~xVH-OQy=3O=TLal4mW%WK{1*l|0UumCDVrY zc+B^EB9aLMKvc5vJv%E_KFRxTISMj|xEo@#t$bfpfuS^IHAT#^YcBL%BE^ zu*hLhQrygX?7*jX)aD}X`nops$OKm)>N!%~liuCa$xHtCH1=vY`{iKV zT5!Woi2Ct#k{*2pe0X8ZNWDfKY0>~jfa?xas98a4g5|YM zE0k8PT&fBd>{pf)l!TWN>LtZwOMh7x5}Bb>UMI9g{Xyx8HEJ5Eb-4e~BN@)m`VLb8 z-Pe1-iF90^W?%D#C=_s(v{-!N{5TkPtfz5=c2}!wfE*#dyZ z2;atMj*}r()-+;3$7I~Glha*&pI9=Zenm?9juBO>qcMhyGk>@5jiq_X9yfNuo;guh z#+K9uK0R%i#`5TJ&yJ4|yuTRZFy>-J2OcPep%;Z>$r4$j<=E#=^IZ3#fEBPbr`U&W zAUF`ouqb|#();7Su1A3zqPb{0@C0|X)*q36mz27q19}hi9(>jxRXK9SHb%X?=60sI zp|$<0-e=a;9BQ{}*69(AL1dEXrJjulcTl#Qo?TG=j0=%%M3;10r`Bm6S+8C5He!HZ zie+^Vc!a?WS}T64maqpn#(wCTU19_!qLZvN30H*2w6-KG3u|urSS%H^cE4_4|N2+# z=JhR4dAhrEtX2t%Q<_gOpa0;S_S!4gZMjNxcEYlmxacw|OvUG8i=xjl;d@-Pm537zOgI@w z{d^+6#FpEZRzHaHiKE96{(>`ZC=tJ*?eJXqYD~NYeFoPszLVaKNGy!itjjT~GVjoj zxZXy10jB(d;cxEQK#E& zX{>`02q%S+=pQ;AQjS93u<^jpxd%Rgv4+Sl49W0@3-L=}nM@ar{rS!(?CIFE1<@pr z9#y}HM)Ops&;;>_z<&i_WQQs4V_2ho%he5AUAt;A(OII>dcC&eB6Pu1@2OAVA^JL; zG(4qcjmW-Us7p6{M3Hc2D3}}_?D-ta`IaZp=!D3jXuRek#$V{y>FJ5)isl(|NsOpV z9G6KSns+*YVF^)ZrVm^a&wxL&pD6U0XjmK(pbPYkXe=U7;eGBz(AHQ<4niNesQde! zy3=OT+Aa#0+pS~Ue)z6ve0i)J z9r^}13f70X2QeM=y&vL*Q=7z6%nU_CunTV-G zlX2f1JCzPh#217TZXu`;V^6msT7+9g2ku`ufsi#5Xh5vX8-2uzSz`h&3y;feyYLLi1=BH+7M z$#l`%@AM>ew>_od!J{4P9G^;K8V{jG0%UUA;0G+USvcI`2kS3059`C*h7~Jnf7GaBsW5v*|3+VufPCN|mBVfU%$)4}~xD zGB5KoFJEl=;tXHk`|kfSCD<>0K#RZV0{;l*v%fvm@Y(A5Kpihxo!|bXQy)89Mu65tV?kvQn++Sh0MrXfer?zy$dUIhlwj3}cO2&5fDJvdF^7 zrYM1k&Z1?cAF9=BE{mg(!YkTkV8IWg7asX|I=dn+!Ct&^S5`%IV4y(eLoRd08%}EK zq@SaYssn}ikz~Q+qeFi`ayK62DAGf^IgQErnf>lpKek5?-gnP_Way1eA{1`<{U|aS zcNA18F4?>uWg|zqT=u9HJj*fC0$U7Oy>82mF?i}DXGYQV3Z`Sy5Mk&@kv2(d1>e(Y zVB6dGh2v-5H`;KZd2w*CqxUjKv-hWh5WPO@02TCTKg3z4ul5;AZ+ilIzntMA|l zQBhzrky`Ad7KyU?eu!)UwmAMB?Qi>@VT}Fp$*GY(9^7Dk1iVO3g))cM6eS`@V?{KU#xxQa+}tR2Zlgg@w1s_PLR1lJBGPv;u0D@ZLXX*h zg|!9IAv&izkmvc1;RxqH_Fh6Es9x&edFF!d_1_fM2!e>(MT9{x0&&0Q4=@(3%4RYF z2UTw&pSSDRuUWaeE?mXAQF!O$#hPV7umu0u({47tdZ*7vs)RP^yXKSzK&NRx{X$Wz zb!e3RdWah7YHUR(Ny{ZTl48r#MC$&K6@)#Kv}RPL?1{A)xwPf#s&ID24S2kh`52F< z++fBkiYO?L@Dq)N4ztz)PHqqa01gv=Gv_A89!qid^jaj^i)$EgM!r6cq8wjJ>zdZ8 zqWwfUMuhjt%(Cy56JxU{^$Wgmu=mJ~>eXu5ip7fHOe6{E2k8&Ew;=pTI)2S~7VBjU zLhM0^(bkPcT2EsHz~GAGDVbJK($bcNh1nQ`E3E%O4|E5Yj-NPga4&1Rrs&*(*7+FG zJq==FYA7ciCQ)wccUHKJVqGYvK9jN)+=%Nt%6k1Lbz=%AfFkpicQ7t3y_7>_SJIyI^~7KNXT1CeYYk|m=xKjYQc_qbq|^OVB${o(yb zcK7|e!uxqYy^|MX|}U;p;6?FT>jw!QKCZM%JQ(<8LL_06~J zTi^Psed`-<+IRK&%AM=Np`0bf>xp*3U_{D69~RXJ{Q)mr7o&0GH)HPx9N`#-8|W1G zazG<-TE+lF){@aPJWO|*sdl|(GgwwvI*8^J^uFqZKS>SBERnt#1s*VuQ7 z{j~=AWa|d_HHILM1``dZzeIJR%fKl_v(gP_?3sA)?t9j1)*SAGK9Nc1ZfL|vqmw>f zQPGXXSjr~Df%y8d?mrEN8^IIUkfJxFC{;U1pQ&prFr9Nx?z&8xIp5aPQwi|W(=}+Ib zzx%)b|MuSd_k`2pKY}$8t+dgNUix&Sv*?n~eJ3nDP5mnHG;cY_lM?O=b2~iu^zp%S z;h7H}q418+UP7Bbefg}VQ%=EmwEXk7Z@K4-g1>RCrO)#-mvhc;JM+#z61dT z5ofLtN&SPFaE_e)Fg^rgJb$2|kWLI9oM%CVaD-4X(RU1HESeBH5juM9o}Iekt7+$F z!DB9#lYq6cZtFT&7;%n;r3(tYM@$>fG7k^e`$=Osi;{wQurQ__w3n{1=M)Plh^c$5 zsX`Xx2<5bsx?q?rd|;v;CXZmCIuY(rJjC^RHaN4>qa!=sJFuheJ?kEwh(}*Yuq)cN z>o@F;ue@o0`B#4>q4rxIW{!uTFLLzWV5AC45ehI23Yb~pI)ZDs=2!H`f9pB_>5MO& zRq z;DON#SWcIdQwFWK=mn$#;Vcnc^x2JkD%3;m+&k;M3(LY41P~02Tn`ak;01N@EMp+y zRpSs0kU?y<%=j^nBnVt-}%n}5h&xQJN{5*W{~*c z@p1(=^r6qaM0L*3KBw|&>SA#kj@iG!SHm&ox>W0jemVce8$T);jHs)Tr#AZbH{Y@w z*Ea3S)|%b8dBv_?TeIsouG+@Ns*$$v(%5XiWe0nEwzK`vNJWKmwO&Kn{>bj$eczRq z$V8+gL%HCd`{I?pw-Fnpi|1lkxLkA3(motM0X?1WtK_&m4zGrFd`Bx(dW=pGdR<#Nit_r0&#U;M@Q?6uc! z8&ThbVTf2GyMRMc@24gH-+8{yA}TEC2a0W~(>dP9JDwg7|E8N~zqrc3r$sR25HI0j z)#K(Ked1sf>I_9sKJGuy=-ouja1XHKMzsM)so2tmEmzXET+X^;)A!anCo<;3`op1} z)S52SZf$PZ^=sFReV$N03i6U|`o>-}7&+O$0&jEPnaiQ@E9t(35ov=mj5e_`KKsnp z>or%{vUxn4^8;T}TcNyngAxV+N*Dw^8pf0kB6DFhMdoKuD*6^u>48f_8%;2zH0E&t3b)+y7?w?!K$~Caz$rR;sqLvZlTRs|71pmL)fr-2m9`V7v-Z zB&1ZNjkJL@U1Pxj1z5XLQ&WQx#-kyJ9m(TOZxgaT#v3!>fU{ddb;R_JRm%}slFC_A zb&%E$FMJfmqviqbx3 zkyuXmI0!ASb~A5?L^(Nrr0OPCDlhB(MAWGM=^j>#*t-_a)s72qKT1H4q)>aJ@to?) z=z22Tj|X`qZTVcvJ>-A&+uvEOQMcvlvL&=O!m#J5@g#ra{m)n@lNsSeFm|Ab1W)os z(lk{pq|akbMKlevw#H5MW0VW$QWi_lFFfVdP{C@EC_#*hiyCL)kf()LojBNmFYRvA zdZI%p`5YHe<}p7| z4!E7Et(p^O>_awm174v}vZUG=Ph#xB@Qu@|_<-mN#*&!YM)Vjwh$tUmL-vgx(N{Xp znhPT&Ygjj?3)nUPslZ3#U`y!;)Z_%oNndjPszAqXUf(TL-YFW{s$^ z5j{b%?MCDrI9nF}idJGgjT421(OzRM8ca0l!h+~mBB61@336S>nq>=RizM>X_JBu% zn}7yv79yITG4)?G$oC@Dr+Jiy>T>)%4#KP|NH;`zuEu#|NL8f_0?;(yqvSu)uLV7TD7ZJNH<)xVj*Ld68mbQ zP!EyaIJ&t00lLiC!>@FJKj2AgyyCx%iL{_ETrQ&v*e>{vew`FI~5w zdoc17=^l4o55^OI&x~|A;eI;ILCH0vF~(TU7(EX^8hF2hQH;4j|EZ7uo$FpAVYx;` zHF#XF!#j4xhX+oRc(y<23nh`K8sa4(!_b1}7c_f8^oPBu-hKBMc65B;(QXOxB<4E& zi~5PqiitkQ5;!`9y&5kk=sM1=-Ky)|9XG;Z%w3FRG{Y{e)j08XW}j7{lG)(!Y*fn2{Q{t%o)g7Fys&Ax(5qU$ly9M|6oS4kBLt^%jA=6t6^ zbSHa)1$`a5ry(%aTqjLwSM=xT=+IMF23garDY@p|cYp7D`xEs=`a#B+RHy7Ah;s~c z$LW)B59ew2SA(_(Bj<V*Kc1Kf584*kP%eKZ)jGZJ$PL)=8;ivu^~13vWBW(;t& z9lUgBlQ^_ja2&L(ulEl<`W)DZ&IvhW$cf3otj_kUEG)%C|d zKF=~Ye9gIOKP=q=|{(l$-f|Dk@@Ashp7=1j-OSfSlf+@f?AP6qxBY5bydjTT) z@tB_FS`g6mj2I=Jjw}{1cEA+4jxnp%YFq7ylm&QL;@Nd!#g&S!Y;8%XExP~)v%(PN z!U|p_=Xkqbc-weCUXJ{B1&rEB{V;O`G9rl(_V82*UQfJRg0}<+?#Ba$#T#BcM4x#i z8MW}KHj<7J_z;cOJgV8=!)-e`II=;zYbi0lYuB&aTVMT#ee;{&vTuItTlTfDf5SG{ zH{44GJ_g-HsBp%lwk;s-srX-i7lmuQ)4w|W_;iCAr?|uyeY%&pp7RTo>AkL8(tnSn z(gVIn#;i_0Bou{vf}j(=&VK7dL&wm1S^+IG5Qyty@cYMmb|isogn>%1xb!g%DOzCA z?$M%8;EFqcs3!jD|&zSP8%&v+Ti+}lb@oVz`vpCLWQg-{!bt{#!Mhc@FH#hCh zt!tJ}#VwJHS}M&(;%wT#Z$PNz<4DWPO3po!I??#CLzeTW3(B5bw>IoM-+9aK+_`D&1(itRG(<}6 zp|KYPvOzAFwqhagiaX>$6qU$VywaQCe}Fl%&(zrE|3dMFEdQoAPg}zeFaGWE&rlDI zfEJSASfV(m$_Fa0@WdFZG@516vzad+p8@yRx}#)oRJAm6AJ35wSw{0rp;6 zUar`iZ@gj~8|$vvL~g~{)vO=;o)wQC-n9VxKm@;?oktq?uB}P7+*rTrMiLa0GdY%Y zcKiE#c6xFmTuR!;=9cewOF!^pCfyeXNuoSZz#*p>3b*rwdxUwgi&Zun#;d$1Q ziL~$>g>HyO!)u)WG$eDfe-)nS$g-sFV(rlGwAG)U9USgktKBf7I`H%lX`WDIqwI_7 z9Z8ENFgWGZKD{HkU>VJ^d_E{4eIE`ywn;A-0UkViX2ag8WY~da)X%)eNno&(lS4Z> z+BZ@+F;6@ik9C22?=#NgaS{eIVu zHD(|asr!iZ3XyZDNSI4tn$|h-oZxw4@4ox4-gl|_a>GcY?h0eoP5Qxu!(Hoi+g2=* z@~-U0If=+FLjxaI2C6#n!0Q&isv$bZLWOpL%HXdUyD>r>d0b_+w92AGtXq$Ol+ zK?V~VHynJN) zEek*Lg58oUPr2VC3uu=c1Zf*-vTz2i+i1|%`W6EiZ3RXcb$}Q5vmQd(sb?HlI7fQ5 zrk!fNc6QdbxCY)MF9b^;vq;kC6_LI~0TanUBnfFUQ5F*+1MgtXOMA}Lc5sI4D24mo zo~Qi7NQH5ZG=#x$#QhX#J+N0>&WD04P8}J|Pw}lqa78`UdF~^^4qh-3{l@SM?^^P- zh8QJL24g@552+iR)cilkAT*;_3vQT=CCaXl2d3eCxS#9cb9P>5bP5{n&ZGVVn1ah8 zs&c`j`*2Jch*owqXGjwpcpm9jzw*W#qNy96lD6Gy`&x7MCf*R}iPMD<>XX z5PimZ0zC$XgGRIA?cyBt`$EqViPdd&yx-Xj5n&mhryLld3I)-4)j5+bBASQZC-6q! z!Mn*M=xm4{BGq0t2Y*R=-)I+egudfA&0LMeFiNu5I{U(rhOjF-K+4~dAbO#D)L%FB z<@D~H)2U0n3%^=$yw&MS{^_~lYM_3(enEqYo@k`&7$wjN^+oGXYvMuTL(q3%yScGp zw{PF_z31V7`}@0g_q})3ZyX80ZydbQg`IhH?#}Lg@zRNp5i|sPPikD~m#5cF* ztRdKVB%NT-KBCZA_&oJ7m*IItXfEm<3BihY#Zo!vx$prDf;A*qrZ^_u%bDbiN9g>lF zPSaImme3r*AtvH-_x|Cb{q$$QvfupnJtq{dAJYMCU+{enMVB-}KlbV38jRm@L}SJM z2p+-f7>}@!B8FyQBxBD6o(ZAz0iQh85e*WzaIZH6f5Flh2I{^GCK8krN!29?Ah=F- zH1jeq^D-}gsPcswzW(g97`~v#)32XTd5PL|>yx{m`SF>`2YU1w>wR3`OV$&3Yj_Nv z?F@-eFSE)*?eIQV%<7YWL@G{k8RVTV7f9jkQsDSM?q5cJ@MI4;RueqkJcwVI-Q;eI=WS*T3`b zU3>fIzqaw@!j4=)sib2`~8lsu9WP}H(%5FtGe&Z*d#xQRLB=%v@TDC zKG9K^btI&q93|3>s0^eV6ap0FJ`@^@ixb=2sMwodxotPEZP>MIYxdTguiKTaO(V4r zm3j2i-i{j`&Luw?_ilLcd5qV|?eQ%flVjT48@=h3& zS@Ch44x8(b_|zTY)Xd<8azbaP!kfRrKY3nY04RP3%UU8(xN>1-!SdBtuBm^^Zrsf0 ziNeZSL7%yN(n|T1tqI0AuC3ektDA0A!a->;XsiFHc6hLD@4fqb`^|5DV|zQh>T|+w zOU5L18DnrZB1)y}aA-@8M%G4Ay|s1KmY3IE0fpB(3PO5~0tp2a${G}_L28`1oJB`a znqd@jSq?`wbpu(J{ga4RVb85}I%jc|V@px>8;|j!+JX{@{l1763Xwr&^%r>!*x+rx zer3Z7rJ^gPO2X4rDkoe|yVrI>{lSwQ?|s$)rzc0ASpoUCSXj2o@)awxPgW{#z24C7 z-MeRZ@BUu>>RARQspbsuM`s`KK>az#VG4r+V?q?zlI3(S>E2MJ&axVK>O}Ogx@|nH zTd!O9wiK&Z)t9QVpUI%t^=K;;k<^2t(Y@RSFE=8AI00dV^FaysSfQ?eDD*HaqCj;+ zhM~-i=pK}h7zF}+BTETi7h%+}1r)LaeX1{B`N;0R`z!nPuYPWc#FAaTdPU=@evE_i zuGy+vt;Rkq6X97=bf zS~CkNF`kh=`1(OI|I}4D8{?-aHtnpx;T&T~YMHd~PDHsVw zPXyz$LCgE%sR}VFJAMh@)z5YZ!!iz!to79*!5!WLKf`%(aSGdD45cu?=)16CG*$G2 z3C>c$m66a>{XgqzO${vqXL+6*`Z@xTyAcLbb(&;hpg~3XeWv2#0S|KYf6Y-~cf*mf);XDVN<4hRg!YkrmL_c=V0>hQT3| z)sewS7Ytssg*JGKIz2~PQg|e3H>m@sidMU8oh}A2_V()eK4C*ocpMxL!I@-8-!D>h(v9kl%jnaFb}G8r5nhpMkd%b*zi3o4QMsz$71dktc2XzC zEN~BLWhlAi&Yf3n^U5`sdE;@xUU-C#5JP8Gd?=$nk!lhB8?tX)at5*yGArqG!Bs@p zq39rvH8|kl`0uGy<5AZ|5|vBam>=+Qrv;*+o?S{bg!xAVoA1pgJX^p3CXnGk0qnr7 z-~aCS_TT^EpX}|oe`UwVr-DeRQ#-^1@G*FNfaQTeEAe+uREY&)E3Zupv)dHFIF&FdvG;!LsN-aelD8$!+kSb`4` zTinBMgszc@JD(USoTyO+*YzhDUr_V}B?lh69(5&#iZR1Ie=u%{Sd(+P+iFQjsM(;y zrlF*?F zKi%gZUx)$7(SED`@k532;J1JGL;w5>@71R>$)KPL0;oRq$J?VeU+Ox>!w~ItXsv!* zI3R&XFJh6;IC|c8Z+v(!?FOE}je1vkU1~&GB5M;hbey&hOfW{!rw2f zOkd|b=yQIxSNC~$=Oyc#-Tw4r@G~(eorA%0Wp*{l81PumaUY7Li;FX>RMYm>TX$@2 z9dBUqyG8gpau#WaSa4%VAo5uK?=aWRC!Upik>u7D9MJZs07JDKuJbo{bZyT~6ch-?M-EP93@pry!4z z@+0&$yl5%NV-5(lL4q2x4aN?PKUc4=SRs#M2*)tw%mpL8CGFqXSQfnL3n}R^IGHPj z+nt8hPWEkY_n|#_@X&U*cfGF|Ij>#4=8^B+9?H798#RLG_o6GhR#(@oSgPn9X|+9K zc!;A|MsWyE`M#`+QExK_FOLQrhDfHgWGS*3;IM?ujy#8w2qkGSE(RkQpU8Bym1qVG zU+Hwgvbmy1wYU;Fin38~5k3^OrXZ>dbz|~L*1}Iv=)u6;@ue`P^{LhB^-Z`<8lRZ~TW>Lh&E9!^(y?|1Xam8s1gU^NE zL$n0zBzF?jxyiWa#w7MvLJ5jd3zQ&AudDGyzDF4x6xkR+fFmCIxv;MneIK)bnPh8Y zzmvLe_>UZnqOIRKwSWAFf3TnZ^hcVDG0lgf%fdvV`Ti{$KacDXJ#b?Q3Q?UuIXTjt zJr=BvG=KNi&ao@ZJ*}M(ILOywtwO}x<+!V7HK9m3r9Npwdt?rVchY%YUi5X~q$t_` ztmpkIl|@rB%c_(8cQpDbRMEGGNx&L}Nr$Wc6G0V%!#uZ|VF{upVe$j@4hrg|#ou5DvJZ zMr(1w1lW_3Fc`xapN7?sckFQQo;5VaL}PTdo+b+m1_s~rEn9G!|X-(#Ye?2~z4 zV;S>Eomq-RQnF>m12@DU;fvq>&e!Y*fA%f=v+sRd{P7jLac$M!eEo*=w42wj=$Q*^ zHyffaE!8=4!yXxKi0~axcqh?IqLHGvM4A9!*1>N0QUgOK8*rXTTHOyG=)Ch8{XjoM zWC@W&JjYmbz^^bM5&=wf595FihG!BQt64g_T!D1C1$RW?oaOw<_8p6O; zDC9)Hh!mo7K}Y=nCd?_|0CpjBu*VqtK+;c)X2Su|Ptd_LYqh#|dfKqly7;G#R;wdg z4PJ@w2+rtdcs~be8TsVeNW8W0d@vm7l7z4>%bZ`3eh{N!T=RwfAc>rc+0OQk{r1Xb6Ri=B zXnx>Ggp62SUiBzeQp8TwhO>UxB7$j{7eE_?(}({NPHFCR+6`|HJOdeHbzS(da>Wft zPPK)TiA=%gD0_6Bik}`I?TeR-UPzvBM{dzJG8PbRmDJp-F0UBroiV~Q+L}_Eg*z}uJpY!41!! z`z*(k@`AR!WO=^Mr{D8sKb|iyy64jzbHmrX%*&Uhh{s`0$cU&HOJeR>38Wr!j5ijc z_YxMJz=j0@2Lg2*A}&D%Atgj~xj9DlVa#EHfYJcgBBms!?2B#H8HhfM{E>~O#wr$w zgN_)ugt*e$ij`N$jUN`_h+}RT(ladZ5vn{)TlKKm!}Fyp=I^2Vy4TwyVS?-22UBuG zi`qxqQ5+$N&~e&C-w^y*EKxTC34(Y`jOnaDw1b^JYo6Au-|UKU#qIUiU$_5>y}Z8t z9jlZpS|CU`mVn9v(nIoDNOGvHz>M}dko6fz>P(qJR1@tX@`+w@CH$FvhG)Vem499j zA8IBaUZeiI(TOk9bNstKDS_WURrK>kZ*Z6K}mLr?<)JyPAlxBETqtIgG_lS5X zat~2mv?ipK39<)#7-Nek zH?1IflRZ1xHv^^j_M`h&Z?M0`z&er#@y@;T$}6_Dbwzz5Vk%{+M8w!IpL9{RM#r{y zj@-KzIRLrC3-XML+Q8a@mAsGNexfu8f=R z@n>~EGOETBMQFcuI-$B1^ zwUZN{tIR9bI2799DV@|G(t&x3MK@vqBNXlw$=-PM3&t3z1qfG|w>uq;XHH{As=1E6 z{q|4oy?1}Bdf4kWqrRb_4NAE}q3jAmqB=X>o;4fIsnS~gQhR&dwkt?8nSw2^U9o7Y ztTkTAB6^?CjYYNBBcar17FwV)j%oVR6@2Qo6Km8CJOYAD7|;q$3$;yhx7x=#LVxtU z)=;rai!W(SFpYEzQE}??C5n6Iitf`pg+_ucYXhwVg`><^6tThRA?TcGTv{ki#}*R~ zEUK-*k4QI+h^+6xxlFd~1}gTBfeyLRKy)yyiPVpAPxYMmSR^oR39tPf>MsT@#u@_z zMro~Lofff=BJlDQU8;{R*uq#S*wnnkNF|y#ozGRR0hz}{yD;C_7YMwejUlpyxu*50 z@bKc2C>+gO)`@O_)0*e3W1UXh=Ls-j4=fA|z8BBvOk{d>-l^wUZOTQFwXQ zhh`kw&ck~?H<;VWSi++^u3o)q>l@cBE1U-AjGwRLH1EJS`b1>L(ZP-z+kp{yMZ__* zAVlWTchZ#spOHrwGVb8pVw6ZW#*6l#WY&6akw~7Q8x&Y0dfI*A6Z7o!q4=^Mjt#J9_=THATmJ;-9qD_p4Gbhz?=D$FTm_f&N6- zD8K@GO-lp64iP@|oiSk_NazgfTyO;1MLm2!Il)QhSU3e924~Zhcm%Qm#)gvkJBBZJ zI!L8`oWp!U2Y^$Hc&z#jj?ms#OZcuaKsSUT%J(QzTYUdO*RO<8!gxS5mPcp__xXg! zGf$Wo&=U9)ju1HI5T%SkqEIYYsZ`W_!1ymYLikHNfHwt0Fb*de##UFWE(^f_kb6Q3 z-$k{Hw0(hY_#Rw6(OuEOc1v@sOH?%cfN>Tdl*|PUA^HZ#p)^ht>JRk*e`ppFL(G3< z9a0mL77<=U+i=dnpo8NC(O%#O&oTd@gN!?RBJi7WVxMvhS+p6L}$lEJhz9Q*maU(CEwZ0uOoPP^rdi%x#5`vG@pqwCv(msdu1}m1phFq;2b>b(rGl&e;8ZYJCMj| zqPQ@IGZ&$|(G<~mQ5$q?p6;>JCgN+FvQ-6RaGO+tf0=+Y$_w!C1A;1@K0M?dLUl(Hq!R1`_AGr>TC^cvlxUsXnXTSKxFYQ;q{tiX~`rGG&o@(PcXmIKChX-$d|yIe-uFPG>R|&pLS1=r~b|E4WE4Z z91j1OzG3#x=}Vse{Yj2L3$tKu_?nk_`I3~0m}gv!FHcB1N|UGrb}@)EF-td& zOea6W7T*y{5RkZrpy{FGVkS^dlm-Yev($CENsJCJQJ6R$dJ?j9&J|TUSVW&mFhRhG zB%)SWUbeE1jF^q8b%y4`v)%&(MQKB-6+RJIAl5Kg>SBXa76vT-5fo_)ObRCEjL?O{ zkuL`M?scjy^vRV@=Mp}}0CmwKTBy}ePVL_B-?OC)yk0IOxTQSO>pS21uC1)BNU#X) zAk8Dp$~_H%huT1Wd{^aOKVk%hej_ZA76Y$M@4#b5!&jaU$INJkf<U7UJ;UxD3VTbogXwavc<@K|-Lp09*6YK}4cF%x5FY_`l^YZzWFU;`uy)T2|>jgB_ zdG||{kG=aP>wCU@o@5>#=ASQ7X?W(@2LjL6IaLJDVjr)oS6A)!oh_?WSj3Zd4y6Qp z8?i9PdmF{c(4$b;!zL(lgFz~j%emr%^g%>AyOWMMBvH=rVj`=kgZ*51Em21(0N4YA z`%tDJYY{QQ{YlAtt7|K^y1L?uBUd=-UlQdMp4x@{l;4y32c?nvF&ViciIj8bGB8Fh zMI@gsoLerRwr_pwP5a)TeM5b`W}8>mtX#^ey(q_tF1fJVx31Y+Z@%VU;4{Sp%H~e{ z)E?Y_*ZPC5CB(zopq}(LYpd(FELji_@yRr`A8o)u_TKvsZD;#P?~b_A%!LtkEXW*y zeJY~_$;r?Am_9p9{*0IDfb*Q+HoIBX#U)damhctz>&Ep>wJ+g&koE?^3Z{NJ4wihi1Y*1KFaP$dIJ1AE0x<>hdB9UhqD-1Olzc6yLpGB+La@h(=4%r69 zBOb@d)h^>MMl6-cxG^J<%(+4eTv^h+u_)<=h@K-&712sTK1FVK?|x*xF$%n0-$#sS z2v_t9zu40wrg}+7$R0hel)}kP?RSrO;SdHal;bgs1}MqZ50~#QQCQKhRF{Q=C086GD^7+zJ2~06gZ*8- zBkcK$!4sp;_3N+L)oXVwmLvrv#*vidaLJOF7!A~B;Z&#F5Z+*@xD-q}c6_{Vr>FZq zE_i`^iYU?|#mM*&l;;OJjPCavdI1^LAuYbzjNA@Q(fme1dN~oz>DH{<>)3)| zmCdma5qqVe@J3P2oDvWgNKYR2K++(q?HHIac%WLn8l9jt|_Skd$%- z(TbGdoy#vep4DMII3!`OW8N9=W~t}t5LxyWRWpF9}H_4{(%iV3TH+5r7NPr5e%_j zC&ppu2A>#(I8Relx8^}CmKE&?5hp};p9>)#Z=!A z*1R|qqcgzRIUEgC5Bd}g!}_lST>{E-bP4b#;DW)5l&&~;Vr*hxL++huyl~3ky+l+& zpLez&x={&(G|_%U zC6k6Z!NELVv_d{>o13e)wpR6bVCW+y9rrQUD&>+p>r|I3o_&Xuzjm?UM!R~W;l@Dr zllO6QIR>7Lz6yg~++mAz3DIcmk?H%0O@uS*Yp>IB$AOM`0QlXgjSF(-PMN*C3Sl;FeolHRcAQMqH$LgYet zF?-~tQw4YaNP46ZZaF zSP-6Qeun)3;ZK1Ua69@y=-KfhdmQ2nQ<3~y5{9Eo8u=C`7|ehfMp(vTd3jav%~_*) zYE8A5IhD`?RL;NZ~SeebUC;q~iZ|JL^Q z4z1Q`TdRYUn)=}SLCJT*CEtfma|Spuzk|`5c@*?!p#&Njbb7NhoYPG5-+>O+}AoR|-rUYOA1rlGZATas6+;9UNVQM^ww-Ae@i#owBXu3+PC)~-3w_B5s$^VQEJde zlo0O8r}hW0blQyIuRb9psaAw|-T|%zoKf9^pQpXlv%Hu35H9II`;lPOVw`9X(St6G z>mHBj^KnKIA=s%d_lyG%^?p|Z2`}hx$StmCBuJAw=t2uMa(GMLnwNQ*mwEZT%Abhg z%c=b*I6l5W$3JcHCqKjUUu1EP`6-(E1d2~!3a_7ivH;)OTD5O{<2Ac|bIS^aY~W#f z7rc^xD7sKS;I)n?^vUtD%S;(kRr$URSy!N=7{aR=nFhrMMglz1F-9ONjfP==3gj*# z!iW?@NlaQJ6hfprLJ`5jf8)xQ*U6qHD5g-Bp>T-!-UUhLp|134H=Mtcx{%H1G18Pu zIlFWFx*NEbm#cR3<~5J-T3IQp9`%TRiASd-C$V?fl`ETe?b?>=Sa!pgF1vz`y<-~n zV}Dmd@?XA)vVPSSugGJr=pGHM**tYmYoZBIzU}QES*_mnF>`4KuYHGi_=BPaSj{5+ zpWrafx#)`f9#%=qG4pKAb^J%rcZ^y?CS8`&w;C;DF%)a*K zEB3XwUa?|9^6O;aO4yJkLA4@xNxpMK2ufNNV2S*S?2_^bD~++*jAD-TSSX^AyYR|K z0fXF$Oym&~ank#w^bB6w$h%}vz(9DW&ojMe$vxzG-((UZ?A^$!-)gdvY2mb1a~Z5! zS+z{AAUs6r86rMVLWfjVD5Zo8y`C#;@c1q*vv1cGj~)PCXJ;tYv|fmjDWPfazxR8` zL2!l}y4|kJf#4uxyR<}cr7tfjMA_h_$F8UKXvc<9fu+5h(TeS5U?$c?hs zu3on{-grav>D%_otFJrGJW-rUzKv)tpy%TWjKx_uB$L{R=)}JIz`jh3SGiOcu5DPc zwCeM(*{HjM)U`|+dxXcP?may{GQ9CwgJ4)-oGb#&8AFuo?BzsSCX|{PJ&GX{Z+=p; zW+FnEdsGnBoK6a2a$Lgq}ka^~~`V|R!sL+KZ@d}hg`CXWvHHTQ@ZM1dW1 z0|e)76lfR9RpCOC zeScV|of#hYrOKMtei>a0hN#K7tFcFcFIimcyt978jt{prKU#Ws#^IlcXEYXRSNMU0 z9vz`M(P}l^00Az8V_^#OZj3ra$S&#qq7_TC$Rgo`M~|KgPQoS8vc(9-$|W1C4fpQd z)p)V@8!4$mR4eNgPqU~oU>%Bq_=#a97{oBHbejim2<~@#YI9C>Y(ryOa(JQO?@X27 zZQ-KRb{#ksg!Nm9RzcBDWD|3kJz{WbU@Zd8Iy^kk7|?zK|Dqc~!KI1ld#zq`Bao+a^Tj0XRNYKs6{1p@x4bXB2c|hSSj95J4QQs; zjC${^f2^@tqjE2_bha-wQI|=K1hKrP8}y2O-1J)B?RBH;AR`Sa8^xP6-bCS27sg|H z7}5ulMvZmvSl@N8;0Ufc%@n=Fm<;TACkBW@UOYFG@pW!XYXbF+v;KxXK zG!~(Doe7{6?$S=r0;9S;LQ%K`EubG5iJ-s88$_jth&A1>@u5FG%@^mBY9IL4AZlAM zaf74AmwoUUGI%jYGI%$UL*O?6rB6IZp}+oq_GHp;aJgD3iRWIGtU-#qW#?rWs@Qvt zJxqZwYko2n;T*DDt?Idq*8T%GPC#EUwql$kMKEnm!=z{3~lIt6QBe0@w zBEparM(PK6rGH4d_1&0lcyXbA=q9vY6^b-7U={+4GIZ=rNy>IBU z5RrmQM22bnnIq77p2bi~e=j7ncyy)aL@JflI8_~YdC!jcce8OUc;p;*qzZN;9=zvL zIN%7WwhFJo4WiFNI$WI>9Ro(tJ;x`FA$S`XTydaT)H6iQ(kIekf;;eGaFaPj+F7FS zXs<{5i7zqk&}Gs+udZ&op$+5WMDhZuDZv+>Wz6(?r%|L7eemFs{p2UVu(yBy8~e>~ z-j!^!t2&1MEOMw&#pf{5{K)j+7CJKMu+t@7Cz>zJCH^raK`y1=PU}Li_3m&!Tz~4| z-}F4seBkymw<;c3`T=;00Rob z9R@kxLmx=f0Ymc5r}dk2&OFqhh!|Fi`eEpuj-Bow*vbB(_1f&CpaqD888*57iy!`l zt#4@Yr}hwWMd}FZM38`Q>8}$x3Lo^9jtdg%b5Ou=l{V8aUpNWQ2)^zm#Y4{QbWjP` z^~I~CF648r@SQ)?uN>UM`~8cb06WnSjxb0~ij zhA&Sm70C2Q9QyOj=L?QcQJg<~%4a{Ucy&`g^GV9b-3iZme2?n=;Qie3$&c`F_AS(g z$2fJ9-tN||4ZC@LO>zX$F*wbTE(`_XG!={PM=_No8V1D(%0=-zWFTaW=#u!VxUkDp zI`5vv(S(&ME0!;>TQZr4kxLFca~_Jb%tXIY{NUwXt*%%sTku6Sd^ARMPpsr}K%;T2 zMSjbbGx1DSEg{t#?;{eSr9OjO-F3#snAr;CDp#a1FT$Pu*6#ZZY;%DX&>BUsXHO-e>m`ANF0Lv9tHk_x(!5 z5|&A2)lZanm)7mFFAXpWif#bOXu4ui$E9myP!y}*YFBVT;$UckB9U?P`@+M14+@G4 z$(Q*;#@=}Swq3urZpEC&Wf28+TkVmYw2MI`M7yJ8S*c{~tv7Dj))i7mUKpu|P=q7n zkWNj)is1l+p;3e7GBolp%041TGC8s>kj4tUp*<)9&uuU~^L`TD=LS8sjW(hj#Te#$ zc$|;yw0>aQ+YjvY^hEE}DB|5OJR)V)*$|lvv#j7~ohNkc}Y{N1>M0m=Y$m#J{m7ueinL&?309Wz>=({Y6_YWHXg)^}zWrtu z6scM#u%FgqS|aes6?tgpm_sOhOLW25k%; zr=Cj7WnIbAC>K%2^ODHo$o6+1*~5GH!dh*Sy^qJ9jB~A*Z!kSe?tAQzzhoqzBK7OBzZWEORj(Mst;S&n< zLSfkw!ogS+M}XiUh%%OOCqmDJbFoB7&F3k!&Pi?Au%n{`d-uI}?CqbwZSTJOo~PU^ zY940wTzKC|_z}{?dPFTL9@QrdB^i(A0#8Vb$edE$J!VBEi@{6iz_1qH)Gu&pEvdktab3&e#D` zz1(qBMfiGo8H`b!hqgm|Z~%aAVubKLt};dS3!`mD@4#r=5e_mp1@9>RWj<=Yc2BKd zJ2dv^gO}q>i{62hl|<2A2sgnkjDRzK9M$;5)Hjsh>~}@<6! zs-4ztXM0z8)Y9|fetVRk(??0uKS^%uCnz=-p^3fG51j`Im4GT=jl2-hwf7 z9GXnOfH{1J6s_n=Nc9JwZ8g{~pIYwxlKQLzH)fQ+(x6`v`vne?C zt<%Msrep0^*ZTU6<1=j|!wqd9;;K}sx?_hMXjHGKqt;l%FQF4evO0|x9D;5~^I7m? z9%7J&UY3gMmM^Ue{w2*d3_u#I(NOIHN5OsYR#ZB|>xG*0(1^?Pp^t&nAqNK0@WRpv z4j4p+3AY3T=r2ZnoCq)k<81Hn)jwn{iA|~_Vm;BEnPWV7RV^-xC69LO!e1!7k{%4-$$_viF z==f7Ff2jTlrRIjOd6}0lQz6YC3~B-6Q7$b8Cjm^v8*em(BJp%LAYe>FI0%XYgiHiG z{TAnh;fhi?6Lk+62)uqf1JFN&54=CP?%obMd|@x4ocanC358X1WlJDR@P082f0p}U z1fec(uLNQ|n%%nyM(+k13@>=WAtW!j&_G*x2Emn2+Q5AnO}waHHn5GWj|m;;gOQyc z9NPZ&p4E* ziGifh4!=L-M<#X8aieAjr$^S%!if!Efl=7-T!J0&r`;~GoeQoQsDc-cf2u#8@{{n!bxKb+%U*d2RO$X9DE3A1n5mz#Pd)v zmg!;rN4bU9R4UEl5RYPVX_JQ6XXDVNy;p;n+lcCoyc{u&&`xjf_N7FB# zxp-Zlr5Nr!Z2OUP8nC}yP8V)2bE zfKn&yHxnXy;EQhH&@&-YL%dZL0~?emMCZ6NE1nT=B$6jYN3q~1DggdY`eGDuq?{T` z&T7;fuINA!Mrt)xEneMK8%X<>a^uBJsl9M{X6L#Vi?FG>>KAW!Z`{kVCB#?Rn z;0kxnM>XE0??J{%Bx0&>?CH*kY$9R{MIl)eE+r44R6~|S<|Lw|*=)GH2OhHj&&uki z6^j)gGjI{57Y<{{?%<>wVUeqJzo+5yb2Fn=kX`X4Ux);Q>EhDZ+L9&N3us++vquSv zOcbgpn~=xiaUy_7O^ytQ5rX-}nnLArWGy{Ulnsh#WJC6H&8ZHQ_i5oSawsw>GQRHv z!}tj=?Q*EE1HnylKiVs`k>A5!!{LU~vQl2LbgrOw(tgr=X&}Jq_>yG%tYBC2Xeo>6 zp2duCKs7>DRd#)5vaw^U#E*PW(dK!9$A zc4=NM0B7|=V~OE%Z|7b6(ZBwK-rKe6>YC4@@!RuLhF@}E?Q@pMLX zrf-KwdqI&u7^rVrOZdB{{ZZ-n4y}H&QlNt^OOV(^r(V2k1qNfwl#nWw#Rm&BeL?i*LkoF4#srjw(B!ZIl4C@`7 z6+Fv{;DizvxahRQ#trN`Pb9_h(XlJ{iNGlqmMx^U~=uw21nN)*vdA zd57^Xl_?0U;0=AnVIVR!Ff-R^f54*%(PL_3zt{3TyYAh;XFvbNFYKTHFY#{DDYJ174<+P)543S8@*Jg&{mDHp=fZsCEOqNeNMQu zuiiBtb?m|Y_dF6OmlZ!G+EwjGkHDPsbb*@7&}CmA3szz8q2Q=H(HLOtEr`BAH-~CV zPjkWXPHkdODflIOBsCjtd;4dbN|j1ttzJcNeoi^d7V!O-amQ7h0! z_$upT-UH4+_lZDa?{Rovqh5EX3?jd1pQix6KtaE#WNcZ(LvDeEf8m35I{FNZc#=;v zpW*rFO^`)!wBaBEFhsDzOWCtB<&F^0L*55`Hm__5&xjt@v%-Chvg|FE*E#A85nBbz z6)?iUyDlHkQQE{DxPJYbz541MTW6n9!Mi7(L^K;TnEqgJV^2np6cvAEE};*?IfV3v zqzc9uL0Z^+E~mDV7JA@@GIT~{3hH+H)@*e{JCN5fB4fl|Si*r^yh!5+KWEONGs2L_UXI9P{Pyur zAe-@w_>5>$yxG_rf&5gIBPfmZMacg&aZgh+Zeq3v}>+V$Kb~E+E$3ytW*a^&f zDZD^u_36A3WT7#77uVx@KTZu8|KR^bm;2tM>Ns;7!!COhGIki}ptsQFVJoz>|LW^In z%=++o9seE*oNI3QnwNR`k`)%?3$aDZYT=j8lYRt6hX}TWJVJ)qkQIgwQwpAH7`M({ zphL(&KyrdFCc}Lg(qMuxV(#Udr#aE5lTr~hqNYfbqKme|hL>!jDuKp5IK(vYe#0Y{ zeaKwl!?SwE4J49GW<)VCGL%91DdX+MUKs-yzI@|Ok#O4YiX`33Qz#rfwF1mVeeBem zw*PS3b{{;lmV`Jq5U2lZ>l^m1Z++Xo^X+eI@v!0{%%nYG!AGAsydC`a?uYL%Wdvl7 z(AIE2Oq&vjdSG-YzIaBr`fsmm`uy}}{nz*DZ)f`a4nL-UroUM<`}Oei1B_!@cTlWo z(IEk*D_A|+-?4*}LpzgjhOrEr)h8Bu#n2$CeM?7tVar=btJs z@d&*9Wk6ffsMoy3@uF^ z4OfQE(()jLpu9tAiJ}&TG)gK`HxYS7Dk+qFlM(5ONOOlGNza~ltRA-7q}2ij81V4A zB@zuDjv^Q(1ct9xyCHdG=!%+hY1x*S*Uk4j%aGm;<(!@qOxW0btY?rX6Y)i>Rx*Nl z)k=kwWRgYIhj;!+@>|}nZY^7>lu?~1dpnXFfi+5piQp2kN+oNBA{*BaJyK}7QqX&g z>OH9+@gyeQ)ljkx`;R0owsdaAT*8fB8yoEXbZ$L8hj%$fF5o~vFK+XO{-EqB6ql`BUb8HQAl< zu&~5_Tv?6LrC^DnQL;EVp}wL74^t&5rr7T$l}HHI8&;@Zv3R=Rj%*i~!iRIoX~=QH zH8+F`ciD>vft1J_j8x-M+YK_{-lgCoM9{c~C>os5=nu*>j}~mze2=)%SWna-gRvdMM@)Fk8U%nkO?8DO1{+ec_3dEyJ*%DW8L1&rn1YuW{eVGFbB5Gij0r|V zPbHTt`dXHC8;+AimQc<$1|0fk_2VOZaQ~j@R!E(Oa(h9rVhq`r3u6XG=JqtQh)5Zt zyub)>3|#S4j-K)oJR}m3^r6f|e^8CT&d^pR`eY$OIP!w7^iov0GV5BdXt;2!RU zj*B1pUO#p5q?*3h?Of})nCgNq`8?76;5T!eC|C?u7>J=&ydS>e#ThO4W9;G`)AtC* zmlLfGiImekq%NE|;c=|1J>8$?#!?K!2QVZGvTtq8+uG@&M^TgJG?9T0$J_u~KiRWi z{QM`P>+p{a=aak*e#%-lgW*W+CxUKCW8>*Wwa#R14(&!i!QMgfOi}Plsn29RAq{0z zu!<50;|8Rh@PV{=>}S5Vwqk3VR~T66Ge$T!Qe|>(EGKG)_mg%IH1#U(h8Sv(3ffk?Sllu%WR+cZ4yAXf=%X-i~Qx z713T8y?`TQ)or(|-=qI$qU%I4iXN$-zMrM=8$JrnbVrgzQR9)e#S6`0bSlV2;&0$L z5w!K%iN-GNPA<^TctYcujM@IquKnXb{G)^03aHHPQ z;jYgS#wv!fP;>|$2Tv6$3BNL;r=qvaH}N-&_|Uf~ssGf!WIW~$RNbCnq*ftkv9H%~ zz`kij55uP<8|oZU^0Xb944E+K41=>ykO@gunH66ss_#jE7ZH5SAKHoGo_S14M;sv1 z%q=&(!;?e6A za7b8U??)W1T;3cAM=?5!PU)Q^wWBLJ?BwX!e*Dw7?RW3I7vw*W^u=%wCg5Nt`mFH> zjy(5F1Q-9DzN+ovZXL+KIJGh7L{~ZJ{PcX#4RSn@7D64m&Vl?i{mns{efJ}r(X*k> zaNfT@bx$}qJMZuDYy1o=B+Bfb*};Y9&&`fMM0wGBK6p&~^b*G>DKC1C01JvE1cNuf z@|Jz~yWg`rw_kA~k2X7_a>l0q&X^m-SO1({sNE>D5SH9~S^ubvd+_QAu$n&4Nfm?& zp646yKz`m~0xXUg;R4ob_pkD`OR_N60}&b6k;hd1u!n*DU0Pal-0 zzrVPIJDj@)eysz!!etwj^@|s_zFM?bZeMkSNIXI6vq@mzdd3xddJtt6MhjBXxzb5I z5#=C?B8(a+h~R^+xYbKs9@6(kEzGIMBdEG9->4gf7yQv%re}~r@Tx}X=6u%qdEnP9 z^xb=3zu}R{Q1IW$sAuiQk?rsASf|}`UXBt11qSK8@Z?A7mcff&{2#?sqtyuS*FE%U zCSM>MxSWQJsD98lHEjwjj2Wa>LIyndv`9pj;7v~S5j>m}IT%<-m6Xqy)kc)<>?x7Z zvk@cB7;@;*(V?y_2;Nm&->BHl8yoi8tJm$;jVr#dSVnSXxtO!tx31_KN;SOC**7-k z=^Ag|x^CC6uG^hkTXyG_>$bVEV!3S6QmTJ#wPKYD9>GKPv2N_a#(US-sO>&8GS8;3YYQs67pik3GuJ zbSh(+Y}T${zhPhd+Sly%9rjY&uySQZ@@PhN63K$mh?L&QMJOvnR1ylvsNfU>S2Pwx zIItI3I-T=KtW*kb^Smp>H27|4tJRNPVdsj~QZNz)V+Hk&ZO|j#*VGB^VqoWIU0Xn5 zw}1gG;3(ek@oYu#ASEKv9l>zq3RqII0S~neMW@S}KHidrFG>H{*Q(;eBMmX?f-cCA zj<$NxPw!p^qM9UCOk@5FFdiXm# z+P`l^p0EbNYahih%6p8lVec?frsK#(YOiU8-G$^+U`dpU`i9~e2fC2H5d}7KE&B_H zRO`@(5a}ry*bRNE7K5Q5Ktr-Gh6};g>pdf4Kr(Y8>54y6sbSn0pY?=i1-p9vrrp$f zq*z?m`|9-5bN6u2pk z7fMFx2kST@*M#$pV>>+DbGTQ^!Uwf!Np+BxGNd7l*sy`vwq9Yh%SJyYKQeCr5 zPVbB7e0=GDh)4_cDSU=OWv(Zaardy#<(AcN;f=1HyD{7BOk;fa{olFa3ne%EhlTyW zFr?AuS;P_bqP`Pto1my&5H7OjTyodB-|4?lig85iW`z3;3d;4OiGRcQKaeadnk6b?li# zBo2nXvC~$X4NW7<3Ql@Nrx3A$a{zRcbqsij@dJ=yjGgtaqrR|T8POqO-OHqeb_C-Wcy{5+WegS=W^l;R z9l9d^rTN3ecU^$SF!Y(iIAaVFzV|!&d7*v~c^Bs?y+<@pIK32w_5iCXeq3TGYiX`7 zTA{om8dX&v!2@W`$a>8ad-vVnd6ZC22S9~yx}&G&7i&vsUq?7WG>RJ|)TC~=>8S-V z-Y~yN!GYoTycKG{30D7xQZr*d5D}4)4PZQn(+-! zk*far_5i{?WE0&$N2hV(W8CkF z9v~-bP7gGH=&Qp=?e{sLV^KVRZ~Kw`(?9-`{q#pavY)^G3w!_lyDkScRga`a^;7Ti zxrP&P!g*JUxsEY7LR2U7MYLaI8i{9pPGImP-8MMvR$3j=@=?4Q_ zF|WBHe1RW_=uY+}#K0^#=p7!JFL~7?`!(k-_5PjRdrs@)q>B_kW3RWpy&WHO_OM0H z?g}q3UbF97JSzAL#yh*)_Rs(PPlDsS#(t(a{;(hD-tMl>y>EB#-4`DepX(EGjU2M* z4)Dl#%q7MhC#P8^DA!jBSd2a7%4wL(%y(}@IQW>Ir*R)sLO-88 z^GS~n*3C)3@KS~M|DnqBbqizXhOc>Qpeucg{gL~@mv)rQtRu;bM z`|Nfu`=99#H(pJ@>zsF$KYotqR4)&6-s|H0lgB8$DSS?^PrvKQsqh$#SslE58>hB+ zv~P6@V|Z;NsHm0t&I@>+?--^8Q^6B&Iahq>I)WcJA)wO+_VtO$!2X%mhw4HGQ=eX`h zT8%qiK6p+0zGL$;FY_`lFJJy-3}4X8XA4As`t=Jc;dL)~>2s%M_sw|L2MgzC*JeF? zVI?n7p04xx@)6hkJyV{p?=H`T|I>3QzH;5X@cFl@n4iMB$4isB3T2IVv|6xZQ}7}Q)2 znzq{wEGWw*2ykyIlk@X?yN_)95r%-Um=9jBX5C(Qsw@az*YH%L`cG=dZt&{jDLWjf z4Ww9WS+h~Mj?PWQn|T-M3xmUvTA+6#m*H_vJwYja9_rS;YzSYfta|hX2Ea&!2#bOd z<%Nua5rouEDAX|Oc|`x>xvi{}?8c1^TU#w!u@pAOUtL+TOgg1DgtUbl8*5gnvd4;^ zS6fij-@0?tu3p)&_0@`%%cMFZvMA~bxYgC*k)KW{-H3!@2haIRxoo9k(G?#kcTk+5 z?BEkQggr};Eje6XqOX!2ISNJg`zd?BiA3x5nqGJ48?tG{@PNN^^_pF~cH1^K|8MsG z^SjX`N%sVe0*U}g5Y%MoRHduByZV;yd;9L3**P<3_OILzvmfTn*PT5(dqs=tE}1ei zBSSE#H31NU1W1DW{2m7)qB0{@b#``EHJ$MWfLHkIZf-XJzF+E*X zeO zv;M@_XEX*S!5xKBjG!E*uny>XOxTBn#X_&svXOLs{fVPvfJs)*CxtT#abukNm-a)l zlblY`eq=wQ3C1$2%X@MWfk0}m6d{024921i#$%j~{)w~zms1*btrH>>ozt!rh8VW0 zGdE+hGOvD(SV6tFvlR{Xi%10U8G{#yc-8O3qYvM;VQgjPrtqt(cO@J>?cyZd$L1J!{-ll_LALQHcyrSJn?&h#I~ z4EBCwuNm+l$-fwE*tkDNr_|=M+Lwv`d0XFw$ICZ`--{Ycy{j)dSTqM?rK5K=*P$C2 z=os&mE)4~;)-CEkDj4WXUO0`RfDSwQQsV}kQwlu+0Yj%?&RTC~W1MADGj5d#YAIpG<7C4!4`C3hhd7n14TInN7B5N^_i6Z;Oj7&68ede1%n-U$$r(WAFr<1 zqif20=RvzjH|nS>wSfphXg>$E*=rxs4c3&xgMA-oMVlte<(QwJkGYwu>t9`c;&fWZ zH(i<4T$m6KBf1Nm$Js)>Wo$xl)11=aL;uD#r!e{vjaWM(nv>ML&``mdY3o<;9|t-B zqGU+B2p^!XK|fR%Y?{5`t}qq~FPz4c=uPzpCA_14R4-$o2B|s>)hS{Hhk%P75hd!I zo`F9d9E#V~YU(@29O0kl5Ph+8h8P?&|ajNbI}enLjEWy8JqqIj?IR124MyryM)-~s18Z{j_X77v zMVpB3B5f}`%Ek|k4}BaO4lS23E&@A-C>)-7A^qbw2FIbCgprDOF}4^2ozhi^Kp$Fq zAC5NE%Lu|(h+JY1$c4ov8{mg~-!V5CZ+LfkvZQyG#bYOh`vtetX+}$W_Y_8F2VaXA{V?=s{E&%| z;n+KlXlIOt@SdU0i|-hNN#Tgo2z04?hV$;3=2lzquA8qx$8O%b5wE}gjkt5~l~}%c zJ8s>1RkTO+T6BqY#=x%+JvF^le-VBdYr!NrBWNxPZ|$Ivnb5Vw7ksEa-tSBE65Jfu z`=C!at}rH3Q?oWO!>b+DtNAi6zBHB*ofJ=W8cy+ZA{U8h&1vq9>m9WFqDLxF_SI^| z!NHEBijg(Z@i;31_Xq~eEu6^&n1tW(GvPP}H=I38Kh@5?-JSURfB5h5bZtYhX^B?V zXqkhtg)u-$6%YXWn==~ELMByJ8ir;+mZ9V(T*xA|FxFAQh<4Dgm z8Yh;kz+H@+zz_#;=1zi#Xo}`X;z#r!xn48?{1+a;#em}Q06nZX1-$xgz^UyV{N|eH zBmCMoq+#$-`1|15XXo^szjHp_^z2&t`Rx3&Mht1SPd_`E{s#5DcnofQUi6dGzBGJ} zKc5_2AN>Bb!)0*)=RRIqKK0_KmY22bqsPn2%kF#e_-H{wxi)-Vm+SI%ETX?>?M`GQ zK(RS7LfaLD-h>%LhrWpkV}xOD!{jy1Mf_3JB!d!)4ZM?CXklnFQ_?3w6T%0K2Ihc( z$)cQtg&IN+f*e8?US{@emQckzFoHnX5XK-XW+xEuA)(=`>V+u{83^ri#E|Ns;BARV z8Oj!-m0&QZTBK|}-H6?d&8Qz7#wnZOiW#zaLBRRpU;TCb^k+YdS6+G5o`Cj@hN;nc z-sKnZru5zH%K|T7l5htD9QN5QA3no1zH=|%_2D0Mfs#(7GO9kg+5~Uv#`xtre4}dC zqr*q+X~KBvyRUN1Uo@8bM5x4Lt1F?l)~d(a&PMFl_8k?6Q10;oo_Yw_Coffm*h?F| z?Cq%U2-FCPz#W(-Z}Ujwraxevm+*s;lg3aVcz{xmHjr=IxT1FgTLg%t)S!z=(4ox~ z-pyViDNPb7Hq|!OfilYYq5BY8sfQuZKjRBHhq3_A98wCMbrAZ2%yqdg*X6o=q4Kpd ze7&5C=`3{f6Rv(%Nl*Q8&wi|Y?rK=<559h`0(beB7MRT7>&J?jW%~G}0uR;)d=+ks z0?CX=d&Cuwt=OPFS>oyBXPhy6nRZ7-)%Z+pa^V>pN~W#M@pa+SwVyiNTj9#}FyW88bv%RVBUCXcKQaOlf!?^|z@$>Gv z`9hG7E3UlP@9SJ z5|D&x1IEbU;UE$-o+mTcMl5$6gqOnCmkJ1jj^E??r zt|uxI!-DVzuj@fn2F5SarxBeaAgN8HaLlOxQ;{!E$2fR4MigT<*aN9pOer^k-OZb? z#q9hY;m)+%j$yGQTttE_sz0jH2AclWsoH!f7_B?<>CT;3RX>X9tl-cUeDw_DhN4pM z25#UJ_)9_QkL-(K7twgQ7n;`w$hzF8{sFQv^}o|;SjkDG-Gn10lW|OfsNf*@J9T2Bc6$84bP= zDZzSx_7Qaieq$Iy*?f3(80}Ni!m}P@eU`?-2m3H-4OpHeJ=IKPC)g{Au}Vr|_fz9J z#(dK|NIf{3t)%fB?4dQh=jx&@IUVIGr+`l{I<5WK+<2_>q}3!!j`t_y90emFxJ{}& zq6~3f+fEhnEW+;7g z6Jy2;_RLXZVsT;7h6u)BdS*`F1#iI>!>VB^m_mb?>rSOOA=nf|SKQSrwXqV5E3d@L zo!2y06`hP|X|7^qC3PcfL<~HMUZZdpJ_!ayYmn*^BSYGwW->Cu!A|SMbDeGiXOzyQ zoW1M|ZWH*dVE_e|;>h8AFx z_Z+*ia?6o@tf^28aV#$0 zjQP1GE5IGqdd_}VnlqwDqoN}*Qq-Kra7-i~d?lr2B*GS>3h=^k;PhiQI1cd>y#i_f zP(0@ZQygAJZ#6e<91?J;1IGZIGKhK^8HH|58ed4`2|Y{mRd^=&!&4TQSHwpu!V`=b zBjz{E_ZE?qqUr2EHa!ik7}Izi*~tU`frAD6R}+zfA4x`)gm+Gq3gQ#&5yqaHL{kGh z^i7$_7xTK#{&M1z!U-Gs3OUXBoMgDA_~y628+Y%$s%J|Ym!?w^Ggon`lq=B;%)V(W{sXyi=e2R!MuXeoTBEdE;(ts?>$9*9%T zct+!+_p*;4@&QIM(@fEJ&r!`qXzi(Gm?Il6*^^5b{XTGKX?am_&fBm@rXI$e@f#Oz z64{lQNI$yj&;G$)?Ck^UhoG)|>B$<~5_)I*q;k!&qC}jMdeRI5@0{hcse) zXE)w||6y!zNq%aPh7o!EDt34Gqt<%x;A`Wm+SI1Ef}^mvtvRF?UEMx87okRN*ghCF{lxLPXauI2%*CpJ?c4( z8Qg1vFXjjlN1(zZ2XACZ2KDI?6MqCa1br5na9Eh5l_S*2^I~#Nokz+$FDAtp#9TO^ zyfDOg^!rlR@Svh*3~uznBvK#A69W%SJW%u=Ro-c`@#kI~iV;TlB3gCA+K=>ZLibPO z_U*gzKmE`DbA0<--;pp^dB)IC=1}R7$qZQ%ix~c6tlYS$%`2c_f{DR?=0@4eA*F?^8PGpXnS0??(O889sFYU%iukyH2$**gDva4_6;X zTS84%LLdS?JeXEszt z8P$;h#NrC!Vp0n{1W*<{ClZ25nLt0hfKdS-I6=RW-x+rnu#AO;Xcmte8`=!05TSV9 zhEKKMURb&U{vCPL%XRqz((FzGGFp#CST6MJzLazt;TP$I=NDSS>*=a^^1tx;T|%mq$($7iy0I*;U= z*m3{>|MW>jK~w>xpl6VokOfgHWOWXuOp+~;CrE>h?8!|;C?G@72j&LG1}kXPU|ElQ8ub> zBDL@^=lv+1ogz=N6JtwH8AIexaDdcQ^+wIl)3;=-B%+A1Oi^u&D@rrQpZC%p`iz0@ z=x9&p+kp7x!Fc6_&WzOIs zPoHRm<#)FYc|GB%mBOTOBXXqIjK1VIA`5aTqsOayUsAHCC@|qzt{Rh57zqkmvs6^q zwEBrxIflmZC}F@JA}gn;6^Ih!z`nRW8wCP`)CiG3Y22^+ZH+PM zy4o?G6e##bx(I*O}`?Vrfl5Uu_^k8LPHjwA7zf<1~sz_LyPn0vGV$ zve%AQ^U!-zVHljBn-dJH>XYgaE-|;EC(M@=g$6944bTaU_F8wSKN!|9s?mR*1EkCw zXowd%#BHe`p-5q)yb1cVc~gEgB~$&-R47apP9J`sy3;$}6wOM1>Tl&;$6* znP8ZVDWpQn>ODlmpnT7Xh7Y4YF}f5ch@9b_iM}#sq}&@NYSTt3(dn^Er>1=T=uylP z;X1ABjEiwL8LPZMq{j(myNYNF5v-XE#`>z$tg@dH259OT=}0Cn7&@RCMDy^8lLiJH_zFCoxo-SblNo!Ag6KZbv9M=35!2{L^1xT)IaIiV=hU4X zLz4pux*KRayp8oXGz>if1)2dJTwh;}jm=ff!4uO==;x_EG3bycwIKRLTi|PR3yT^v z(kc>>McP#&yf6p~mx`pGB~q+pgBk&I@y=4>*-_sq>MSoQ-p(7hSek30_l2EQgX?-rNlV|jVWxQjfqx4*AgJcfzw8)%(|?28KX%89 z2Zefv_kYr%|9$Tt6i&T(Jpb~wEsXfJ;p@6wm#=ZLXRzo-&IVqclp9W=Yt9oMXhpc!u`|ynCE_X``6${`PjPKYASdo7?IT z%7CtfQu3GgV`=$D{Osqyh`;%p|ETXvNwGses01dZcRV}X!UUIR=?GsezK?s-pa1!} z^gUhV3nhK}^x*GGOw*t;G$|;82G6*jRQ&1R!!tZI{H6ajpsq{5E>z)}7CQ&^qjgj2KG{jf@enVt+S`oD>_H^k+dwW5A*b0TFy4EdtLnb{76Lj+BhX2jvRF z7YZ*c2=tvMA#^6#l2!qQ2!a&?r500Ke0e_z)k7*E1a%9*;EUTyIudfPlL`PKHNBgZ zm(DA$7YvPcHqc_c(>)k9J8j`;YTk9ZF4yI{eBSbv8NPn>!@vI01r!jUvwJoh5sr+=E}jPgzW}r>dj+`zXU}vA?%&uUOJDSwWU7 zL^jWc{wRFe&kLDvB-mG@Se$ZdA@-rdfYR=CBbzHa)ew7fAu68rQ0|ULAydt!`+`4;JQSJ28Qp6mgW8euYI8`Ca^wXD z(7e65_x3j9_;_D$Nzq~$EK#VVghB~O>OXHHuX>V^@Gb&4tbQlMTjw90OtLoHY zzBQa@Ue9C1&kL@}$n-q@rS2hWvws#1(U1OlGjbWxeesU|!09p>;lWwK7RLsC@3UW5 z3xg2RO_Mh8LF3Uw@C_OB=}(b0)MSMzQP#8`?v>u zWeiCjOq4Iqy5JBn=e#(#=nzrW1@_V^VekTO0yOJi;d(wVIx#gH#mU)VpCmHnFb}ih zMVZ`$+5$|di?#~S>0`So8ni3;Ev;Ss>PT%3$*Wlnq@=M3s$U7g14 zQuLTeM)rVWPe|rW(#fQ#Ab8I?{nj6K0Y~14^9kdd99QWdX_8ZvInE>A%U!%2gAsDV z*4EQ_@cz5;0`RiB9xM1N!%1-#W7p7xIkzrimI z6a0o}19RGpEI_oA@lx%zK}4Tpnr|Jw4_d|khwva_gRY6jQjcgK4kPde`U0=Tallct zYCn9Iy3zlThLt_-W@Z+mDthldWXJ(e^0Y(p5qlC6 z#f=^W`Y?tONqmMmh2zPE@B^nOQneD9d7*JSt{n>+X@9XX4D-y3%QHta!jFhj1jdl7 zP6q?mmHJKe?v(15Jl93flTw9}0+i`JjG#k?VNZ38?%h_)GKi#2&Bc_hfE2FPY0+Zg z*16h}QfCSmB;R#)FMDscTcr3s(R(n!!LNboi24mZo3L{S4)4y|qjuVnLGK1u?5_s= zm=}|J7x;?U(GdbJKMu2WiQfq8Z3B;1SV*Q&U7gA|DaGTh{L>8^72O zkSKcg*TbNR^E~^wkzy5HB!)?xPB1Lv97DA1@o`P^bWe4&pKC?Ol%KCw*$cHIyqb=M zg*nN;80iXws~UVsAL)X1n1ds|B;7MCFJAxXq5r7O zw?BX4<7L>gbocYWj~C8;T1_u6FKgS&j+d2}-S=q+?D^X8bzQE@*SK71LCgYmTnwQs z;!YYDm=Xo14WmK;gQ_D)Aqc{_P_kT}ODGbtMp(sL1A=6xrE>@~5P?MS5kMibiLh7* zV&SIW+=uYPZ*Jxe7>ETn9gd*VeVpe$QuJL7o_)q3s8sK4XxC5TaCu13aiUk6- z0YQp%PfnL8!HX3KLIrK)Im2MkKH7`0LG&AVOP==L8PB-N>vCPL%XRrY<*PG%{q+|$ zd_jl@#MtGuNJCGY&=&G=~FzDOB9`_bdm%HSUJ*kKv8df0g65?_SJ!F%yc zEywr1|BYCfXU`Wrp-~oIiB~0u97Gd4d)V`QBrW(+D)TD+hjJX{i{&KM46lNhp|t8r zt~x$C4E7X(msz=vY@@pHsz#Au>LOI9AKN2JO* zJlwGo0i_r`oejjm}%#SgOR8j0J zM0zk3J9zElO-^*%{K7&^&(2HkA=RW8NW*iSaYgY zOM7qW-55dH_k~UD1xzb;h`s$K%;g3a`1jIV*gD4SN}(;6;YSV2RQgWk1nf zLxoAFU5oqo-}b&4^Rw)QHXGvwqOhi{2xgvm?^fMQM;Rj`jjRyLNKV%u4ppSw+$K7! z)ponV-SKRa{RKVAjctw98R(#TQdIxwD9S%@je^rt+v&$h&)BFR#`^jr^A7I7SS3Agb0*UX?{;=jijc#4Hz)X>hD+{ zVFDijg@De&cZt+}JN~c6P!0KUt}-$&|_TJ+Fy2dR1$jS6{sw zQ&a54r16?v);JX6^rRL~o;#Fb^I)Tx)FhM%2nPjk_ z4H!){$Cw}BDeFtpb7AyGc@54yOXqmi(JRzfj79p5K^_B{_n_)%Xy3(b2qO-qA;t+KESrM(W)0@sW8!N)yN!YW=1A*v~FS zXJTl=(4j+gJUK$rPUZ;(W4`!?XhWlMr1!ChTZ%ly@J9+k_O#@k7HP*sg44pVf zY9*I&K|R0$07rzr`iwII;7AAa2I~YsN;-&ij*IXm#!z%+?8^L)C?6t&tV0k#9p2+T z;VyB|AX;T;=vK|=ns4em(LJQh^xVO)4qbsj>!15?+D23tbo10}QKI%ziaDM1_z4d$ zyLvn;Iv~EKc|@u@B332m*#g*yh7uq@grhTWJVd`0N%_o%f}po8L}q^FL)1ZjXl(G zoCn{mi`2Y8KD2z!pKfAaV(eO6Oi^hi`Xd<;hmGW1L3A**CZZxdo1dGp0S%)ie24qs zyKa}>@l3y_f5?|S$Ge^t&H%tbKfi0ttaBS2`ei)g@GU&gQ~cyS&kyS19_ztAv!r{{ z(;xpE{7c{cgU{#1cYXZyCl=o}xcAc@d3N7NkB^m4yzsRtNF~>Xuj_JMzUBo3)|r?^ zd1}%Ndl&`=pp;fd%Qb{hF>n7?;WzpC5nxzAb3Z~@Ujh>g4g_X|PLw5SaSwAxDuS>h z1SLZkLY<9XVxErH(S0x`dq1e|^c$g;G(2j^@HxGY#R5hpGYtJ@#TX%nPVb{S&m8Hs z6YEb_ay8bAN}&*F`5eM<~=){KgF6NN50}JJ92*M9uKw|M09{e!(XdE0-HV{UA4cO^A-b5I`Q0(BbO^$Om(dP#56(*rJ ztpU_O;Q-Ho3s%tSV2o0#OawnInDh=5CKfOykR!a1IB6UO`*#&`>}!B0 z@_De&1>WFz=prwmL~&}nE>UHYz0OIcbz#NAj^quz#}5t;+^?im!owIN4xYQ>+o}_J zZG5yZ7y@?;4w5O5FMC8bpp-$;2+k9IgiKJNt_g;M?=H`|K+rFdPkUhbzG)6_?&{T|R42k$a zNeaA>r7&t(+1)#{@sB8&e4!G>@?4DNX4Q6ZXG|EYF+olxB{Ml3n&qpl@#G`uaU;MFPTy>0;Yw+WGpV+is|ZdWQ((!C&CZm4r>c< zl&^lF48<^s(JZdm$BUGDL{~KRj!U&qlUs1=Uw}g$8xD|ry+4lN8e=KF8L~8nK8)0p zq)p5avBP=^*_Y!?U~6jn^B$Drqy@axd_l<{8sEt%2<{_ez<=6%pP*377qY5vI;N%< zVnVoRxQ%K&bBPWR2?0#ONuuQnnrowul0yBWCI|(A|3tA8lhgBhPu_d)lqS_i(u}h2 zQg%E#nzQf{6py(H3}?(aXqDbE&fZ=)L!ywzX)Ud>^m>gkN^q?eHHS%gMd~bIhC-F| z>a6~$ZuQ;k#SBVW4wT}w6Qc)f4B&U_lxwVM=4PvEH)|16zP94{_#nMg!~^-Bs3j8} z8xt{lK|5%#&il~4qJJ4u;b{(dy@S!f>k8hBqMiG2jH_!6QWuV%Yg|#xM;zAYz)GPfFT-Mj$;DOsa-wSIYohfqC5LhoG6J-%?NHN zw$)$F(R%$zILqE#W$$aGRgv10Xg2FF(~~B9;&5Nv^cmXA97#&?=VJs+83WpD5Su>> zH#8Q-37i`)MTfh>+u5kjEeelBt3?apXABh%2Puta+DFfOBZ_7@LRoELf3p+OwjM@Q z&1Jnx)hC?*?`DiKu;_=sCxez6(id$ddUAXua>8@=jLhalpT!$fq!;r~u+{xz7`;e) z==niiSE5S?f(0-pt*TyT+~*^$dv%NYiveedHyRhw1M4!>=TRmOb6WHxGzT!$5(x=LvKmtf?_r zlQOXl4x5e<^@ia?aMoHMyv4{5R$&OK%n+$Pr}3z$U!u7h1EQ}N7nfssdD(j;67@to zh}fg_MB}IDmZB`&20xM!trCk%ccW5WjJ#ky0$sNLM{^Y2kLDlibm~FJfP)6|3;Kes z?X6f_TeB=ebPmy6<#NU8k7*bEgf60I!T<@Xkx>SmB;_8d6v1hpgFjNJ7dZ&r!C)-* z<2GQJWdAyb97hqNeV{f(P*P_y)UX9Z-ZBivzvH7LAMBlo{DHBJw1k(UeJT31?J*(( z8#q6H{5byM@BcC0d*{CTwj1ph&I^)@)Na&N%ni~;X0pt{BvS%oqWVD>BFIJrL-x(e ziEoi|6PXem8qZ2Dlq`cBfx``{W=C*>7VY4BHdivu&gqjhr0m(reu(HlFmRF*7+kvS zve%u?5A-8y!T{HklfX%>9)|~qmIsih% zGR76T1l+=qg_9Ta6?vNsQh;W1Qg|tO8r>MOJ+f`>_|VQy&}EF}9#`mua2cIcL33_O z_=54z0OOzD$pIcfGk`sFpNqq5zR?Bj(D@2nfrIq=FCUMRkoX9xGDbA#V6 zet+T6e?0R1pbWlq$v=np^4-VaZ+Kp9Pv<{=@Snf?-eI3!ehhB^!{deP=`EDu=a*kz zeBbc+q6N-!ZTPw_*X8S8L~qZ}(!LAhELb4I!}$(T6VtTdXWA@=EdmccV9^c}!DvS4 zJl;>7gE+I8gb89eK{z8)3t<{%3Dw|jW`;FTa=;Ai@t}&i4`FHWdcT90LxfO9p@70$ zMP!MKdY7KnJ21ZBad9q2eYAfN`#U?)uGgc}Y)cS8z$u!6A~1dLd*6@0`J2CqZ+-jQ z&L@vY2!xsU4-W%@PyM6Kyq|Tq6S5wsCzZOh7PG`_ki_OwYjJc#gA<1fy>h zTxhtdsbo_G3dTj4v+4ofbc-|sR8RY1x{`MjHVAV8z&FTH7^99Ri^>e_}Use*A)Tj81`S;j`WQZ{>ZVOr%=M$A9Whw(f|5g;C~YT<40 zEIWHh4&pwPHKg%D34yYR>!i3tK7!|wDhtCCXpgcnHW0;CxJ593s zp&xN2nF2K@p5;kN316q@$b>I^7fc0(JdX{&#+i5=w`hb_b z_i+*I@zBSa=j`;<3TEoHceVwP5y3*Tj>ZQH?{|Po!%lKPml;4;p_w&GE!0wUwQ=bf3qGIdzp%CXv31 zv{c|+u22?!Vjx3~)7%*CM@B+rELGL!o*Z&DOCEPdHy;NPZsiL+RR( zL?2P`k-}fUBx(oaDu%OUlvLZPLvw8OO1P}?-WT3=7;oV&^on{C9tmH& zZNcx*#xIok%pot~^!&N5bw$fC)S+lkA^}CaGOR*o&9tF&?0-XCJ`Xq&(J|mFN}PiE#|0hliZ87W_vw@1d`S0`1b+s?W^v zZm*?wvlm>&(Y-{Z;9x;Iwb7BT;0s-048bAVrExrmE)(@77z+N3cQQN=+HHc*5A?$MhNvf@xYZx>1L?uHXWEn1dcN!KKq~7&a)kN7WYZEe0-( zT}E9vP_Nb0KK5xOQur!*noB6&q1EvCv7E*jgRq{%FpmKOKEwS)-4Iy?oN$yG)0n{D z*c;3#chy$#_+Vc&ersFr!q9~tBmC~wr%%L(uEhU{M4XRug~-q;jbqxUD@C~w#Z9_G z(F1)hEG~)1R8>C)ylSl6ycd;eB8vqZ^^eqyg~>U!SD)fhq)lf3%V|ABv?_a%H5v`$ zJ@f*4={BjqI9eo~gJ#e<`zH1bUyL@)!HEKUQBK(S1Dyd*y{`DE>bg|_#coYw;63OU za1cO;1D@F##gUDo6T0tGcnIGma&32S*Wb;jzRy>YPZcB zFsuxtphz(ZE%Tmcn#)8SJzaeiAAInEV817M<1lu2wlx;JHbgQ8DI#Aq#X5)!_ZOoV zx)#Q;I9U}en1|3~^+T{>exS%8t#3Aq1Iehy496eQZD^?~#+XZFaf+H(5v|6N1mg@w zAtK2z`m^`evCe^;IKP~V_arA4Qbg)G##G0oXhL;XZ4o|a^iKBRBYKs{XbhB76(a7D zThNy!eG&a?o;2g|=s4ClHsaC4$MNLx<9PV!VXUq`jV z7z+z4v9x^4_%`WCzKrEoXwWblkUD6(Nt8W%86F)S8F!r0Szl-e-g&Vj}ZA1>EZa<^`0pm2zN#-=$(!DN&5BJk$a6*M| zmZt~b`HxRSa ztMA3*qXiCeZTPw_*X2*4NRmLjy`Y10=vmz$E2e+K9H`2(O?1^r!Ld?|vud=NGi7 zNSe)VDI?vyW#cQr~b2>5j@C#sMz*y%}RSDk1TPVPY z|M_rpI0hg5<_QyC{Q)DCG5*wH1&fZl1cc4Kt=N(P<`jow;<{pG2V;T&%KilyD;XOU z2N>wZUy319HuLO4NSVc}^H!~|Hs2mAp~z(wG4uJ+^g!y?&`kwiyW zdKu;91WF7&$Df|-3^e<5l*D=d6_1ZJWp=(tA)8!5>lB@O~5qcwX~L>L41RIy3JyR74)2JVVJz zG(n-D1;5?_|F;rMzfm-JUkCMv{VS0B(q3O$)azXsf8YQSF17k$>`RtoOqQ2##f=+xV~&mPHCBDqN~9B!8x8LX zM(V3ED+R|SH+er2T{|MhrC>KZH>diEj7X`QFiHVeJjAL0xsn&Sr!g3btnNFB#~=PC zPU`!9FGfTZ>lkNPFA!CyQPyw@$*+2GNd#e+eM3;hUI^Dn?IjsrZF4F>y_5ZVhyY9x zB|Mw4Aup510HgNnULq`rG;$hlHHq|ehP4X{=3I=EMlMs-bCZrP$!a{@dPGM52i`E@ znX{LX8_z{{90h;DxQ)WIRy%SA0`M7S^H_#7k!gKkBc}S7{^df=(rG!`B8v*qTD zN!Cq_y*T}XEJ+=3P{ zQw7_;U`wP6(L~1wyEfQe2u{t$VQg;-pK5!8TSxuZ`bso|y;v9r=nXP64u)>@mB#+E zC-`B=!xJ8Z4sDhkujh$|u@Svcj_H{twRh2YjPZI@_Yhq`q#?$!Q{fSgi7A>}ZxK zIL&Jecxpp>uik-SPjIl36x)oB4voKZ0LO7w6HieC%9pZ zWu2$`)GiF1dEK8;zevT0qML|G=nV!ZXg@|&4Cw-q-BfY&{JjU&!1Hn3{Whj7UIzj-V)Us!uW*GKzte7GB1TWjJWEj@o8S&YUbU4gbO z97%gyVid+<1tmGg3DW&dl!`WLrSzcS#7Oi`bzSwbCnxJXP07Jv>)0E{$KUa^ql(1+!S7t zVh`g+GIEHQPF7=Pc3Ja&$>RZz19Ob0qz-lDooG2}EQ!R<Aw+96f9d z7f4+?SZ>Ix4d?{W7uhJPvAz`8&xO*T4J;$YJzi3BwW-b<&Zp7T&g8Ag3XbuLm>FQL>EzEnK zqhnw$)4p1rNU)k@ievBp1wVj3v&SWo@bC|45_NmeJmD7+&&X^?8fOe{PUR_BLyLJH zXK`dH-~-=Fc-m9jyK1XG)yKYQJO*?OVTL`pC^%j9+WI8IP&DnVVTY6x(fqBAC-L^% zztddV)jYsRnv7FK_F>R$wOVm_u&;RxuTX!Ecg<^rW>KzGHGd~f(}cBgC{9AF6SOO7uZF39BQoeuYrvko-2XQH2Ko7w`Nf(!5-=3y3k zh74!j8L7Ry(a@YbmE4Ei4Zq~I=;5p<(;w-ZF|c#ME1nzZ)JEM0PfLfIs{1V~YVJUj zIG4`T55Dt5-}P>;L#}+8V%n8TdWKV}u9RiUXFl=Z@kIYPo|klv&liq#<`WP8Tn5j6 zYVjlb?-LIH@%cv_uKpvxzpV0Ny&Q0yYs1%dxh{VqPlVpYo?jCFZPe0%k;F=Z zbffBJftD6&yn{AT35K+u>LtBIMnpZUd*ZwwO)=!1&CS@`+Ky&T3&t)&F#Ai1bL#o; z|KKm<7eD`beCIpglK_YkL<4m}4`VIApb zxX4ZEm%qEO>6c6DV)~8QYIuozQr$4W)D|xN!L#}s-oyCt9cZF_uyIT9*_U9lA;F~H zl0d1mEL0HG&$XCgL1y7Y!Y6_?9CFAcsU27&w2=yty)bN~)OgVX#vSh|lshO05MD4y zGR`Q57%S2Tu>Z)=6BXfvdSUwBCqu%7amI|Flpd;I2Z9Ge#E`M0D6|)=+DJP|Jz{}E zLK&S-W2dE|>H!~~8E5qjb?^=^5-h;r8HNz8g@x|D6uw-S>vCPL%S*~vX88IKKm6gR z7`~nn<(HO3CqG_3{V7V~DE}JAA2#Xb_k8;CDMgikYTsT44+M|TfC$|5`P=osZoh(u z=oc_fUYO@mt(M~3-+Copxwj&|H%#9L&p`%4HgN^%c|C^=gts#XvQu&jQhnmT6rut! zs*q9#@18=i(31vBQk9ZvW&S0n^O%&-?9Qj~{5)oY}in8L3L};D55qRbz zLlM1%Qk0a5xcHp5+BV=!R?>c1r1it#k@h81Js86#h&E$Smb4cYi+}b-#Zwng{iNL1 zfnfz0@E+Q01)SR2N&DciXB35V$PLJsz>@_#(FQ0?fi+H6m&hiPRe+x)vLFRv8b86m z-%%Z;RYaINkImJ0;?3XwT^t|n*;AMOPxOG=Fk#pMhbK=yj9>ryAFV(ql@rQBl#j@2 z7#lks_N*X1RDv0DB~DanKUL~rpHNc$bW}%IZO8k&XBihIu@!UbKkfD2rg|RZm1R=_ z4JC=kMF%MqE!*l|`cFM#5BXE?(#pX~y_8m)Ihz!#z**?4TY9>O=)H23%A|=(kz#n( z=L?xA}VWYZZpPC&ZWX9%EDYMF5eV> z&p0BEz2nNog7>W|m1mt=5(PJg9{PjR9_ivpnVF0-D4RKk1=#DrNO&RKY@awa;EBe{ zk#v5(q_)hcKE_$kGEY2zv<4D9aLUUP1!v=o)(vM3-7Bi5CJXu+3(*P`uX+aDZ?&7k zQzAo}o^MPa<{Z%zL>gdNCSnC;zq;anfaA#s%#q;E`xD-2ZKJlc$DJJnY;fTke1-K* z#B{Y1w{G6mTwD>I$wlkrP;;rS@1>ZkE)I-dJjZ&Hbev>%8AOn&p1#`ItRGp4@2Cf0 z4P8(_(Ffq9N<^29OjkrKYCWlEtb^CQN$sXh829y^lz_}d46f>X0mX8;qI*ThL~l{Z zce|t_6|G@^A>*5>7ENbAvkTE<=3~AfTCKU6=FPZh#9{33J`wEB9f9O%O!$KEp~sx= z)Q$h7?*%vDAB;cgQk{m7!LXq&(Uf7EfqDP3CEDNgcbpy=7Yv9PSKxn+-ePPt-p~gl z0QGRA=oiL`w1?!0#)Nw={kwj+8%G#LM4RD*&|8na9wnLtet}}#DKND*_VBBJ%n?$_ z){l?OC%^;J%{9qhqxO(`7aok!soi2e_k$=YqG=|H0uyYZ2h4Zq6g2Hi3goDIHaawC|A`XR<>KibJ-y1fjdB750!2x`M zX_^m2aIrnXg?JVB+Mz|)kx57~NVFBkE8u{>0R9CZhDKrV!a#;0c3ik^L!Ib&SA2rB zbI45aU8nCw#u6PRY7BV*V+}Hwbqtb|NdH^W93;{a1I*&mO5D)AnVVm*-s$0o4`Oxg zNz5(Gissz3OoEQX>FsKg$t2IL>?21{UjcB(drt^&WQ$&#L1j@!3y#*LMgSYBL; znVG6-HF9F7Eg3?e@MYuT)=G(@FqnX7TgYSq23S=P~8}~yuZ7iB~9h--kv`7PK|pK zZ<3sD9g@ZwewFZ0z1Iiw9Osc|(038lh+&whF^sFz)oIITIE)<~l1BQ#d>Or#_l=#d zidJVlPL3i}%@pPdxJ&dJ_zi!sLxbi8ZAHc~?m=tR5Oh()KBA8@|KWbY4VVkzTrYAX z{Yu}{v(Jie(SL(a3|b;s!wb*amMWwS>wkVv`i*|}`L%R?a8333ZvDr%^edI&Z{Mds zZhEnfj~}VdbnDBm505{n{iT2WOE>!FFH~N9*GGT9czhWJ>UVAUx-Qq{PpI?>I~Q{% z4M<+ZIU`}r3L6ngf9ep0Fp*{f%Xt=JUI>Uli+q^CBb>3wB?TgaGt7y5@j!vF!T=F+ zU{)}DhXLy#S1!bxx~K!s2!HwzgA+%vvPp|{>K|8IvItXpFGAvzhmT`>eJvVd%G`qo zVRkGlMpKs1cQ1bOd)Xa5yHe6ptJOASW>FPbjFN_ zd->COGamkPv2gF89^c@b{6C*GgQsnd;-7DqAS*#) zR}1s?-OboNJczay{`7-|reUT9RARaqlkh}E87Bs-dsuLw%t_v*jBR>9${Z9)9^>@7 z^g_4fdCRB=1ro>5(*^H5yb2L$fbXTGJPcLjlxHsvri&7}$7Q5^$2C70)abd^xq9{#e*mKQXp)4}Br>i^V73N!>7(VV{)qxahJtzAo40 zx?Gn(C|_N~*AKtQ9$$&(zE~1J_%|x>vM*AG_YZi-=PrJ1$X~zUJ3sMNy5MVr8>m-b zS#&*F7_${rM2#N*A1LN&=b@OqR-1@U6i5+Um$w_)TdYJrcEYC5u{ z-BPEJ`|wm}A1QTJawAb@dEdjHLMUESdLtAMC^*`&v$bYV^kFI+?^7iCfHu%>ls>&K z-oiv0jO+Yp^w?kNqT^Io>VcJ8lq1PE4?n!0B10q-;vJ0A3&j>5*X>TzkzT;HI$aI# zcc#`LF=1$7Ula^fz>mFo)FZTcBUGO%XhU#AjM)z`-ox? z;~)y5VtH0g#bAJA84)yTdZGLy1*9F41jnJ$6onosm~dzk7Ft%-i}ek|BSw}zM@X^H z+*uo=ZAX_$MJIXDQ3oi-;fc5E<0;fjLG%3GAL!Z+ZJfsL`D z4=B!&M=R49eMvh;`)ECiYEm+u+sL)Izvq6U5Tic_`}|0fikumlw%jo=7 zOq8Z#cHxHbzZ8v=R@56Ox}I@_5vk|$SyIo1jf*J4ncpRi9ra+Sz|j$-GjL1MMd~w3 ze&*m9;{?orGlq(cjVs%mYl7LO=M@fR%-y~H9kpjf_^Eelj(dG%_^~cHNy=izPV>pM zN_D4*Ef5T4d?qGDlRC|#c)Gf3CE<;mHw7mQDbO{P|0h~!@Vv%OFiO#Uv>DiP4BGEc z9aqdp(N?X4I!;%n{#$7|sqy9gL)_`c)g>wQ*u$se{f;r(j0jfLb9LE{{rz=~Ge+D? zE9Wr)IL*3VcO?9L`0xYG)iu#C(xI`Qfo2n>o1z~`kLTz@%@YhGr|o0aajNkUCJNT6 zfG^+(@5LwvkHB#hu7s0?K7=#S+A`4*q`}M*iNj~shFxe$X>ulV6QoeXzy&;#L7Zrq z7=ea^+nRT+BjHTV(5hDFJavifsM)advEgJO`>tw(=<|%L^N(LIuq{g@e40^K7jJu7+)fRGtjpYy()=tfR70>iiG zfv(#qFZ^bWjZ>_nZ^6+%xPn6g`zEEdv%n6T%O}xjHcm0F`h@;NJ23o{0vFztcqIF< zGnN>(Z~!3ftayrb2or`4Ml%eFeT^RxMnum6M@EwQm>g4*4uSo^*dL8lyqS#npU!9V zY2U+{*~O^LE{Km!*}!%G{kLrh2DZQ*zKkq_E(6$M%z@8hJhl!+bRLvPPlilz=vvL|ZX7z;}9PL3NU*a3prOx8v~eIR5dU zeii@M|M$P>drjjxCOm`Rp2pL)wRrk;O?(7{a!+`?7pqU6#_=)ECq3an-|_|WYfj@< zou08w0!?MC&$^_BJhg$TUdK6v=tCS2Fa{;r2cE})42@ir93ifvqxX|y650t&aF#ZH z3a^PGLxxS!V;E$M9&2PrU`ajP$Ft+`ctcts5KbV60S|OX$c&_d#OQ@_5;+y4CdNE; zSBwqkXVfQjQt%AsG|wUncF!=(lGOoYm)b9!#_0gOflQyBCV3u%sC8Ou4|9#{IDS{F zRkdGqO!!agV9RH^##qB2EDLIWv4&ut@hs;(r`%uhJ^fifNB?Mt`p9#szZ}p2&ZY0P zYjD|xCrt?l=lJfg+{>rG`r*MZ6}}FC4laG_F}#@{pIUtLrxxn+pX&OwXuXz zhkJYRR5yF-Cac85WNS8g!P>b`*yw8(8=wTnvQ)ok;i4KiW(i zRSyL`L@AlmLLE<_ljF3h_jS20*X6prP`);XuSA~o|Cd3hzGPze$JE9%f3TqV9BuL) z|B|*3U-!}~(n(|hzNPmk zxt`CZ&F9B+)8e5h$oiI3az&J_7?sMt4-bA)gJlbIF;SjZo3pY0^uu`k=)Kt8erlru zN`}f53Waeiqlw_ap$Wx%@9e}1NDOd9M|hL_J{yyhq6~!uDHT!XBwt<6pM z3q`~1+(MKli$SDIvsE`-?%aJ%GT*XVdu2~?QiOFn7`=#CF9sXbm(^$51>f5 zl8C$sy+ksP`h#M~>C5cxjiKaRZQ;_D#~!6H2A_k&BjMm^%+D`cnNA-tR-E@vtn@$Y z9LCP}str)HC=6$oB%7yA_vr_9F{UUN!2#n53Txp-PBP&5Sk`hJ`=p>)N*nJJNkfW4 z$%?>Oa|b*He^KIf+G!s##()S3l+o>G&F$3$F<#@SHEQF;r8~~r=B$8n)AHCCN>`P|Gv!1y||B*jw5-A(If(0J_DAyUA`Gus= zB>mEJLo@59QOVe(@T4zl(+G15V+P7{K1D0~r>d{*IRs81vl1Ed!Tq;me|IyAg{;$2 zW;C8LHm&{<{f9Ci0qv zgtN%Uz?AWtuFS^N^n&UxyB<=N^}5HxvklKPA~2kqaU|_2lZ;+MSR0lu1>ctE9BoO8 z!Dj3lb{)+PBAbfpqaM+{M0fEhk$Obm5!pjqZ1DEJW{DoAx;Y~1N4s(Vy>~Spd!8>C z&oLmf7I0<<^?~$(j#Lw_u;*2R33QISIQR}7)||d18k0R*1an;?vH_TQ{gsvmDjFL# zIvL4ubWjb#U2qPgef@YR4iDFbhbd(khGWy`z#M-W&E|1zY_54vFH)YNWQ9-AR^FY~ z&%!z3@wwh{c(fBo>SyP)uJ&pE3tuqSxamVfAQ*!2STF`Q;2{Q!=lfd?KL_8%L;4q| zNufG{A{|=IJ-}6c5^d9<>l|}a6tU0#YYn|W8R|)EH(n6VMT+nmS6f-Pk7b}I@Ex_s zsqvVP@VT7cLH)p*qBi#G`o#F5zBol9hPTwl5z@SA{$tFWEER=2S$e% zC|oCsl=ZnIKh-zVOQP^D6xFZs3F`qcdX0^qtL-DvX{EG&M+aNpf0I3QaC|sEJ`mn_ zJdR^xvfjfBI6uP?eN!LD$KlcmS1}qfm%){k>1Bvtz)j^!Fc7cWSbHztdFR)0w6~*? z!cauy7JG^Jyq_Y5TcWd|A&q+7FeCME2yXC83{>qFhKfCnMMrc|vOumZu#w(2C%UV) zs@?F>$;!0xR@B3N$6yFwB!ZL3?4sxZhDMa-PM2KUSO1Tks&4tlEzMONR3rlkw`~lB z|BD8K$65CK8ZU^)2&S52PHmc-@ZN&-CmFrye^zynHn0s~1S`0z*58s<;3H?<4J z628s|MuLOpHF5)yQkUYTPVJ}fLa#{~m<$nO#lot&B#>6h%1RbK_;!^17r zb0Qo)jgxxQhQwR9ZpF&-O5D5mO5C}9CvMz?2j7mx#YK-VbCZ5d5e+}hepoXxGq)sJ z@fFeGdoic)oLgiZR#r4lMZ*NW2u=p*N~WhpGc`V>n#H(E+D#0p%t6wOjs=cR;%n*? z4!wQ#1UZHM3gKgP34ABzCbGbSaO~dQS8QNGKI!!|za?9Y>dC#Gop}6YRs69Q4Y@gUz=^Bw0m}<=$>^Ymz0cS7}LsTAQ-b-6Bo zf~D6H0dKX$Cj0h!V^NL}Xhjc)4GjZBmHuGH7h)JN9`!3|s z)hCzvIe46Zx>xsbEBEVwt&^7IivH*iIhs3@K+Rk9M+H}dH*;El+-SkuFHY_8HD2mY zruzF@*l~xJg;Ccc|0zbVz3r&A>fZMX0}^9JJ-i3_;?ZSqbk$|pGB$&Dr|@dMLgUeu z(1hTE0E)s6xb;xv={nwOB{6P$z3Vy=b_j8dB}|?Dx@-*7c;iWDPf8Y)syrFkQ0OH^ zpuKa{UvP+pEn(sq+ZgX8{7TT!_|w1ycP&OGq@&nFP@z5cQo|cb*J!6#V7y-9$skq;W=G=|acA8(a%)7O3!43`yQ| zRE6J8eW-fOr|?|XA{qGzB~IeUY2$hnLMVbzn%OH@2g-aLcAP$$y7V3t0GvlzkD`dE z9*kgILkZw+=s#eIv4JQpJgiZ$!7oubqC9cRp7yB~4;&aHXpi@lvN1x3o*5mLJg4{L zS&fovY&@sxaePt#`{%k3IgiKzE$T;dR;=XnoJ)#I`i?T{pa1^@4o%PssPTM+2Thxw5y=DajUft{?lrJv|UX$u~A;`#H*d!6J9lGlcEMx3v%MZ0>#M@A%UE8%;r&W7 zD5$|(lPgFgMJ7(1gN<7J5={UCn z8xQM)z*jeo z=bY*azwwGk0X8{R5f0o^zgG0VvaTlF94Zx4WX-tx))ii#X^h7_9_(d8>OU0!op#fT z>qg_)hA-x&jjW}zmDPMwz=LddA}ZA-RnNXqLxTX56P1WQHGg`ic+$6YZ`uPFCHB7e zOZm`V{j;;vv9P%8Xg0>0eVH)wn4W2lrzi{RV|9U1gF??SK3>I?;5$9H6vfG<$QOmT zW5Nf$6TAZ_i9E>*@BO?DBO{v9bsML_%L&b6 zY-|XJY96PB1;JTxWu1p1jP#W3GZVr|3_hgWV?JOcPDTx2ME#_r!#H>m6QZfizqR$X zc=F_lWqam8S$I4(Rn^*p{qfkhtP|&&Pc|$+Gok?#jE&R@{z02tHUfYwDW0Jp$f zi~yMoDL9F06RpwQ%LtiRi*R5JVB8N5c1`OS7nh=3UC}$|)c%6TM!2G}#5m60G#H&Q zxI;5YYs)+&#Utw&3iN>WFKGn90pNpj86|3#z0iP_+OKJ>lG<;hk?JQ6CWgE;uQ<3@ zV{$3jjp{qN#TaYOjAaE6aO8@*)z8z0uiH67b2Qa^u6d*NkoXE|aJ}~-D5_`Ji;HMi zoIg@Z$@D(@iy_+k4GlatNr`4Wx$3E}hnh4y4Kh$pL0G`H(9Cmxuj5)|h>M=P;E zAI7apWj@9W;#H&w6+TWBaxpVI7qg3^ec~-y&E2ke4pBYup);+MMZ%*zHRGtzarF;6 zh=HDcLWy9hh_0gpAxejc8E6fLGxjU8@l9<@22$v7qS44Ag$c<4>~RRLXguA2a7ObV zLo!k5@D%p+8j&1;!!yxftkp42rD$Jt7AYDnrBl}YQr)D-#farSzmRE!ufzSnFd`8J z!yKI=;&r+zd}h2Sz##K?N0I3_jyTgZ(@`lGH6OE@V?@B6I--zNdFU?SCm2yNb`n_y zpT?mZXPvz0iSbj{;cXM5BN(gEJ)k$Z_v$P0-S7QH+xN$S_klT0fIht!pvPNEY z&?jUq@5QRVvbP@kt0Y&DewR6NB_1&;x=S>Ah*pXg32&ULQSuL|0Wl=$PGJUVqU(%g(E~k;urzlz^MTG>Aq<^;XOnUB0GTmz_2W2E`C(N8o3 zm>sdt7c^A!!DB31?QKINwkgv=?I)QJFTNjS+#y z-eed|GkULZNwO(pg|5r{erXKQYg+c!ISLtskYkB*!wCqPa;931X~~{WW2y$R2EfV5 zdMot>81OuDfKwo1{1V=${m(eiqu~sYbaS|_BSR)#9#fL_fi8ell6`my=c$+bQyF~Y zJb&EabIkFOtu&!wlx%#;!q9Y91PG%Q%A91JK;fc^j{qZKk;9Qjx(>1SMw@yT?_vl9OwZmK zI_LZRi3bu3A{L@ziFy%6854W8Nu(t*sy8pjG%kUnws#Qk{r;_3d-OQkwWd=wUUU&+ zuDqG>y;ok1U;N@1@spqa)Jg+V`#8tBm<mZCA0E`CpCJ#qnY-S@ zd4z_Nm@}R#JjZzeN#xvocH?@_p%1aFwT{n#M8ysU%?8PEatG(1geF!b~K$bw& zzu@e3xh~h`y0`$#Ks3L6g?oH`lHu!RGzrRT!vDpJ=;BvK;h@2T;&1#O9MAdcS64pk zeY6Q)VctN42kjTD6u*kNu{;ys`OYiedq!u)*Sfk#i|a8w-cjx)S%PaUz~N)Om4z`2 zT6iCea}*Wu!~}uVD(*osf=4cV*a{T!GL$==R?7!4Sg8iI;+n4ht${(K|hkH~;y+#IOGG@4VmYYp=c@3k%EQ z$$7&sdG}_lR3IG=Y1w9~%aNa`N_Lr29rPciuRbo$B-bSe7-s<($y!M|KacnCn2lcS zU4`KczF*KM3V!xrz$jU-9a~X}p@v8T?>!>fA~|LC9T~8-wI-ZJzDW@)?G_4=u9c;1 z^v@WeL<4RpUf5_I1r`w=<;g*MJi!Th32$E{Gd#}$k?~BGlA;JD{J}x;$Yv!#;sUdx~=;d*Q89ox@g4xcYhnd`pqw`P=Do> z*J9=7t1&&Z64`uJaG8+o)^-#YFr}Rs7jTY3FOEWszJoVJ+MP6xqftMy@gb$Q()ijq zgusTf{WMygW*pb|1UqE-s=fOsN=q8!s${@qSgCE(k<}`ay zi5BW!@1>`2DC&tqNKq+Nh5-#@D{u$5E^KH57pMn^M`*#;)@mFcY(`FFKT(2CPUwE& zrRo~d93t9uJWFcAw5K#tl~dD;!Xx(0Vto6eCkLuy*UEjOEz9L8oMF90sx0=U zVSgX`%f4W&nP@36K#9yXjDlBv@et97t4rpP*1f>T>NKLMnsKRiq^KoTe#t&_2Zr&L zpTBb3GkFyHL|R2O>ua&Kem~B89gjWi4a3DKbqha6$0zhmNw_s`L*hx}AkI3+QLF9R zPy;Sta2eJ6uAD;jD2N(ne!?R$36lNrxsWCM;Dnny$h4^!~D3&Mwf??iKT-{~Rq zqANFV+>OPRTWUi#NUz)LwLQOGFd{jDoA|i+8tLg`R0pu?V!T#+)xH$zEuN#JI5j6SN?OZ|a0esFuJG#0Q8Tl1 z;-``;61^86({u14)6HT1-aEfMh`Ftr_v8v1~=WfPEWUGb=qYv!p0q)T+}^;%9Q$PG}QYi9ohEED|Z|*j6gghIfJpph}&qM#Ky+jV1KVYrwSwu=L!38Nv=vM z0?(2RfU!o5l*qH{OeN;#NP#F=Yn(6$aUdThr>~saQjpxSB>Cf}cs%Ky*_W=Vwh5M! zVYVgXtgf!vXorkgbNbJ^^;e_}M~6dXq;*t!iua@pKpJn2>*OT+n^lbyI9D;(aiVbg zX`ZpXCHk*+V5B1Q3R*~;nPZF>#xES$kilkWk(EoS?V8sd@D+?%IF+?EHprXQS0*i~ z>OoIMdywOidoj3K$A;sSp24_>4wZR12H({^$dnkqi9X|#C^4tk)HUk~)9C4$zC1zVWU2=}&(iKl;&+;_khBTG)sIiLpA;OMOU$UCaW42csXf`#JqX z5ain6n=TBmSvQvc&i?8#aeyDo=OFwm_XZgZ+J;D11=U8m=zYS+Zhxx2NxmW-3 z`Rq;!l)gjn=RTm+6{FqS-;IY)AH~z{^*Gb-OfGrZn9;&i`zg{2#>gVwX>MSc>T^a6 z8D5IlA>%{aP~e?N&|>@Nv#O1c(=z`%$hMl0n{eM z9ehFxS0Pl}QFlB~m-L4x4DVx+&)BeVL{WgZ4-sf=nor~yMl<@rGrZ3cXTlkr91VL3 zKL~hu=(u`7tA0^8LT(OWM9(?ZhU!FLcU`W_b-6AoU!CFWuYUL`ax#=_SYQGJM)1*M zUi3961D^DWB{94&t$b#$x#8I&@#Vz}9`l*OZym@IoL~X}op0TXJ9ic%FMbODKrSK8 zjCm(Ajs7q;z#HK|=RFh~cvgp=Py0u~d*NS155V8J#zGffh}Y_g7S^;8ewiFoFodOu zXcp0q43X?Ll$$0>Wi5zN{D@C$!Ht5zGMeNur_3u(#w3vuj@HVW_p*Nw3L+v^3KM0$ z1A|%1ZJe83jEwH3Vck8D~;HjgNQK{o+yKoL8~A0^DC0w=92*q<(Wt0 zJkHw3!5%P<}bygDJ1oN6j(ftcRWTflu;-%yf;LN^fNh+ z7ltd8Y$?@EN=HSc1`b+`1qb&!N=7hee;bt8z#ZiWQ69snKgI)jrl9jUg^^;bagvlY zPK~B(Esgd5{(kZzJ|%iWcp=#d#X9?g3B;DyntBKOf3=z&%U-+-Z}Ov~T5NA`dtWI$ zp;3Ziys%fc@B^=Kl-%@(P55~hL#MhVT+=y}qG|{Gku1zFSy2UC%9B%8kRsnFW%E_^ zI)|~f@z@H)nb~T*{`xnp_(yq}3?F##k48?zjZDZ?YN*|(!W|TuC<)m^3MD8;BNSyg zIpNhzd#va|_SbWlg6o;&!xWX+(3lpZSei1fjyqB-;nesT>GM!3>O0DA;V%Z`@n;b~ z!b#x{(f*pU8ebyY(tcp1Q*^{45jBA!mA!#fR4;oiowkV-WUrV@E4Rw!ic?~ZW+x;g zvt~ePrn#8USrLXji<1`nt}vdA@6_as4L2!5h84i@pr~y+j}elH7v?5WHYi1_GxLt> zyLI!Hm1|@!pneP=DBts>Bg?S&(zy3=+TU4=wZ~ffG-_%)Q2{m0+nQwR@E*C4JyOBd zkN4y7Xy3{+D|Q7>(x>7bPjr`~jK)!%o$HyDs+?4k7)_Dei9{iK!|)&Acv^Mn1F1Qz}-*j!$TcU^HG5&P_+D zkQI)fID-UxhZQGCzu0$_6(05&`-$YS!B}I2@x6c1(m^U$>S7H<)Pdfh_t+o}Y(*E2 z1se+Ooort2Ic}g@4Y5Twx z<^^jh6t=t*xOvSvDDWQ}%Y~cp7wA1ap{4oT6aCQ2No~-L!p~;?SiGVhP0b@BjyBdF zd7s1Goo&&uGt(g}^c|^3U;44L`9VB>__me7qVqff64j@Q~lI;%47NjL=@sYTjT38ylxi<|Az&lCtUfrO9I0C1baa5%7aK zsCs}sK=(7k9Y^2|`yqaMN%}~`V%Ms%-%4VW&q1DAwHFCwd$W6?O-m~8% zG(q+I-S7_D!9V(;diZVJqrQ~3wLn@o<}$_^7M9{W;43sQuQ`d4b8;}JFm__BE{eBI zRpw%HdN~=b0s~J!wl<##?(JAwSvC$cw=kB#t8CDQ25DYGd%Z^%>F(S|+9cVcr#ac! z7u`A2`*8}@*boh!!&pRgDX_YVPV3P7LJE__PZuNy%y@oa^g?C;FO7raxhRxp^gj5w z-i1+{wL83(b2fVE{Z~ZvihpX&o%ZS+ZaXll_fr>eW6oiC1x&!0SLht$4IOl9P3}#7 zNe8$$9FG)nir;!93>uv_<{YC#eRD;wLy@Fy!z}Xf@-`_6iaOjBywZag0z)j0ZS- z6M0<{-XUKQ{YD?56-2@_zK()Z8;~DpN7AS0wZbb>7vo&v{^&iYqDkz-g@X%58s^;7 zr>lZRPBPm?{N}fB##?W_E56)_o$dX2@4XM={{0W)!v~LIb7NcMG-87sQTnH6=drhc z6ziKiHk3gNNvG%c2sStygL}Y?{Xd!4>uVdTcUN?ms87v3bsV_{ye;9B!F&=7p=}s` zFq}z134Klk?b zV|RB~v=f@cI1B$ohj3WpS?CxJWz6mB3R< z5849Eq4!{vuS*8?zVpO+5Au?{po!?wFWuv4Ehz1PURvNcF%p3oC~;t*j=(a3 z;w=(F#7L;$f{z#kUJwv*zF&#?9qjJMyKlZ3AH4l;G{qFTpXYfEA>)Lm|M(|Ai68y= z$8r1i9WCyY$B8|t_~c#shwzyimk4BPLptRq`)9hBOLT>|__o0f{_`z^oBRRe9WWK{ z;@q?Q^{CHt5B=456m6+O|Ia&oUI%rhJE>3oL>5-zgLCZbb*zQZqqQfoy7AQedXbuf zec4zvGd9EVfl0&Usgs2@UMHzj2yzlmB#^;GF+MWp2#uV#m#77uB7Wch2L=8*`1)^N)DX7?e)6wSEJyq+6nNnfh;}^D0k4K9 z;BkLrr7Auq-pgWCyu}{-Fe?>!3hf%RF-F%$$Mrioji4w+F;Chao^G4k z72Rk_GJyEo1zy9)RyYs^27e{RUc1%MB6>R5>jDK8o2WNV4zsb_Cm$9??I6nB`-MIJ4-T2YZejW?mBS%R?s+w-q{XPdOJE@axSt1irj;P!)U8L$ULNjM7D5* zkKj(49SmPQ&wdxQ7g-jMUledCj&SHf<~eE9)echQk?Ls5V~BBwXfb3fa0Q$}rsg|J zVLYL!+^H1R7nE#615n5Z@TUPq_E|7zI=*x@~-aA8mB2vf-U1VmBIWiAXN?aon zjHnlkjHKv7P9#bT&+YEHbYMEO>nP<`h%ULr#m3R5wj7c9N^(uj>M|Mma(|B3(Y zfBS!WOlN1N2PwKxQliLHZzMMp<+ZoFX&B9uDpK>D@f$`SV9+EDU`DWEEu<$MaksX< zD!R1obwEk@Nb0-YWyHAX|0Yi96E_}f#%7$ z#&JyRf;0A}LqYnSPUtoj)&WGQwSqK<%wbX|5~*b+p{_$;!C#EX;3aFZbHS3RE!Hq7 z=y71^U$Sov2B>2zHE9F110zvWbd_i~B4nURmng|KkD;m5IaE+mm`lK@P$(I%Jg3!m zr$bdciP9y~h&|Feos&2g?O0!b8t=dJcD(uf-^AL}$C|&VcFZ6PN8&foMaJPuxW5s# z!%e}xsD92z8641evpo!t8l#ahoGnEAMKg&CoSm7A>DiSiPR-k)kThl*DvuQkS@vUO zokp9%DGUax%*HWC@EBJxU|_I0h{o|#!Mtfh8-`f{!PkIK|6F}kKd&xGiK#itJa!q* z6WvSQHg=JfM0g`u5Umw`Qs=WLq}HyQf7F9v#73?R26x&(d-T%2?ia46Z31{dxR&N0 z5rL*Hw2lAxXTuu?Z0HH=?3&Q(a%EmO`a74~#g)`!N zA^KrB>0PI-S{xnj8&@XT_bZDrK=UZ0PK~LbEZEf-jH8(Xk*R{WqeUB@kKCKaPw=_w zMEhhrHa8v#AI}UP_F_}xEh7;%I4ayB!uVWx${3C5H}sBu;Ls01kCH)oIIhD&ZM2z% zf7dV>whda0(H@%1943ODeHeKLnyyNPbNtrx!bRjT(malgl_RV9%Up&I&&)2wbag?$ zv*z2R&qbS(6^>b+RQ=$K24^r<=!g2Tcd#q?VNl6OM|0~`ePd3d3$f8d&(W5Yo?2rq zdPZa{(RJ0?CCL~wj#kF#SiqnzT%vE_E~zk)>1^!QJZQH`<)<+f+#S&`p1@q&-8+o^ zeNrM`#{S`JQz_7lb#G5$#}wZcoRVWhTvCjRnT-T21t;!`#AoD;LwEyVKQa$vY*};JMj3 zAG5Qwk|X8@QBtJPEn6N!w*!1g`-f9VGJ3Js7}*f6Y|KlBoMfy*zS`N@i`6HqYH!VT zIX$!*4BhPa)$pq%AKMV5HsF+n(F^AxqW6i$~>3(D|`ULDT z;v$0}m*W5iZ3efXfyji&G917L-j0I=vJri_5N>mTS44RsubrKe!VrC#F9%G#;v{CJF`_%^Op$+IzDew#W&pN_J!x9F^a#U<^gs+mKm-=*{ zV23PgxrQkP=BXZ6rQcrj=!C=lJpL7<@}#RnUJ9?t6an6U%4c@yX@m?{Q1g z*Dp{$UeC+Ri}(Gp2UO(R@O53T%b!6Z?IC&d5sVYzxqH(F~Jo<7a8~i z5(SZmFrW~i9tfz3y%zy#QD6csrT~$)G0b%!$ml+OUWw7v4vymfJMYA!_dkf{Q6s(B zB^ig1__kA56??%uUmmQyK8u=xW5rT0EJOzAB!S$(%ah|M<--AyWk$`v@pNM?>W!L&OcY}X`=d#)(E`fCr{HOYo$A3L1|vlPLkYoR(B79ihwy{PE(#jP ztXwR`gcz+`sONzj$`ZzoXGv2;N(hgc-iuJf`|ZUnfdS_2E{O@#28@`)e$f?h0ioK8 znX^HF9Fty4=ZYt(F+e?jA<+Y0U2Jic;j4HPyx4e z()~<$MarmrF|R&IaOsg|F~R7%T$k(e@3wq(5nrEZ_)0YL509@=F(G}S_~)M>;S}E( zc4f$yP_#*uiOF)#M=qdzj;cyj8zz5K;{_|8Jvn~$p=l$jVUQ24|D zs2+tfir>>SEv(y3@!ym>k!G-v#|T7Z2j?(4I6ZTQ)L|W`*JHm-QtF_L!6_xlA$r(6 zcsxqQsmP#sv+^-Ln;pA~(gf*%CdBJ{QLi6~A9iD=I-@ogRd?6vn=rz`YvKC^9Vyy_ z-k@y=4y~WD*>9P;M|T7_u-( zpe!QA4&pF4fLAaPR$NQbG;JFePHaR>`zocqGOoO*L`rXoLOyGG1x35}mC`2)Y@*9B z3W1v#H<8tlzmSEHyHJp${9L}V60g7UTHLsCBeh>L&`{3H7fER}9ZoGMJVa@dC5mMn zV--pw6!mA`55@{747G(~OcYaEz^jXv4JR1IP|Bd#N5O`H80D6g+$uyIolACdG=Olq zsCHmfOKB5PcnaS~nFGQc4b^bp3~+a9YDPH0y%-j$UvP<(I-9=ZSclBWymPdOaEkrv zh+@JhY2$?OKRL&#@+--*XU*ug7>84j$#Lz_GOnhR+u3Z^93h2*ixhX+g8DlSy!Ad^ zM@i@P$DnRri(wO4m$61E)$Mh3&!`oFOXXocg!}@JI_f1U;jv6!4CLSE_ z#o^(uzO(lfp6atUI7#C5xQ<9R2A(M7Ynp49f*JFYXp@efvGGs!RI3$x`LoYjioO}Z zzjY7~?!OuL-+SA5N;*;IRWeQr!~3VA32l!}CWk_reFMvm+{if+?82O}Xt|9h8W+Z_d2*yVdt%&X-9x$H9l{lGl(8pjgZgoJ zsEJ0buRV^f?RDcpL9k_SyqVcq&27>OjtPIX*63f^c!c50ifFHu`kogkr57#VdyEg@yUJsku*zvK#uWinchCL4EOhR> zx*hlNOuUFxePz)e;F_737VZ%3d!f0L48eusq{f>FSCs1PyQc5OWRRtOSG`k>HDd(4 zlk&TFx)*ypj{+wR`ii07Ykg2jxYQOOB2^@YLVB5>z{m<739!CN_p)}!fH_#hGX^#s z3QtnnMxDPJjjoLw4c$YkS=D2sr`E~p+o|Xk-YJv2cu&k%H?_-`DXV@n`kldvdZ5*EsKC?g&oM7U-Yo z4f_(J^T_8X%{PheUf+DGx;x1+#`BW?lERp%=zZZ|U*{)OKm8X(&YR-Jj7{6~6x?I{ zoB~g;gAO`UQFD* z&jl;8;o!vEkt_jSIP3J{cW=HE|L_0v|BCgEEgP~hR1u-|{s)iZ@sp>bd+dpY(Woyv ztvRhRBW)*6D5R(^mn$AmWDC<$(Jp8`dwybsIzcX})toH{T7n!!+u+}9YtiZuWsPo+ zJqCfdD2C(^XwKBsWXy?X5$S|;N!rq4ET$w+O^Y{7s(uVxL(INw|}TQxF5U$wb%Z#7c%ToFp*RS`Vr@55KYAP4Kon zs5V=U(M!0GcO=~y`|%=U4YEzBX2t@87ki?SF4IwVgZ=JUqgc1f6jWb$pHng;L;9VG zmJaofA1}OtC{(Wp1t_rssW#`FyhySuj_JM{!9u?k~DLU*wJr<0HS&zo?R9U z`otiD_W}$Fh5flq~k}#!u z_{C>>zY0QC`l7FDo9};qZ~DQ%Q~~v+yZMi2(>*Y_^o+`&uYCCSVV9r%&$|R4-%q`q zA26u_?C5&Ec@nEzYw_XZ4`cU8j9mo3s@8(L$4BG{> zm@iC{F{I5XBLuEAmU^Cd!@$jq#fbSX=xLm_P|!6Ccsd7@rTsjQk&43D6An%q6+Eg? zCU6d6gg&ycwa}mg1)lq_0|uXrTx|Z1at%*-2`Oqb_oJlqcBW2gxE2n}uqHm!F|5y5#ANsr=kx#Y$BcNvEBBV-`#*Ri=H@Emsp%dRGDQ94 zb0`>-lJ}W&hYAWI?>U(lzq`8h;u?=lekVSPk_|qTA_4rTPoiPGCyz^V;9!4%JW8-; zLksznXnIeYjaXk_8yHh?Kw%U36wRJ^Hp)~s?q=W1oMkR6hfsiJwOAg-5Y)F~fOKZr z%t%a4SHvp|;-@UKQ3Q}irfiRCE3<9fNPSHsL7hV-7Uf(#v+4I+F=hpQTJWQsu1=R? zVd+LpRu&|SmDH|6WC}!w5aB^R8NrQ6r-|epEf}speXPDd)ndL9Gt~tvm{3sR5szGn zvJFM|^F4hiNJQsW!i{GtkzXhVEJYOaINH(}+V}2A5C=PVH#0SeF7=4`9OtKJi z1qMc^rlD5J4WtuXd%6)19z2Zgt!>LUj3ayCB472or17i8NxiOdYB?2IyV+D-J$vB- z7nI{DiYzBd#=^javVs(Yz?**U?(aDr4+^Kn<)x@-Y#2jiE#xy4=gTWZYE7zcjASF; z$My$*@x!=r^Ntl@1=U6L3H!ex2Z9@pEI`4o@j%9+?chO=J+)f(I6B%@Pe)?q#=WRi z<|C7@>i0yDuI}u#5r>j3F%*GczzMmL!nmQMxsoi&ez47UihN=YIND$DP7yaivZqDF zsQ}uwK}tv&>_0c@bW%iCpd>5^F372>+w&_an7~P*o`{S>;fWlJ%;>#=B)ekdz~Drr zm5n3JWBt#11A|UwdO>(jn!MzV-XDxH2D-`WqTb7%O~T!5K5`ks%&5-ZOnB2DyA99= zjAs~N*bA=SIM!IOH_4rtuFk8jNsl3W)}q{Ie6xA>9b-ORMzgjbd%NpuXFVqJLcGhi z=M9l{HjcT7j$EGTJSidBU-#7gqfd^c5ImWKS&hrm;?4NRw|@|eH?FTnXzFNWiVrdadR|FQ~`z?(#(xnd5Yp18UQ_-m=LZCFIf+mw&~RZo9@x@ z^-tsYU^})qpE`Y1b!Nc|Sc+B_f*s25v-Ax606NXtuxMSVKDUJ@DCT)TvN(JMV`n0P zjGP2>FPKD&HJ_)eb1_A_PRa2U_HUb+yBX!`vZLgj?hSe0%5fCpmo`XXFgWkE1Q%$x zs$>5o;Sj0(P|Rb{Ly6292qP#8N@yiU;bD5Vi;H^f?>)6LpMByua-y%sZQV<>2hp6Q zmt~Db8unWKD4slir04d9bCWT@u&iTA{g@SOQ~FuGKyNUL_GHl1If42I^VRJ*K? zpuMEzO9ljJr`B=3lQ`VpbjnA@jP#I2t%raI%4()9`%0Z(un!dxLK@Fe(%)*{seV#g zvPT&7enc?8JQu$cU2@tx;ljwM##{J~;jnk!7oDr7eVQCqBtF<9;`YRRlJz}NFU2w` zTdDI!x=w@*JY_&jY;@9i(?sUGXu`;NQSBkkS|;HGX&u$aE7}8|3wgQb%p=WX!IJF& zFcK2k1s_&Db`(jx3p~8)x7;u4N#}gp@1`9XWY8(t&_#rpXqY4fha&LJ!8?rg-~!H(WJ>iJ0oUq*G=i3TD} z(R?BL5*#7*FZ`5f?wnu>&0JewkAs6FM}6Bt0z;GLGY%%CsD;KsyFB*HKk*zC`#71< zCX8aVDOafa9P|mejg2B}Acv?O!cpcCN_uE4c#E-!IY;CosYsJS;8O3`xQljE7<-Q? z-Jm6c(U`{2bK1sko)MmniUwSC^tkYgQ)(ys@g;h3A)Hp5G#;4(sS%mS>>nn0kAi=i zZ<0fR2V+7c61WbJNYSd|>%#RyJ|h@nq@{0Ze^s1jFqn}JkTJzz$y~-^1Eb#9IBiV0 zdZ{{ElGli+C(?dXa@+RKR;;c)jo3cL(o;pF4G*`e);!hK+eTJ0m$k@&kGkjPUJdOJhPL zB>I!0jbEgWwJt~SXMBnidC4cxebETX#L#{8EEo-uVcCBYeGPJmrvqc8@kUO<=vA-P zR8QaiMUHd?s$d8`@qSmThlnX;I_3m65N;EguZu4NNicQNQN{PgA+-NK{3K-h(cW^T5`6Daj7Q z%tV~`+JJeevEVvzLB0SE&vaSCL-+G8#-7yGydU|W-{1!0n6+LITBRO{-XYuTQ9qyF zN6&@_zXxp?oO5~h<%I$=e8vGxeCwwiFF*VI@ZX@WPdh%VyzH6b@nsZ7{Mzt!U9QWY zQ6cT&sR%qmDvQRc%9NOd1Z|xUE#5FX-~~&>5Cl9ey3@i<)LzV;eGJ4fL}P435f?y6 zO3Ww`U>4OT#>f#6^eYye7jd+I5Ni(~$HRBukAuw}y$2!Vc_~+C;`@L37xB0M>2KpN ze()Euw8W;a65a=2WcRL=fKZ)JL zy*OpVR1^^sc6guRdVx_%V7)T2cZVxf*O+tJ1LqZu<9CKjozzE_jsICC+&f` zx(*edw^uvkLmRn3`}8c#8)zUrz-Uw2ml5Lxi|--xPJL99^emo8?A-=KP9g3HUJ`Qb z8I`5=b7=COXD4vkZN4)XI&G^oDUX9t=itkS{35$MsRMz|gxq|cXHI(lxPT9)= z4@_M$4@S9S`NQ>#cf)(dzZ{7`8>~3ecU@!g%Ays;)npk@?YtKI9WC71bLT`nuay?{ z;>qwm6lFx3Q5VJ>Qe)vz!h3K+BErXeEK#md77$&=Y8O6#9;B%AJ}%>=zhSSel9f3q zxKQG<7Z53*o_Um8nxWkTIJ&U-hOguNgvT)aJKc|Arclg9CO@Tm*!!XsqXUCRQXUTK z5`4xo1zjg%BdjRBQl0bji%}|~@Fp!Gjy5TM5^qONKpB^mixkNTeH3wAO$tnuX6!+P zvIICf%0y%3eTM`$+Q~-kD4o+@Mkr*O-rs_Bg!VpGb*G)P`0&HW@#|mzCLTW`60I3{ z7dPt1Hh_@oiRX)jqLqfU5&2`NNWzhav9ME)DkRbhW7pKww4-HsFP_=k+gpz4E9$w0 zg@t6`5)L(*4Y%Xgt=n<;?khHku@A(x@cuBNMcAx2;IF)5CJFe@(?SZlt z#R{AJqhLg_**ztdbzAtXv6mc$eGK_)bOibSOz%!c!jwiTXFMmBATn#hG3wPreQ*gh zm7J)9wik+1x}1y=-rFXVWK2BCF-kCxi9lgLu92~l+9ezoJW7+ZQJ%V~^~$X77nTSf z?!V;Ga=8){I-c!erDI&}&WvF=i0GU(J%63jjmWUwl^IeQ!HzqPND=(_>SC( zT#L~N#q-GcAo@|l>4W!v7ytav|1}zoUG=LYyxZ1i&(4EZ-fJu`&Pl;{6pfREsMilQ zHXZkoxz%cs-J+*{t6{uv40x1P_gI{XE}$Spxi3m(qxRwPq3TUz#J*}6W09{>Mq+FO zf0(b8>A5IQEolq{94)#~1hY>KxVo?P#o^I`U<|z@3Q2ttabXWRfgvM0~L7$%uxG&_2&`jVX~Gom%YgZ$;~*Asi88H15Egb;_A=C!?_(wIW&b*Yg-- z{e;G7Ip*f(Y@`K0W@lF-?^LcRt4Z4j4st*Ai4}=3Uauux8pccZLE$~gFeaSkn%>F1 zR(h*XL_V^1AWb~`CjnQkpZ98Uu>Vvzd==Bv^QO7bbG-a99%E#|xJ1+$_{v-&eHLq1 z*2oJBOEFXBIa1&i^(vIHYM<)I5XD|^I5n)Te(1Ef%-i|71>w(ZqLil|8Gf#xVYhUgXV_u{_wqgmUDr>pNr?ReMY z!91dE)W@2hv~r}0ZM9SCTO3&FyBe=g(O<@D75%mm?=W#$3eDV_*i>a6S$N~(b7YE5r+JXgSMy06=3Z&c76}zq3`1uO!A_KEsgnBJbLtj&R@pT%H0^xcUn4X=t z69Z9_8MXD`VAu41VR0dA`jUYPXA5Rc zUvp11_6(x|2Hw1IQ1B7n5EYtWMY(W2@T_E%W*#$U%uR4gZ9$gMZ>PEx?9b0mqH(-$ z8iMhQecwl*UBb&N8(c-h@@2ILX9m@A#TE(d4UPd^ypg%1@wUt+T1ERYuDcH1kKrCT z!NW0VkU|w0)2k%Ir3^Jhma;cv(rsM?>2xu4b%fLJzyEIh{`bEX-+VvbeUIIX9`kdP6!W}&lvQOF>$D|9O+0X z+Qy;Qt0~Y_mqKYw26>yXg?Z+5|jtBV%+#s3> zha6-~_FRX5lg1Dk2$`98q0@m^A_uc)XjOgT6FHf>;q`ncwc?>c4?ZGK5A}px$6=W`ptPqf=MQHy~01&DcIJIYmN#84{S`*`;Z-M%vHNEBqDDngB*L{k^VL9FUPfE zBsm?cn2;(XBf5gtgFy}!)KB{4qYEcWt>G=9}xLh zwBgZv-HR4r6eB{LwlPtA>KBe)v;sI&t(vR?d{!3WB}Vle*IfsN>l}J6F*@A`=d(AEp5*>inVGVQEP|^(5nNa}^JadS332eBt_w;I zmv3pIyS29+Pqv=Me*M7jX3=Zo9-q3M4S<0+%oo_R7nt)4(-!^Kpipt@2j2yA#8pRMBzYf53U9QV@`S(-4I>Xmrebn$Zp#Ptz zK+FF`%Gaf(sU7KmaRWGm`6V)nxRCf(#MERimX@cZGF|e%QdX+!5id{$bND+3p2TaD zY(caHDOBL4=6_mTrbT&ZVT=+X?E%FCnZkYv$Op-jGc9~EX2F9nir|sy6wTtd@FL#p zy_psk?KSJYak4DN@$4*EmZJVA^U*Cv#-@PCA?|&HE+dEFfb9~&0 zwe`(-@Zn~xuXW<^a9{VI=;(UPNr`ml_MNzK>rP-GA)O@qE|jOrmT?#xoim6VfH-@-I1ErJ3f08uM7*$7Xh=N```Yv;N6eKrDgA> zF-`Q2}}<(N?5ZLZZenW!Y1*7<+$Nyq{8((Khypa!S5uifqaH!tY^p2Iah$l%}LZ zW3L*NR6NHVOLH6}cFTB%kq3o5DH|)*dCd*x+#oZ8&rfRnlMxN$AqKHzOd1s&OS%Vx z9(V|jpU0cO`}_E(U;cNs`OL;HQdilKQd!V_nxn!`D~koUq;w>WSelotIKTnmf#D0; zHl-D$ZX!63{eDuMF~%5WFq#pC=e1Rzh_S5b*}V5{GE9U|7(2)FGx}W?3??-9RiFA! zpD^m~?(W3Jc|T_7P|D70zM)VimAU$;`8l_+9QpE++JaFP*s(@H_GWGljSm#T|LP*T zokkpKzM-IWv}0NHM&pWNkv0?E<~@tp%S^pC@_Ot9NBwL!54`>X{zMs))@=+!plJa2 zLsL@J*4TJbx)PFIQ;i+b0n5ubW97!}s7#T95T$- z$?FXEpCJ{y)5Ys~E4tMVV9ow{DB|HKUa#o<)d=h4mf)sw*Zg5Fk7wW;W%mi3ehxqI zge)CILkMQ{O=p_5!&rOzP~)8T@x#fG@nhdZ=nF4c+h zfxo^IQLH)X{Q`x@z#4i7Z!C*eU|7MqVdzM4srD0{$aNy$oSxRWP3vek2X&)E=m^F& zz5i6zipFRRFS~8w0rO-4To&ub0Y2$7&I}rB!-Dq;eq-WW7frznx+FZqILN&kL-wU2 zYO&vM=_h-K50t{jnIRp)ASgV!6tB^D8|qy*^$gy9)l=I}G)#J)M`)aIHAcY2;h1Pn z>b2}ExPP$c6mZKo?y0R9%T*sZO+Q8F+9yYjJjJ1AWoaehlde+}(I<=fzI8xOh6x) zx0~zh@#dRv#n$Gg=)zX~{&&BR2M<1sy}kX|+}QLd#v|SX4Vj*vwbKh3iK^n=lY$R> zHnEQ;as%`izHdjLOU+xHRK#midOyY+y-sr0P1$RpSAwHphh77NqtjuF{&OBVuv9L2 zKQ8ofoOilr%}wN!>8Xlfr@1OzVhobOMWZBHfOlaSLe`~T^fAaU$SQUA0#hBxRnRB) zL8R^QNn{)JUXG{}%%Pv{)*xC-{J(L6!Ao>T=e%F3`h^h@xraT&kk3em$Ztn)seRA} z`a6trBO?L@eo4Q%HZA#iX%H)*5Q zUsiFG)7MWapYN`(sw7x^_VLjIWxFwNGPfV)qIu0CFWE?+=O= zfXg>;#ozqm7x8l)H*VgPV8@;YVv?%Io+ECD7W85=sj%!$42O35mxPkE@ohRcEdI`a zoYz+vjL+$Q-!}Nq(OS=ne#4=L_gNqxTz}!igwsZ^!EfKj{nV}V)X6#hC${XPrNs*o zUaOnyv9CqRIi660qhGIgvUs#Wpsph5QFqGgOD`D<)uMw%Aon78Vi>!S;F1hX$@7Kx zV#GwS=6=S}W1{bv_W>P--OQpgWm(xCJG=3Rx(giTTn- z7W6b2(76fvPB=fFN)=K9NvJ@f$9qs7z}Okrp@H%8JbAM78>3eeJ|q~aEfyenzegJ( zK>~)(p#((WMZmvCPL%fFxUl^MSN`mg@#kCu}YYw-VH>+-MN z&QGoRWA9CdMR>roLnr!I7f~){daL;&N>I`YsU*{Rikr~2hLH*Xc0X^)CllUYa|~g5OLE`;gt%} zStt-kMpAUo@EWO#fFtq-p5UaCAq5Tw1Mi!rHo&9(i26T1&Un)2reJ&~xdvGid0s@srhf{P=Oa`_2O$tMTyBR&1_ois%DuQHxsx$NdA6{)cBgn6j4)A&^+edq}GHUr2RWs&wym$J_^VdvtMl;*Rxvx2o7hO$H>7m zGfTqHn=v)BqJEG{PP9n_r5Pr83!cxE`lDK3rN~f>B*1)THbr$6r_|07#+o&Qp5##* z)j5ZOVO(-@SM=r7_{iK!5t(UTGp?jzL&he>9D9*q;K4|pQY?yY=sGFj9OdEm0B{Vc zDvlZyZ7_Xn3U7{#$9b(g#-Kx{FHnV{aRHjAa~kWjF8yg6pGHLI={bfXqCZGg#<@rgRT;zsUs)6XkazQTw+ad7VA$xh}FmUHLl$#sxQE~BYfqp7;mN~XGMD}!kv=m zF;0l!D$!G?otAI|1!*NFD~pjY&e(B*v9=O?5@Q&283#X&f!an&PohgqThta(ly**Q zQLFF9$;qMKdu6!tCwQ51?3+>^m_z}kO-dQ~^F}$$w({<>C4QT2Ib#mXudB=E@`U2d! z#ydn&E=9Xe>uMwLp$}TW>;8+&w%!X2bxQXq9*&dBSj>vy{%@{*O&!X2pjHbr; z@R0PnXE9YKY9=c@CW=jSMR*U5jsB?C!=wpjE($QFbvVmtJhZ+gA{l1_>sZE%`Ya32 zo3Xq7I3~*z;%7_3IX#OpUAW0S?yCQc0mgSdpn9RD164 z`+`++R^UEIf~h{sGXoqM!YCco2aFjb9itdmPomX4_MGK95tTS8)a%>A_wCr<-`0ET z!Y5=Xj0{Aus&2P)EY30Rir13TwR={Jz1_#+MYY)4UNh~PoGb}0;>((^^bZ;Y{xFP0 zB-aiP;vawc%lNy$`}=tJz5DUo-@hFXB@-Oz{Fdg)?|%PIy!qCB@o>o%q9^rwJ)S;Y zizknss9g=!i~eC;@0p6Z*|}I;Sd5jG73-yzmsUiJ=OVAU4qay6Gbf-+%;AX=QOY>S zbS(4aB!3d2ljIqUNXV5L(|(@Ev75FNwL>PKWN1mUCI{m^IW;9dKP_05_3mlogq-oWT%Lsa`T>NW8+(Lti4yoaTpC2HvC_*m}{PN~g|FS-%-xHRPOJaG$vP+3Ot1CF{G$OrrB4ojrGNA@o#%JD zl*SYJ1bJMQ8c*!Z!uP>J8NvudJkRoe#+v)l2jXZ)`?KmB4i?8plJ6SgcY=)_<_C3f zeA&g_N?$*ve7?IrPZ{>((~d8ze6(J;z_sD)x?Gn((?Wz!yV({4=}3f00v3jpl+H!s z7Yk4XCX^Evd{d+kjEhA%48~r^{5H`?P)eV^UqTFN6L+_F;yt`+9zBiAGYPOS6w)WW z{>^X2&wu{&_{mRy8n3@O;9^1{b;2))9pJ!8uN)|8;Qh zkkR-e-}R|VeP6Pyr0?{F-`wxTf-j{u`HK#ngE9F>pT(8_1~;bLh)zqt*}to)h1vGO zUOd$TdhcjII$C5B?Il)dVGe-=xbiY!iGaW&ZphFHeP-iy_RE4{!l-%Oka?n@>+2mDz3}Fyon9CY z`f31c(J(3j8Nq^fQRoNlDYFQakl+Y6!H<3qAH6Qu<+}V?m#@(9^>4h#*Oyp^eB`Sv ze&ZKPc;k&*vAoP43KPDDQUOH{3V8Sr{O|%rgWd^$qPFC` zgW({h0A>M-yhH7F{IFbuvL$)UqLd~o2pNRBXaf6u!Rt6jJ&ErpB?gKGj3e-7qQT&O zC=D=Dz}u}LfM4rb-e)6=+D57^l;A0qoEBx`?YV#>0a_^()coVFYG z28OA#L44YyXb3S34vnZC?x(ht@D%1b6dh`h`yMtHgr1`f=~0wsDrz560ZKnS=36Jn z>H~^D!Nd)UlYzs-ak)cg@Ktp)lh8VxsAaKSTT+^jDm<(e4nf9WSSst z)4B1*d&sKejD^4$V}dot!Le+~>k*Xw2L}g+G4oz%p?a8$c;2^Fx8|$lMh&RibgsEW z+QuotgZ-mON5uoe2+6@H(Ah`n*T4FQV1KahfA72T>Z`BE)YNQ@d7cau-G+_+F>l5M zDIJ~i9b_Y_46{-G=c=EXwU?eNXGxIiPjpwR{3%H2l^i=Z`V>J;3 z;3`ocI53cYk5r8q{E8D9D|~T?U=2jd#FP4waUMFGnIK(k*+xG0Mrvy=x0)yVY|$mP z4X4s%G;TK!qjR$FsH0JhEf8UzXGA|TS<-*0-y?#7#y6|+CY>lL^lsn2tu`T26o*K zO{+}LM!qJcB-@e z^G=+#j~yv=ekK^PCe?d^oA>S0`+H}iS9*p$5y6EKqE1c2&O`&6y54cBS;i0IlCkrF z+NJRs&k%*CzKAY(?f_sz2Hd6Ij^+$TKX6R*7hFCAkB1JP%)^Y}IcD4|X#9yjbv^yF z=roSvU~eamg=a^HyQcYoSg#X3#2{2q8?yS1!aGI(I6@oMtHzv&$Z@ro=qG3d#!D3M zL_&h|7rj<&Z+)n45p6dUIiA&+V?4xo&3YK4gmoA?pT>(dJAGyRFsy1EL{o4i+1uTX z)u)f5b9y4U^rI=h$G%5SL8oVdmG}M=O*YTaXJ0(PFjT!veej}DuZia#i{_HnQ}at> zjB$|^uw;O#)oM;b2M(Y!aJotX27YtVYdSqE(Ne{HM)TlEbM>L~xp^DdFa{B+heM0?HRv-0Tj(FUGaFWfLquZ1!zz_2rylgX z^j8q?Gwv8vqL1ePniprx2_hDUvJJcr*(f8rQcU$sPnowdw~-qP?CCXGj+v@pqP8P% z@+>j~>5y?qDHIE_ytHK4k+vDQ;^^Zv%%W9HP3AMkSLy~%ypvC4V0bddy;igB^wH3I zWEvv8Fg!s|Q-oA{sDajujvnInCUA~P3W44q(sJJ zZlG&KmWN&v@rTR`uXw#4>VXU%i18NzA@)Gm;OtIv8Nu!lIL7I_YDreOE)Cgi5Clp zFq9+X9v-nz>8|maHX^6E)lTpPZw%XRrPE(n^Z zBAzf3&N_&@#+j`Vut^*8J-l9(gHpc*u&7xfg4f<4&lLie~1 z8alX#&*a_5N&OuB5p~2_8@vWwiTctX=lS1X{G_Ym&ll4*9&<@AOy704f9ZJ^t=vlc zP^_gZD&lE<37I`Du1`8A@pNk=R<-EbJ=#k~FTIoNc-SE*QZ?;FXeFc_&l5*+X$)Z0 zB?&=nbPU`rDCrp(xx>754+|6az2bWE+Cdmk=>q8{OcZ4sJ;1O?pB>$$g$lwJ(P1bH zST)-#NS#91VE=)hggf40qbFl8e88It0g?BBBa92r1Q1Jxhx#W;uu5JKP36Nm6`ge(@dEaV-jrg~`y!UKgq5u(pI1R3y?y-vuBjPOU@ zj1B_pU9QWYVfi;Td?f|o=QzHk@@#?jiDkggR6hIOude*DZF&A!S~TJ? zF+X38Z+`2p7W$;$!f`~hi*AH}@CVOA!9xmP_!ygU!>eta(Y54(+P4t`zJpw2rMd2< zo!kpw#xcaQj`*q<@Zvd^Q3eZd?!81|D}Koy6evD{KT%02<58^Rz>@f@?iIg68Hlm~ z*^B52cqetUsHcA;S17lWp#jftc%4{ekba6(ZYia)T7PjCCyknwuJnfu%0~&|aY0eg ziM}H`F2zeRvJ}MYQBF#B=+vWodTN6W8_T26wW3_@LMe&T>++&wWu{Xcsn26$z?W-8 zmmvpA9_e+&XYt5w+8_o0M|PQ*s6?SO<9%R|zeo>8)kGGIWoFbC_F%&BK>ENG!GXfC zd)AJra>??=1+s`_0hBeQN;;4nwX?hBC=5Jx=Vq65ECh-zqAl2;1|x=0KytuHyz$2E z`1wzN6hHdW4`X?GQSfH}uePJbh}b%5u*v(OQzc1XM-4?z8Ol|bGbBssf|d3t zYEV8+;a#my(m5sXJn8p2A+MAx3go4@}}{Qckkx48e_+cuD)7+YSxWkr3y0F3dF z*BFi=+e`M6Y({EI3??@0owfvneZj3~#Uaruy3zQpht%2>F+l_bsjN_5l6q@`$TN*0 z%3#z7;0DoGw3$?F4SllzNqK5Um#G&8Rnho?=nE`U+Og!gfK!??r08S+qjAj% z_I1UmMEkS(VvtTSC;S>2O;Kq%QvRu5M1j&b=B{N*wTB253_C|aPSc!4 zDJi%Y1ti)?>8+Ln7kkyl9SSXt-?{J{U(BI_n_OAT^HndVOmT26H@T)nEw_qe1jUhF?NBz;bjp&}V_t}`ElIyiy<6^hl))8hiS0oPma`UX0Jl z@TUTw)tEDnod!|gMo1kP1&wbz&O`%5RD{EfC3wf0m#E`I!JB<8FFfzgI!zmR60gE& zBpQujPjv&UQn_k8fd@LZvBpEIQ{lA6lX)us%$SbAp!^>63zA_5at7xvdMB~7$$ph5 zqD#}}F{HpH%`3d8P@EB+Dcj)1T&6R~Cdeun=P{rbbx$r&)MQzFE@JiZho1jL$~=Df zP;+-(_$6p)9co#-)oLG>fa=xt6(qo}C?jYmEPr{O8cMDCZ` zhaSs%89@^n6=xuHPCj%UKAencI3y$IVdzd#R!NtnF=6j6{RTI1Y~dV{Ym6ZxGyDua zCG?lbdLrx@Hw<#L8$%rJ!x;$}lqcE8Go@Ulf9RfQFSMHXGgl}>IgNHDd7mSl=hHey z75}gA!{6NZV)6VM9E=O_rH}s2GaM>@O3%7}4*%3U1z-Ktd`bA=%tpHA6t?ZIBNbOy z*Cdl1ST~n+p{f31;rmD1^)D&Z>_hc_(xLx+yzJT+J^tA8FMXZ@He4INuFG}#b1$Ng z=VEG!nWb=Rggb~bNlnFoJ^Q#R(L z-z-ql+4M;neoqX{?8DCw%AhXq?Ukyq%&XJSuDJ{th<~LQ`g<~X4KDa19}-Y>*3ar6 zky1SgI44?UtZ#3|{fFKz=m>+g%96>s}(Xj5Fqf_BmA7a z)+nzK)({j^xV3~7EkL~R(>pLkVK5^FR6{~I0zYj*umg7xyuhcP`f*NMG0t_9aSFi< zL5}_+aM<{UN1&KILN;}?IHZp((8kpdr-`7wx*vF1QKp50z3e445C*Oa)p5bb*Adj! zb_sj*KN;UpBznlM%XPUfe}3hwGkpE!AEr9|D#^+hdRJl?e^$jDShSv~Bb3rNZ_Y<$ zngwp+p)4A`AcrUDZg>`{py0dki=h!K@xJ8Dfe?^9Rg*_4*Wpce#8DmoV{xzdCZm}p z6fXH*>K4P3sE~LMd-JeRx96+cQk|Z)!UZKNN+S3q#rzEqdDV?G3d%4l#i#}UL!oj~ zuSKiXP}_;HK*5;O$zTM!=#%n$9+VgKW6X{2InrZ& zZB_6%4Wem?_`-nTPO%i!2a0u+Zz$@mj2jtK+mO##sG~GMW|RDA1z9t;w>RS8U{8FP z=z+<|PE6|&j1vJPx)ed#g`CkN3wsYf1pm$^jRJ}cUV)nlWP z=XOCkIYQ}eg0T&1$gGLqeAJvwQGO?SUhSV1eGwdq z>_CBMTA=ZB8Z{f1FAb*)%`ud2vZjDuvG%jPtuacGr-Hu@3_4?D(B3oS zFNOuu4<$s(bl{q9*FoAsl+o=Lk%cIDX(L8D@R5TX^*?x>9n(B3T9J++j`x#N z6eErhWY7lPFZzTdCy_#V;Uw^dyt6KW)(%syVRUY54iXi`yk>45IHg<7^pE|oFxFBZ zkx1=kUBh}|0|N7hu>?uWQ|!^Gb+GEdaP#(?zjBnu{KCAASdNC`aDk@@j;&*jS558I zyb;o)h(FdEtlc^lt@(IkV6o@Jjc(LEbVZP=n7)>{})^LnRnK)B$2p>)pA4BnH5D7|~6 z-;A?PUHz|nPFClZ1REk&p&8jIFebu<$tlqu95oz)rE+yHen#59Bi{#JQeR#?4H`8f zxgbSHiq44#K(j{2#ecM(zq~jVpKLm6nn)&S2Y87ws(;b8As60>F$26y`}AFUte$G# zFjg3K0}iM;g->l+(Z;Ilr*&|~_dwju8j^}e~e9>4v~Z^WbbjQ@Gb3jKaE)XPh!G6FXvdkJ=3g#3Utk#AKR9sOVxnkx zcQT@s(_B7;x3UK+h6){mm>TN;(N`fmcn_vY4Du=EAMYaC3*L=m4KfD05bH$LHh3-u zDE0)yfrb9lZtHGDbJ4L7_TtK+xx|ouzP|8aJ*ueWLy_;DMLi z&vj%@j9SK3^%Fkkeb#h6;d_YoYn5%Ltpt0N~W>)4?c9b@0{kk z&kjq1NxF^>ZU7%$VZH#L;r-9*9TYq23BQO2=Q~rATX-#Psnr^>wze5t+q=TiM4O)L zML*h(FRy&Qy8ks>@Wo1k{pUMATHrp{hOg^#UH&~35mpvcM1OU~JTTZm#O%c)28_YM z3q27EggB>g@j_KhAHhnD*b9D9Xauw4!^3#z_ix7Ici)TFffko9l&qNSH^2Se_{A@N z7C-*UPvW&V-tcCX2nALch-n}zi!AATivBVK(cjR!T3`9ahYl7$oZvpXVzy*v!FQhX zJ)HG**QC01m6N`b>hN_wsRDUDfx!nqxz0nb*RM&n`#YD?hwtZmR|0MGv>iJKd+}s* zHTJcj1h%A=L=Z?}=IImTkiBmtAY-(m1{NF$C&1Kun5iU186LWjXuZW_rSZ@`c!VY4 zCOyxX*;`m}V`F0k4HzqsLs+6G+$v~zTnW+VKKhBVjCv8a`At2J>e9U!%MfT#=HazT z`X?6a_K?)Q2r(7_CD5_AS5CqUimS9}C4B>7?rJxTUiD*$!n*~5lm0oikLtK)GAp1`7}N>GtNWuaCFLL3VU9tO8)OMx8RTD)=10uZ3PF4yI{{JE8{ z%<%QYzx>O8bvgMNUwN^>;J(J?%k((>#3BL?zsP8zOlrgVx#_4*69Gk}H2id!QiTOK z2ClSt_5xIl10IaR2|kCM0q?bvLA(UTtUWHpQy2l1qfSMqPwH~ywB-@~GQS-#B6S=7 zlTw-yVa7(;$WCF!@9fN+j+DA=sL(*cgq-CCy4nmc#=wJdj`wmO)f0_YJ3fe06!BT2 zk7&zPv~@4_Bt>T0m+Y(qzfaNCC}d9>Cqddi8_WjJ_0HLEYA-f69!KZ2X>ZxGQ{Z6) z;htf?P)N~FReY7?kK~DtVi|b__KSf{upGfia}rzYtI=wm#>&cVd$^Beh*UrkirgZ3 zG9x(!T`o!u<8b|)z+ue%w^|g4q`qUoz`+HkaKi(B=+QGi5^Ye>w^Tyry#y7tc zw{G8y646PyVw5C@O;xJGLBUH6C3>TAQnNDHY1@d7iK51ZXqcoRqYoI?FcOizvRD*e zjANt$Z%K)mQY)c6XC7XjpQ+vIyYPfa6&qWGFWqiOeJ8RCr55rZ%6mGGY}u3CO4fp| z4x(n5XBb0?Dgej0k7HOyqkFm+AH4HV@!^BFEi0BZe&ehYKp~X(s+VYil(vw0k210p z`Qnu7F6%t)7tZRyV3f&75++ik+j9F0h2+%5^UNg_b{IxxXBI_Y7F0*kV~B@4PG5NJ z+wkTn$z+&7c?n$X%S1&Z_;;UkKAua$%gIEZjKTM9@J`p+RF~7(jpnbbxWfc+UDI8B46tGali5hXLZJ(z@Y$VJKd@_ z+F&L+$XF3ggkc}Y1Dpm^bRzq8Y0c3)iw*{;+M(Y`)Dv@q^$7e1gCmN1#<6k2{(dLw zkM6@br?~*HfVMyEmR^qmg>eJP1K1~@9LF8JH1wOtE>52+lbBehjA>Ppaz=O zA0NUWgg=5Uw2^mWJi^#(XHCJ8H4-kGMbS3qaZ|Kqq<<=?V{Bm!Cs=t=%K}Nfj3{0` zlP{3gk%-h$@e@*MLXK}Q@69@ad#sOgEG`Lr!PSm(N8cDQ8cxr>M za0@!lo@*twkJPiK7yZ$w5Mc+c)eWSJoSL4Cs_4gbbxAaf%r*&UodS_@)xfg8#Zc4{ zKS%apt&5(5O4-+`*=h-tBast6v;Ps1&bMyeQk^r#72st@3LHm7^DuZamlEznYv{4& zp!a{nILZ7KKi4~Wrc#}=b3~;w7t7+?i%Tmpzo>qQ&WvT!UXpGPc*6Vyrp#->drUNx zalkQxe)0Yg4aX>kQ5I*Hl+HA@r%^kJ)hBB-)=#aIq4+TY!=(F=nYhDP?`x_9rM;5r^_YwPjk$x|EEYW0TbN5|`Z zPdrq9N zJNDkOT~MkoEi#&!$@;n|ye)llKlF;C%qJxo#!PLOGOR6otYI!f8eGOC}gz+IkDD!u4I*l{Jz3V57U64J=SDtbw6u#;# z@UHeRWej-c=^rqGr+fPu6ZFuDWRg6%C?!QRdY*ZE^ypEZQFi1pQ+NG`Nllz0uLDI%*YyVlvavI1aOP+T1-Tl7Sdh)G5&sFQDe>aZx zU7o9ZlDg_^e^9)bdUtjYYkllyjtk+{iG}l|54XpoT{(7{e zRQ*4E{dJ`uE*F$sE55GNb^29F!SNT_q=^k&mWDwB6WJKdEzZ{l!A1^IL?9?G`o`|c zf~6RNm)W!(xAo`G+xNfoo%Y>7{l=eDdQHvDwXgiWzu*4xKmJGUzx;#WZ(sbv7s6;Q z_stSv6icik9yZ=VLIa|b(mP_RW`#1i*GW+B7P>`%q#~sVNB*lYhV?>EHlPTqvgD|@ zD{m)gRmau${-1mGRuQhs8LFi0`aZaokGku-d-;AI;=6mW*B-AuZ67}VxIMY@^rD2( zRE#aAh)_yQ=B^kb5<2XAbtjA0dV1hx63PF;#UBKjHHKNo zU|`}fY$Y_vd=lu`xZB(rBNjL;C-qes+HMTWx;^7j8DJbv(ZX_l&60u zVd}II++kX3KD5h5A$_)?!5|Ji*}9N3<13&ovza_Q~F!; z`1rfqZ@u+;`_h-*YOAYD*{o02Mp2%klc6DK z2@6Uk5jGdCbcF`m^b%4cA|-?!2^|jI!jIIs6O1R4oLAA$d7z{rlnSlNw^DB9UTvh) z9yA9pfWGn+sxzCybdt z2z|vHpuA8Rn+ZXeI-SwAv9Z>6cdyP<3tTdWdiwNfdzMRhC<0mconx`Odb@;{_wT>e zZrr}xW-_PhbecvYDf?v@e?h{SCjkySrX#ufAYuwXM6DRyQzye1AdZ+&{-hNT1vM3 zH!^1Z&15e1DQz90bW46f^oqwMp=^3RHk|p~Z;zjR92n_BN{J#BOo1`pK=X4e6|T#g zWa(eg3i2mR<;XbU`BW}pB(r{Und6Zm25I4Ct*gN6r^>vngO_K473X_h)OrJN_6K-q zg1~~o;0WG+?|k>$ZEJJ0-MF#ZmRD|skDbdHs;{+^tPi0ijkWbh@Y&DH6)U$k z9$50s1uv~G-%4MEhU^|dgs-nk?I z%m}@CE%8*M9Lmk`)C}W-H-igV?DIt8iM7AKS0VG~=bcNl+HqiTl)16L0FPjGXyCaQ zAfd?9Zh3@u6%G|%rl_ZooX$9mQk!^3LEn_8MHfB?k zv+ZDSx4n4rxNy1iy^J@(|6m^lpGc+T3=Zh$mQm);2Y22sFGFqTnTf8AkB_vMsq1NQ z_lF<6Q|ownc`>+svF6w%1lY=r9`cou!H{H*nQq1^kpJpH-1H4Mt{Wf^&pUEMtsLbBqx=#Qxr9 z(PGhN^vN1T^T$SC1vci}*wktp&$w2j)4z$SiS!FRp!HxP5CR$LXT}%J5H^z+lCdgf zKrV_dN>6JZ{DUv_zxajJF*kp|6kpC71sAh{)rr(=zbm}!Tws2BW+`iy;(Ijf@~{+= zFP=XQyp3HcH%E)EY==%60Wd`IDU={%9ylIOu+}K=DElc);C4y^p1)^-d28rp`o&X> zF#>N$^!7Zsfs(e4R!IBp!@B{CwFWk`H_y753@(^S`xz^sW6G}i2(QA!@jPW1PxN7Z z?M1D#9#$EzlT>rqVW)@HHO{$jeggaZTifmHU;k$N!$11><-KC>{_)2T+V{TqUSQ~P zd-m)_dGI`a{37GCmoW)_b-v~LdMT+0{zZfVW5!6h!rOOlr#+YL-FM%s^N$!BEG;b; zZYtatSc1z_ReozFI(iZK-)?Kd9PefAYhB8uNZZ=BZrAD@PoWJD4k#WEL*s<49T?VL z6u)`r&dt!=JAu`Hb{GTXu80~cqXW2*JjGn`A}_C{yvJY$jFqQW=pJ5!a+Bf-p1>!R zEF&;y0Q-7^FP+EL4WhhXGNben>`?9vco6d}FCIq-K~W4gHn!`$uAS}edWZ5aUurEV z&nNx@KP2t%hnG7P8AyMfr8`~OwQJK2J!v+`Qr-gd1s0#JA_0juhZ2}3n1db%z zp`^qwdoH{o1!DF2rSmWk+K#Z@ndjoE(?)!Vwa42NIO*@xr_aIzg@+A)B`KTN+@LSY zBR8tGp48iG?e_fx{@Zw)OYotO;L4@mLBhj#Llu{P^gj7f_fkjC-rpI#TOa=Oc}0i) z?&VzNskPF7m-no)>Ph&d+=B})&V>gKZrI){_{8fE%BZC!`_=CsPJ?_u>gpMO{3Xla z=TA;QU9P{b^ke(-GbT`St@yf5*XdU+1>v(a8X6sH^Gi$FJafypLFvR5dMQg+o4qiK zFGEON=ZNa_7wwyW{HN_ZfAY0=?a|BAhbeiSD&43l!B>l=f1z%_3s5$ zIsF_j-+QWe@?W*%)2yj)kRz#{_j?#+jLKG+&_`iv-~I5t_TXtYRp(*U@)R>dfKo!P zylPX8u|&*mpvxUQ%%u&hxj@7#R(9IUf*9w9*`X{n4?2vo(oX`ovP8}A62=_vmt~K5 z$r1}5^Jc8O)s0Xz*`%I@u}xi=1x!taVai;v_N6q#WKt>_pMgd7s7hiLMr*4E5|=JY;}?j}YUc-MYEbzWQ5VX>Y&vdK0RLSHb|_<0p7h75&V{ z)&{-G>jl>T=qCEz(5Mc)()pz` zzq(*zczB{s^Sqe7(MHFYOW2;?mC%Raeraj71c8Kz1Ys0t1VhfanVDToU(s{p;arEK z&`)jYg3ErDXsCa`5}5Urch2_OM<2ac!o2PYHB%l8!tAk#uk%X0?|hli^7Fd3*G^QIE6DM$JdY0Kae)en#lLdY1m?c@ZeaushGE&(DI23sJF>uLCL%Ucr zgBxY=nChW>cEj74^ULzOst|Q~r<4nUMP)glpF)IUfVKKmcsN2*o*xteuU_%|>k7M? z-?R-(&CM=^m&6mM&Bgngud|TO+hJgCH~h2lF2k*?MSL=^7BEAAXPs4jr8oq?#*v51aVbP7ZAXSW z%nG5#bI7_pJ9W-g#y8)~Ag;Wq=CXEOWAzSY=fIeYu+*N3CxCqh#nWYY?ez_3<8-e` zZ5C#2Wo0$_=Ck%D12c1NKHtF?9K^e0YHF_V3}rF{wKv{)v%UG|7u(%?_uJCqO4fvs zo{K4Cp%gN3lf3X8@1+b~;X&aE3Co=&M5zX64Ucv~J-89Qf>O^~dh+CP;p5x4@3qO` zDPDBeC#8jTsgGmw7p{O?GA7w)jE@nHjs%u?LogONOgjz=zTp?=cV%}|b1*USDSkE! z6Il-vQv;>sP}>jO*b@m)X)jY=f#*WWI!}x-C#AZzL(u}qWnE<*dX+w zd9{CskCgMw+6jEkr~lJ|uW{k^G6vQ|C{?XH9!~aryvKMHYD;;fQnbu0Un#iE&TZRV1yvb(M7VVnK_zBn7Ltw(~_Uh(le&J^58;|Yau#{7BgQADAOHG)Y0sWMYV(UrZE5vJn@)ex;4Fh$cZmJvbl ze#Tn)=)wsv#o#75J58%KvAIbp%QJUA<3C^P$vrr{yskp z&!4sZHT{^K9F2M-^o&Wu@T)M4gsaw6mSM_pXH^D*<$b$IyX6|>T1C!*+TJE`Qzc# zLnShHI4vb3Pxw;QhW1cAz@g6a;ypz%;u+dcHbcQewgCSM!Kr-4xif+1mlwe)SNxw; za+<(gg+`w4-sA9kDZ6qNl?dLUbfe7Uq4wf=aJevq8Dl)pdGM-n)_$@ed;~hs&lH_2 znp?WBy#$ zhTkr5Q3lfKa~>siC7LyFe88w@`rH*<)_Xlj!YlO8KJ9((e{@Plb^7L=y84(8E_Ifo zF!gz^uX!cyHP2b&;Wc@8dbKk2e}7^6iFtm)Ly!97!M7iC{ZK#ts@Knw{yNHl39l7j z*XcU_il)^&H{1QU-fAl$QaE*+Y++_t%9T}TmFJ`2L6OgYUf4_BXns zWsq!!|H(i7XYIfH7yqLD&hLD+-FfX^ZPaZf2XXg<@k3rZ0__QFlK;a<)gAYXP$4ad zRnirqNtUY=#wp+Zl+P>udy$$Du71^n&^8~H@&&@|<@oRFs(;#X^}pMSx+=T!=Svr} zVTE3{(`+W5udlavAAHarK6%*IcGla8O#+KQ1kHOHN1j-$3n}0*L7uaGvN6>b<6?|q z;<9FuFYmL4^&N9^aiuiUN`$=xVPQHCjt=uu51)bQn9PMKV9BUX8y?I_d1Zy!LtGJe z^$gl(BPc`wOBm%$X09;w6iJ=wagcQwlx+SnDndh1aFylERoxVA1V)%iGgi#yRaQxm`PsG*M$Co?96Rse(**ji({;K|e+Sdwy5b97`b(vvQGd1cSAX+|QWf;q zR@z^j{(?Rao}vY41PVLwz$SPh0DA4-?e=S5daKRNPK6!{`PHd0FXm(pZRo}zui9nk z2hU|Rrymp_TX0RKg_2975-!kIF#5ob^Kxp*@88=#~1)1LjER zr{hM!K(V3yV0cmoJan;lXxziJ>+xq~6Rzo0^`>=X}Z_%uIVOGydlX zq2;`@PI8|Dh@jd=K0MEuaB)|3I&Coa%9#uQ$QxvHbG==h9cBD^SoKg(#)5EzK%#h{ z)PH<((4Mb7Z7&M}vy27+u3{y(Yl$Ret9IwIRJ(34Mvb?gKGAUy8FWe+PBs>qr ziSW{dI0R}pZmzbeNg>Gkxo-N%!^C(|*5DuU-TDf4GccvN5IJG>#;pNCh&)!q*%mvQm_nmI1+odR4Uw_hsd%S)7Zu`=&eWfk0-cDWJ0|Ol5Wyb?=W0b8GHm@sDE>91du#r5h zdMLK87%|qoGANPub~jV+%kZDPAD7am?$xC&cyDXb+?gkeYD!IO#5@Q^-p@5kmUf)- z4%_+hUfbDPZyRYduRI~N@R>p&js#EOea}wzYku(I`q9TNSL(hv-w$8STQmEy8#n6Q z7#8<%9B;|qLN z&i1puC)$!QcC)KBrq)#n`h$b4ZDpbZl&9qxa(0omGt+M0daX?_+)BAK!GDKsYhx{C zQ^t%2r=6B34kb4sH-!OwXWqa>g_F%1bhZ|S(9p<2@YhP4nH7meon0a5+$6KcOK4&W zuAvOdo~rP}&9=CDr;Sc#>?h_@o;_S(acsCPt=?)kZoS^-7H+4!`K)JN55e=PUcEv+ z0OCL$zfukz?QaAoGq!EPPwjJW*gw`8U4b|CGyI&G6oS$GrpbYu z%ZsDn=+KI^`66&|m~~2&Elgu6s)oTzYp20q##@-)vB`{ca8ak5xq^`F`Q@+iw?31G zgHsk3GfopXvu@K?!vEm43VjJkGvc+^EZFr9`k3E!p`F12$6M{+{OkXv{lEVE|7ZF? z-oEtZue3XN@3$$+zsy??rLB z`Nh@RuTx@CLd`8Kx9Pc?fuZ^Ip?gSn+z3JfH7|Sl7b){F?>u|@puPM3?-eZExpljg z7LOKhhIBBX5f>xmV4&cjF$oItIWGO zOyV764B&s`X)XC~-s-&bw3T7i;sOH!^lz$gPkG0N#-kz1u28pl#lRKW3EXfP9)dTS zbH#X8F`~g&F#d%*JI$d??K~i*77)W1l`JM>rT;wP;8y3#QpS<549>@*_!4>*-lzQ3 zcXE_c=7o>Nhrj{g06xZ(PZ{} z=^4f~yxkT8mrLzt=$H_Yj8yQj@C;*~6^hN|uaJXTQ~In-UUHOe)=}}esZYK5rR}Yq zjNxG!K;fCu7VU$J@HoZ?zi!TWg5d-G2CHOe#mnR>ql)C!U&}!rurN?^!RJ2zT&n#` zs9`?6Q%2an*P7}ytEXO1EnemMR-gI1f|0=|nxZ}CzPxPFfaH6bwZ#i@GkqTHUle&& zYNcfP^u`Ze{f++f&!r!Ev!_83{;T?aPBW}ES(cb&s_uGfxd$(;q zUoVSI3FGqC7rxMb@4xu{_TT=Cf6;#TcYe2A(uH-P;Bc5J1dkaQAfb*z{f4UZnP;D- zesAzGNPZU5&llx%!jtcx$wypAR#PTIn|j3-yYUSLk1Vt(>2t0m)7OhVq%CYyQfH8%REPvUrY1z#Bb)Qgcb517e? zFx9hR#HcU#4-V3&4!c!(B_mU#bDgf!b^5!J{#F%Vg*hPIpI7>M*7b8v16p3jEBTjg zYA*B!y*p}ibCd1Xt)i|ZT8duPc~BmpfuTt@%IF>IUNowN zczG5wkqtNnK{m~KhcO7HmprWbOQCi}%PBtyjnOwWlJEn4a=$CIgsB>@KG?*2*KbA_ zyeOVLeNuv7f&!a&{Y7s_oO^?Y=dFPf4E?nCWx4B&gQL(bN{P7zXI{;vOcu@~p=AW` zPfIW$X~Srqp^217CrA6a8~$TzCjIPZ!c645uykmo4Zm^7N0PB5c=P^9yF5Q?=coG_ z?`~8=LB<1zw+Q1X$`PIsqZ7;NuJfY^0SS=_L5E6EIW{I#SPzTU&zk6h?w+pdq8OQ& zZPQZ(U3+bOa;6j&`v=DNqRKHg<>AhQ;)DXzn4h-Yz5NPT#7m2yke3#~Agm>!%`pctd*>hnHU!X1i2?Ipm%KT+rinKjgU_&16(N=WS^tRpbvLC4br-&p5o zB)72^+KD&NlzPH%@iM2E4Cc z9=82mo(~5Fn^S=wdk@A`U>Cd-?6W|>apP{gcQ5mwvMF#U!^awHR{Pehs0*c_$#_vz z;6o|>gondJCQEO7%BCRQ+*m8G4xuWcBWH7Ur4!{4<)rZ3X-D4S4F>LcqZ}Trx9@!G zPb(xGcwzZo=agm6trvZ~&AnMF8?aqK@on`QyAN4Y8y1Ws3f5s>E#~2W1XT8iVw&5`f7=6fm zTpTI%6a2_XU@YU-hIo+;XP)7j%e>pq1+?aNw|6q%+nK|?5(3X>O_ui^y!$eEX=gpK za8@{BWofncC4~4-o;+*MvX_Rt2)-$R;n>r&;Iw=PSaA42sWLwPD&xBs7<6R~M(|nsrVcP;{FHNX;he6%#>^)?O3BTW z%=59(f%2{l>{IZ8TXj3{jpCiMx0H7jzJW8N3#Sg5ha|WSp0-9x@mg6eR znY;(>B`;UM8pW2hhkJ`r%KCUyk7>`iSP^bvI2kxyk_>_Er?1N$kKDBOx3JSIuo@}NK z&M;*NY=Kkgpcj-Lj~+hm3XtvHQl#YAUQt9CPPSz20b3v+XAaY0DZJMHG`YQZmh$&0L?uXw2NEq;g6 zn-`qpI`k2Ly>;d3CCQK9vKA=lN^z8X;9nmGVHv%r{BA6s<&b;w`m`qSbN%Wo1WnWT zL4v0~o2MsVuHLC-xO&#}_DnrrFn6`78{O5j&_c@hGsAK-fp+= z-wi>TECw2*BMp>a;!6t=vA4C=zW2>uZQ=kcGY3PbtC^P?~`Az+RHG*K6$~NWJB*fucyzS zwvQe?XfHO`+Hn~3^DwOE*)({UKn{bTyQNsV5}xQe!GcY{c4DG6qXa40w3cut<9~WA z+!DruqKg%34}U_yMj&8=Qyx$GE320<6z0l3f*o!Bl*miQHf(vACsMQ$SY%%M#wyQp zuM_OFCVjMd!hjHvNCgAw55@)4;@trw!HO0GrjFWRPT7dtSP}TKs3+{|3Nu0j<7BSY z(JhC^iV-&Ym@|SVR%SLR1%JjQV~9!aUS55?Oq+4EF(>>iW;taTQv$NCFdHsG4`GTi z0fS|+nD@@ZxE&rJx69Lk@@tSfV|Sgd({=hgk^Xi)zCIx+zdGrs>T)N@f5|kU!J%8P zT%9%%gpZ6~hPI$VL)oy8wYhocM~)V4uyO3l2|~|q)hVo%CJ@pS0xOvE0iEz3I$<-; zD~9k4?eh+ypfYX32?EeF^o;;|pxnZz5K<82pg#oMz7vF&_x5<-oOiD+RfjIscnBeN zS{BmIIwHVj1cEkd2dh|C>G&_3c$ac1Ixs=nOBsW&5Tc3FfUs?3__Xb8K5LI2epG_2 zj93X_g?~!(8qX=-Jf%oWe`=J|Fn!i6{Y3vM1RRF1{B9}Vg`*c2ln|St%Y^-eY}3im z1$P7^&T-;tAxu^YInAH)hY1Pubz~;rr&4a_hG$xp!3c-v93I2i=nLALwxld{TKK2c zo3Dq*bOs4Q^sI&zUvzY|m-c4<@JP8>HzC@ccU&0>hv$J@ z-uYMr|LVPY^G;h>q#zI~EPW3Q@J1BUk1wgu*ghc0S<36m(USj`LPZTyBud09-i zSAi{IiMpZEW${&nd*fpnpHhDDTocM^tMSq+?+Uyk?~SYnLU;Bk7(6+6aIO!} z6?|r$OBdc-7)6Q!;mdB{eyvRlOE*Lr9Jn7cH!o^!lG_6)Lc3>AK5qZx|M1_pKlzjY z)ZTpSt@he$_Y0R0f@!jKPr>7?E1sWS`63J>tNzUA`9b*Bf9(;{7hzNhSqVdVql}C#r)~2ESHj7`t)*c8`!T6x2y zUoV48MC-_WfQ6CK<+OF6#McP>ovgF;mxmRYVW_vgvC(#RCqV_6;Q*(n(vHB`P}+TPC~C%0@=vs>bW&Kxjg4o4dEu?Pf`u}w6wjGA@OE*s-9C8t zyX~V7z8ji$l77vmuRL>hODP98)mdbjv+5t?5Np4@3WaJ+S-C%CzcrjSoIY=@J#9|| ze{g9jy)&n1i1iKjfrovUJ(qBcPoF*tE!YiQ1$WL1u{fXdjbS&y2qXnwgCjC8&YjM1 z2V%0=aTKF>UZJH{COOrpwA$|AUqfg%q!#u=eKSIW6kD18EJXh-Ixl&;ol=;TCK zu1`%7ppORktY_>W2Z!zj4)klhjn6D*T!IU;W+=UTy#-up-(}X6bsO4yew6qa^$IgLm5h@xTAe_WaqS_WOVEyX`lA<2MQ? zOom_3{tCgE`gV7p2XF2Nw}+-?9r1R}4!MmA!PzK$gF8#65c&jXW*xyXl%xdwN5Sa>W9BY-gZjb(gMj2mo?d-^Z`)~hk```Yze-)TK&bt%s#q;&{Cx7;} z_RVj7rxZ8tKX~}0eel79_WZ?0>bWRm3+ocRJBx5GG!A`IKd(fJm*wT9QX(;S-QPQ? zd51p8GvHA5!#@-?_WjC3-_pQ*r;wV+Se&PCyTN~y|BQn1c%y~;!4LW@dpCAvEKBBs z=fh8R5AA^xMEwIr4m4wI7($@qMfbudYR}Tre1+rV(Z~p4C4J$kL{TMtAJ4M)-g`gm z=2?HHJkZmKiPX7EDje83Lhj$f{G)Ash0 ze<=LOLinAf;$5s$?KBQx#@LuAV*}54SHIPTcP^z=KKuN2`4!%qGOlO~xJ%uh)%*v> z%z2k7dZ+XKMenLt`M-l>-7DFbfv-FL8vK=vGFN@3{`&sOXQ!c^M`S#fPjy_qQ>ohj zX*p#$k}UQI@M@iZmcNeEM%()OW}Sz3A`EvjhTW<1K6`yq){ndV{m{Mq_vh~YxvRJ2 zCnQgQa*n@D`jKt;DXzat`r$H+_O;^cI$ftce*IhRcY^WOTG1J{Z)r&h^5jc<-1x&pSIm>0M4?h zIn8Ag!&1-Y&;|k{))h!S3F0a5Jy%u2y~g0wKl7>Vjfo-1?OA-rKYFcjLxGFKjT843qI*MXtQ zBfm`p%O4C)N~w0s&#H>`nQ$@QrMx1rJ570qEW*OPXsfvIioQ{TlaOi>rilu!{vkODD)#Vn_6;SfDf#WmhGpbm;AXi|m^C5D%^ zcZD6voDwiyoOMNSPi7wATmi;)x=z>W7didh6kosl+dnGQVW$+oDye!4;r|V#PL;3z z&Msb&s6zU}ICMU&u0+!55{RDQoZ&oOR(DWx&Kl+Mn^P z9+XlHuh{1(E$?HU_qw21!lRtG^Y8+Mh-iB%YePaIQh>ZVEde#}f??-J)!2AntA^SH zf$+>qo0wW{3(Gh9c}F~Qa+Pp7`SoFaW2-zU@H_I5166oSEn$sfDr{N!^RNk2eah8Q9v}+YVgp7pzVbQjQU-dJmsR z@s%|aewV^3AeuU+T6s*3%;o+>=3=reR&OnZ8GCqiAqJ?jwu&}V|_A!i7s-;+~m*PQc*n*p|Ou?I9)6#CAH6H<=C z#97Doggv~b`WXgfk2DedI7T5$0oMwbjg1E;oB2=|n7yp=+S%U9T3;{4DQ~ellP2@r z74sAghi!M;{GX(*%%Q$!AYNU<$HLTS&syH7;08`QO@EJSj+||lit;?|OFRAMfu&E* z;32%WwkWk;tgjXRg%iN`NN}d}^(q{F@W|52QoH~9>+R0nyBVjU_Vmf4w!ZnIa4kAS z84RxN74^~h4rdP}oaW)-UPV)JE)rz`ZxTw*8#nK?*~Q!Wp0z#N_eR~b3w#d+|LnGd zz0GtsaK$q-{pF?j@X>=jZ*67eMuo|vcmh85cjyP)1J`I1`b0s+LvkcEg95sHTo@}t z-_%y{I$C?HgT2t8bKxWR+w5I5^k~S`6+PPd@Nc%2F^QC1c>D4Kc0>pOH1xcfBv$```a=`~LU7)xPqTUvGc^ z@Ben@9&MgZT|)QE!+Y8JQjCaS1)m84Io{4syHN+aU-FC4(aV#=%EMrT@ym-BPrGpd z<-+Dpd;0WAoh4V}m~~rc$T6l!yI%$G>Dy>ARrBmVyzW!Isg-;-pp&YZu%lkL@?CH~| z8UGhq3qmNKlwymgS9x}&z3$`tb_0K%|GNs&oY}#5^7^Of!SmHvEw5DH^}+jim9^lH z&CQMaO%CHt>(BhdQAZgQZ6KFpa6`ewyNc|@7%*VaW}a{r4z}8GS^X>?HDxhu-q{uc zv_Ershd~QC!QY@|cxGc!cqwZKp4E2BGvNt4ji)rbT2tw%d4|8L%zSq-DylHhb8~Gv zb7K8_$DEWrD!9RS_j+48?Gr`Fx+i1O2Jphmt;1SqUG8;dQgB1w!ON5R7>gSBbfRQ( zxe6!h)F&zHFuzN&1|ss=e|KD?Z?f0D)G>JW>E-#S@6=_c^AD|(+=ILFp;aQXO)(x1!oQ@r#SXOZKlsr_#@eRdrGstL8YR(xHj z>+~y@#%HJ7Yj1z9-M)XnO=r{gst|j(YJ-HwLL^>g^S}0Dt$pv?-)`@J^E>U}`A!?o z=J(gW{Oj!>{=mOEF!!LZ{^F_dI$c0<+SBNQ}jJM&+jxuwaCD1VJ;+AW>-T{LMV&}fx*Gy zevO7h!3h(1+hInESf@<{R2TwHq8u8W3r1Ol2~sB^i|#61KGvlD{4GolVH}19Bi|Vb znbc7(@feBBbqUtO6kxDy=!-c>kv5av%d8)CeUaaUb~U!FRq`GtOC1Cfl73NsnOjz? zUHQ~KwUmq9r`$Wv21?&3;Rdezm^vY-F4I@^9-~u?a^52pF-A43DU5fW@gOwh`K4Vo zjmhf_51XeRDkk}ox5hH#YmP85HkcSO%((WP9kHzXY%&6${k%@s={o%ark|hU>#JY= zx$w#G+~0Pp7W@sjqZi-n@P8R}lt2m|x9Q6!KD@@AyDRM<{J~e-7r*qm;PuvcKQNF$ z6KslkfGDi!VsJgWfkxO6cl7O9=NoJ=OW=ma)uxiCw9q&dL7~M(2MGsyNF00sfhcbS z8-DHbp3QY{Cn055s_759N(n+B;~;egAm}+B0Bs#ur`9%aKEVr9?@M~XaE30?Q>w^%B_n7wHx%XyUSbjZpjSy-seB0BuyS>p?Z`^F- zGk4OLxzx!bmv!%z_w*>`2T!f=5oLMW+cK0k_N`&Y$jA(J@AL8`C?PyyjKL*XBNQf- z$e1X!gpv3^;dj!Xj2}VCkaJSXf*sFd3|Xo_Zzo6Fq2Uy4>NBq0`nwBk`&C{;DV7qb zlqP8(q2GfCkK0McY-wqwgfJ_sH`?k|$fg@NZ>6ncCE~h$=T7^zU;mBvT6o<%ckb5N zG%WAU)7I8{#!;B+v^{Ww-ytZ%+wiQLpI>YfTZ0H2v*+0DbK3-Zd4=)##?yN!p4uwt4)SX*JXu7oOtu7qSltj*0i z3xkk-D&vrR;d2O7OKCeoQM1sNmmMlUS3DL)2l##Q;#n!3N*IVw58u=U<1gFAnGlg+ zoZ^R9m{3#rqnY&6y!AQHtIaW9+C-T~!BU~!gt=@J>3h~q*6dLD-_EOAd-%@F@Yk&O zH`?(rkEo?KcBQ;EKNJuZx^sH5O-wpNMaUNv{&2W;5iq(jLo ztk_22>mYEN@qm~MU!)>=f)kv>xW2j7o@M{IANbxsAe`OIJK@ib74N5E9z*shaMDS@ zgm5>vs=)r9WjX}Q0j zeRbNra^qIPe$fbR&fj1SIxCJYgBQoW*Y3B4C1-Lo{BVYGaMXN$k7OMN7W+I}sF|En z(pp_i&#nZ+Kj|T3*2yp&de$ofY1pOr=Bz7w|lM>|J5twwgT|X0Z zpb+fdXkFRLbFR}1^ta#V;dOYp(_TD#S_(no7=8=98QNFl zojkjts~>#uz2L01!h5`a7==`b#;dwtW-Jf(*8_hU?cm;kPH^AL^z*nB?9)@@?GOIo z{}Q_M`HTTCP5t8`#OuzUm$&Y4;f3!y2b={HZ@?pXtd zc?>f;efaP}@d`XE8Ao(aadTnpx;$ZbYoopY{=4nncfa4h_r34s`v)20m*Ej^2mj8e z{NbW+=oq-3b$+LEa=-TIp@G5|zW)0Cf^XA?PCA>5K?+=l7NTMM2S=rl+1}aBSf`HF z<>2%A@|s#)nhzeEEjZvAR%aSc!Fv?llfh>^l_^h8O1Wh3&SUAd`*%tywHP}1Vr{)W zf6j}LQ7?H!mt}wxyrlbNEj-fj1`LpR65-PrV^EBAevm?KJoIKdZJKVkZr*6~q2)q0 zQZ6M+@uheL3Ui)lcW&P)9${^b$7j|wJ})>s-Ao!T9!}dUY-tkQ)D0%O;;9sqkZ|&o z!<3;?_(sZRWtm5OrFT}!GpvUXr079g&`>xAU1X@kh&cdQhBQ2@baEqn4c<$C8S#Jt z##sajK~$+9jDG+C zr6yX$*h@W%sPn~=zk8^4k2>>0Imv60JPV(3d=-|`H3;oU9z!t*W*p&x@9Ofd-Yzi1 zI2+u7k&=s5ySp6i)8B?6pSiTRiMPm zuqdl|Wn5i#`>L#5gZJtR45-UXczp`z=g-#*?~;k?OO;nSKD~aL^yl*Z6fahmLA!s< zmH+<2Jb%;IXVZ^*{-drRPAL4f;_EtHr(dNMT)TKo-V0I2EC#{A z;VH*oiXi^ze}#B_A~#9-Z-9&Zre`Vyl|K(Ceu%+-AX6@M;AJxR_~t!tRn&j=cl~+f zr}umtl;i85*sHwtDW7|3zp~x1QQ6N1Z!HYO<7bcC!^aQXljqOc&OtWen4ILl$c7#x zfPmRV3kz7n2C>FNRWS?>7Z>sm0mtyD^Eixxur>rA2p}c_GfWWHz0&%5A}q~qD$A-x z|5GN0u7ps^PniT58eU;P!hB%zJu4Ufymt|%f;F>torj>FlyXfdjFIYtO+d|0@~Rh; zfq~V3N-|6thDQEUj-@|b)NP0`AU(WEw|*Wl2o#{=T+5HS7|N$4#2^6%VWKMM12@{> zJq(huG|vQ+eRGg;9Zw&_)D9RLpZe2<3)ukV&%LsoPkzjk`CwI~?gE{(BIQ>drM#kIp+;SV6xDj5$nKiSaix+uz z+Gc0wLx-JNGoSJ)AZEfFoY(W&yfa$i&TRFJt+C+o;f#gPTCZoIUg8}X#PpwCi6tzg za6{pH@DUe61sdU3?ffKtKRn1dpr41KnCZLuD1}wVn80%^Z66KIEn(q6$Z5k*@Uc~b zU_w;h86|*u#oAvUjTkiKGLJfarno5sD?-ckg=KQ_A7cc5-3tmYQHr#TIX>mhH{Wb; zfBy3of}3)T0trv`{Q1+ivAJG(2~>D>6)!iI-*fXN{KGHcDVzhQ*FyU!pMVCyjZgBD zpRW4@t9A2kZnc~jB7?0GB=SB9Psq~{%tyUKlv4~kD$54$-N-e#en;g$Lc=)k>DN`zH}*5#?6xwIoN3{H)?wKh7gKSBqZhwzqx>Ctf^@6;WBbx2eLg39oG1uL$s-_pi_t$feg z>K=%JuhiWcd+Xg=56qN+KF^D9zpOQTnDuLn;0~}4Z-`E_p7HcD?Ud6bLWdRMrRq@V$F?OR$SK zRp&q$NFh$wZXQZlpSJQu+0TXlruYCKUAa8cjtCU?nJ?Z;6XA$$DT4^_Lz24>)Zr2*2 z;9g7rcd~|hSg!23vkuSBLOarTA_Ze>&%|l+QzO(|Mgo1t*|kg!x6+ zGA5KuqZ14Zz!n9ay_CIGBrK{LKe>x#$Ua>)vZTfYD=cy%;=v=kC4C z!A(O@FklT#OsG?c()0)XRNdNp8Cc%Y^Q=#BGnMj=11nDpf58Xpe|ZV^Cag&sVaQd58T#A3*@ zpNlu2z4x0~EilNcRhvfqyTx_K*jZ!~x(bDA+?Kmi7LBJnU~I75M9 z55K!Br0r!Xt?)aPAUnC&y`Z*BIfbtAqWawDUat^>Q@pv8Ut1}doKwb&+HcBVIEdFW zk4au^3`@`sim&OJ?h!_D^YO+b4XqG8i~qRNvr@qD?6q&Y*bt{M&CAt#_u^;4I0a`I*mBu%u41AFvuIsr6X~ zPPymVLV1jbe+%w_-<^R~=UAnmIAXY!?1IPo>-X>H^KQF&^G4`HH!Oz>@q~=OI`5Np z8@RAO@eOb_kGgI=;rzHBLR7t!+~>hjFP^WJK|8q#yot`0(Q|MQBWQ}k+qZ58xAoA3 zc=K+^{i&TmsMWgvP-J_NSsX6FMd<2CM#hJ>3|?p|=Kt1GVNYJEI;`mDyEp+XOJ z*e~P7pc`M{6CMPI#S`UT=NIrM_~U*Qi21jit#t`Z6rlM3il;J%oo3*HeOxJ@a`pFp z&jXhF^}H7`*e?`6SMLt4D!s1Hey=oW$5q*b&%#|*R)3zJRaP`jXw0WipJ%_}9Mw-@ z#(RTe|1#;%z4B9(@fT;24(dK^{*9Q*XcU_3Z?P6iFWgi*V^4MBgddiWh=ciDE@v6S7Hn`0zWeSw?VS(bZR^{c?Ig@N zMU-=_m_G{lfjR1N_9?f9v*F0*Cj?wstj(sg@x&C2r7f&;cx18irV#5J#vaCnlFLSo zaDbJtd}rA_Ql?=fFv^HGp&G>-Mx^>$Opj79F?ybFVQvWR2v_=M^0Jg~m?KOr;ls;p zx*S%%pNkNuE0+3LVG1y5<{X1V(Is>V2EzC!XL4OBk&>6tr3+@#r+g>G!oWGaSKIaJ zEDWtfOO3A$>I7yWbB4(z?8MaZDyzQcI?Wgk1c=^YIY01F!yI9RT;|I8Yvrk!dN5L9 zaf$(c6=v6co6_3UrXHI)^@=U-j57VBFg)BpYR)5?ej!%K3C{(=p&wnV4Pm%A6kI$O zb}~*U=|5VizR>iGy|(emzP6iql(XSX&a(sDj{nLMN%(?MR^#6Pb$R}fl%5unRy}Hq3~Sa-~qH*{0Bt` zeuMId(2G!|&%s{ut(Wi+9Q6=D8L#je1bEK=FsCK3Nx3ZF@j>q4k9eVgLHrHa0x!Z; z@xm(QZJw3TzIZzd65sJs-FS#V&>UGc-sjmhIW-$t5vJ0)Ug6oYehQZJ4$py+iOe^} z(pdM}BIKW2yxC@RO^i+!@1s4GXS~ri)}LjZFDr!E!~|~*VW%m~E^2)a51qGz-4_`v zUSpeWb923vF6O(|3SKVlmig7o@V8lmylL>ggm1zI>L;NYBe_xSbCy#neh75IM^XvG z!N_R76KwajIuVh(BwL+8X6TY@91t=wsN{c~-SX->zjzh=a!_afmIvUK zu&+maNSlIl`nwcQ;Lmw~lpV(Qo*QeX9urv%d{sRJ(6x7xP^ z$Kv&k#l-YV#$_oN%l+V%tnKb;2VWBuXPh&Tud>bxR`T09ea`ZmoLNl&Z?&1Z)ixb? zV-P6+(&9?Wb^e(*r0f;&>#x$DjA0oHrqBJHGmT0;JdVQ0Q()Pr2+zoKYiDOYYiXx& zk+tJ2K!SKlR1LVPj5724=y0cPZal4dym{kZ)`SrMqwQdCziscpUlhI0nPNaNo-w85 zA8j-9*&|P`q+h(Rf{}v%otI}V2<670(C>qz?F_|53G^upCiQV7aFllOo_qTELEvVm z+6S(A8y_8PX0QDs^x?EkX1{bwv9{ZB&Ez!YyLAqC+i&itt^GVFN***QvsP=LG00h+ zuSJ0uT6RJy122Gmd$6&#yS3Kd%YOFpqbKc~U;lRd*Z=BYw~dYGZFwd2Or?zTraF8=0epw2dMs>v)6*o`ql!mGMY_cQZFrDOZ?U?>gt} z;_|o&oi~&@<%Q=g$X6E!p-Gz=N1-Yo)q50WJkgv*I6Ul}$R2iBeV^h9Wn=`vOU9uL zX7hc1aiQI~bvL+ay4r2Mpbb2RyP{em zmuqq1R>~gFy}rk$crC>~C2;UZUaWTTz_UhqL>^{toPTKVOg=D?H9j)!9H$;a4-Y}X zSzGQT^u~NqX3fs66b|6gE;*kO-5<+3#y8Y?jlrvUABxwx`Ha;{_wubZo4KR-*m&`@ zz5Cuf?Sl{B58MPNq~7Vg181nqIZ_8lq3QWFKeg`;uG`(-DJ8$(OUsLaq2Z#F_TfB` zgsbE!EgYY|pg+8io;`cf*4KD;g1zut;m6QR9%7EbAO|Rz3=TkpD36{$dtOR1N+4rM zK~-4FTxTrtJ~vjEO0nn6yREeC*|W7$s*xR(qANTI9<6xGyljl7LWfsZR?C1zIphbF z3nJ@KI#Dox$}3t!!X?kv+Qqx!=}OU?wLsx=+8Z1Zj=I_VvSseB8}2a zUFZ@#(P?^qCy_l&PEl6Q6fW0xio(PFgTTvCe#2k9qNXZL?ptrZSqkZH{FLWuxBP4A z_xjq})!0&iS_=%Qgs~0Wf~(+yuIT9sOnmEN(e}yUpOo=ptqdw=XQ$KW=~5KW&(CIF zMhZ9Gx}~p+sWbdf;Ko^CXkfaKGJBuQuW=}Yo%~iGYHbeCeszLve3ml&xN-AFz5npR z)ADYD^VNsebj1=`62)#0naKzZ9B4P5`m_8pMX|Hr;dP;KJp(!5%N)R;%Je=sR&UKs z5*YDZ@>$>O-_?Gh+A_F$Sv?Itd(zj>rv9_%F&4dC@4EsJ)h=!5_vHugN1?yZpREU` zdiYZEHK|H6=zoRu=id4$iusGP$dT)l@%Z_s!FYc+~y>ZoYP> zz4_%YmABV~jWxs&oPu~@26mlg_3%-9`2GiNJ4BM@)j#@&|ET@f|J6TlU;XW`w)?NK zz@9I`4uaA#X2?d6`|xOp%_qbnNGJaf&^R1kcdzpItK;^{Ke*hl5C8SlZ>Ky&DPN1p z2{TjPUxRmw(B>-wW5ZM_wdY^`@?SNkmr)8FeB0HZu!V=&JUm}}-adHvQTzDu$L*OA zG0t5`J!1qKth@3u%g?e>33G6nO(X$}dn`4iPSmm)$#YCJCRe@s%96u|+9rte{lKgZ7@<UQkD@UCT})7M~BWNDFC@n*XcU_;-|k|k1q)B?`Znr zP21mO8q|cA3{rj1KX}?WqE8e@QkehUrBk>l?tdmoKN}Xxv+CV|CI=d z2?bn+qn#fL@Ao|S4~yU6Ni#ee{^5AP?e1=*t%s>s-|#DWmNs^!-DT*rFg)5xurXPD zMV&#@(#OzGw7)AAY%3+a$f*+Y8N!?~9wMA?$8CRmtvQove0(HxJfHWvw-3cv7fd=| z$9b|ms|XguS7!W$(IWVy+?bl1YiCEh?cu`@s_o!{u&@lcGWM5&0q|AxlD2{qyb>W3 zUZcEy(jVXVc6a-^8CzRzL@OX<$X;B~flHp4&d29AcxLRx4d*3r)CQC^x@2@h1l=V=~LokuT0U3ed!FW|sD zDBqkIW8Q8&H%2ly6g|S85l9b@QZ!K}@;I1iH>717vYm1Jb1snn4Dds@8&u$w6nnN`1m$@=76kmNEjF#|o zbc}M60;q=rbuP}$TX)*x>b>%8agSl)&~SL~a|(9hF}r6_g-9F898WKlSJCLiT;?z3 zrG3t~Vf9W3*@fBo=x#Vi7|2Tq?ol4^6bejhiucLV^368CbT8%4t0ZkZs`iyjQ&P=e z>Nb`Hs4l`|FyA5YRg4ojP8p*-!e-LGnXHYO;JEH_1tGs!} z#wlKmL*{CTg423mZ{PdgH`_P9@s0N2;ltpK;IresHZwa_ILNtP6hY;&n0F3#)+>DG z>Df`>Xf|U#RC9T9yxTU`o-}8Z?eFck_4OBJAlMZki^&Ie;m_dY>`i&q5y&5vu>t(a zJ5ku%llJk04@-gL%rtv0N)~w9UMn3a7}WOtoxS$`ciwCN>R zsWwey49Djd+OSZJSr?bWfMyM%OLG~ci5X}6SYrSfZqrv|mcFK)m#6z}e}6l4=0(OU zls;gC7Cn8|z3pbE=R;T1kIX+s+tci`-+%8rZFBueK*AZG{XFXF3FouHWyU~V;Dzyu z-{7hiP<~Rrg;oVO+8$huQ~@w$Up`U?N#t=-U=oS&fcyyv$gpwFz<}F!@~Jf z@cRibLSB0}+rrA7tjpE(UARYZO!0elW!-iojkL-74oz}qopa6bEY6G)zV6YZhr#uM z_#3ueM3tq zmh%T6+`4_Uyp4EyQRdCePPcon-AkQQHKxw7GT!(sYtDrpP*yod)0vz?4c@M*;njq{~JM@QOm8ioRv+eP3N!DepAiw|K36i-cD6o^X%G&Ufv`!%%SHZOkLZr?y!uV9dQf$Id_8u5gTC2d`vY z81Xm@?ZXcqww-+9BhWW6iHD`|;_WQNp}si)^FR#0YD0PEmz;;Z2wpdjc&?KDq&;Mi z17%fDT>)oKwDptQNdtwf&uVxjVy>kC5!)Gp!`u9OwKYLY%ANgLtKFL#Q z@coA`DW8@1=bwJKPe1MTqf)TNwc_hKU8i4(6dW+UINRR-dtYvEed$XTx=(xiFx=_4j_O{qukR-?iWSo!@IWZ`=w~noW8blc1F%l!Xfm zuXh0x3%fym{aZ&s*wsPuu4iRcZ&Z=ssqvV9YOg7xrH&VHsyD} zC5QX{zaJ?3in#bsNvD^mZRcR8J$Uk_Blwaz@xDk*Ms+?aD@PSnlD_sg8?(p7aA%hUtnGqR(OiXQTCyaAH_`a-~ z(r2UY!r1E#W=Cv%eYG!@A2Wz?8=L{=U4jQns3NM#T~_v)FG`}CFI~$$!Zv-7U)voX zi&1mncyG5&ShliZs%-qdi&)p$Twy|NJoB~MY&vWxd;nUxm;tSrmPCsobiqpUTKnku#67tF506l!`&3o=&8jbqIntywxra5}+wEsOpsn5Nbs@Bg=NZou-q&;0-dC50rSy6bKE)U~ z59#tUWgPQ5BY;xQaS1;eo0Jf4Y`Bf4V?rz+9_^L@6t6)L$;PNsZw-q;i&b9k3w!oUfNu&FjZBitgv9|IC08ZR(H8LNq!n^)%YY`>izZj`|B z<>h&eU7c$)Mo`YPVW9XpN8f57twbux=D5JyfMRa-NGbxn?rf z1ZctuZfv{=ztF=L3R7f^N?;ZkAz&g@1BbV7-)<|bt5v>(>j}G9j^Da{tAta8R{gw- zuF&Kq#vn*Op7wYU$#_;SQ3Qc5izp)e@y#cmJ()fcO&yVoH<== zBa=cQE@eLFOMp)hJ0a9s;CVFp@%#((EA7Uu*W2>S-OTq~#sCb5FAF?SiX9zxLD|e) z7n+xs{xC~_Ro7zATxCsCzzn4gmnVVS{j70@Q@K@Rb{rVmY{&Z>?c~7uQ^E(nXpF)p zvj!*x#wHh%Z#MnEXfK{WDm>!;$T;s3aAaXAP~SU4N5OZnx7N0|)*5e0DdV%4cddJhLc-dWHnngkedpB#Ph{Tr zHq*zWyvI0DUcz(AXoB-A1ra{>3buuBVk!p+!GAP7@9p8lJM$(fb(Df5svKY#Wp z>zU9s>ufIY5XP@MfTM1zW4pSw^?(SRa5JPz_|8GSx4JD zd%-um1;@Od=H_@ijkTThWpD3A)^=z|#t$w4C%jmuoWsO3DC0m8L3zd#c5Zet{a(&I zP1M7mxKLcsb*QeiF1-^bz!Siehjv?Gn0F5lw!E|y z+$J<+=LrluqZfGM_;BY+nc0mXOW{;Xr?cuG9D)Y$QnP9@3jv;__#fM`1liVoUV-F zZFyFnsLtII+Mg1EqKX1u9~hwU`nhpqrLC+imICPBy*s%_A2l>L&tP^1s zdGwH>2)8Fxq2oBv+^zJ1oCLl`w^Cxp6WybH?Q$P<*;+@B4|r7_W{u{zHR|XDN?!Es zcKV~gywMmo@e;=;>~8aLC--37+`XsZC1rLG!pj;{eKf8E&m-~>5efQH99^!UUBa&l zeJac!;~01YT=K9|FD0QhN7;!MQOxTL8HT!y7cV+@7q7+|GpFXYM@*sIUuB?A_#QL{xe8;Q$-Hn60!2#Okd^t)pG9qJvCxIK4 zi5J4(XeapF-sS;|?-dT)`FlcluGMpMsEopYX*=aDJgC1#MFJNLti20Qnm=U^&OyUR zmy9cI=`tO2Z`AE0ltorW<_6|m9sbD62C}qnL=Jc5wIn-;{-uBGzdpU^d$A|EdVO7% z^l4_ifrq~L^jQxw?JWA1aRlp!&cWNFo_N?D5|4f0p@mVtxZgIrn?Y`c>ckG zkbCVj;l&V`N+pQu2vQy!(|YgfZvBsDT;&U!+cV{N{-IxWAuNhSSZ(qVF$4?YQg9JH zS><*4b3;-FCM3W6mH)J}GUqdWr?4S7*xcP}A3pl1efRzEwkK;(D>Pp*Fu{;QHxeum zrXkiC0)#p(3DM8?Y@85cJk?<^I#C|Zcov~kZ>s9nRNZ1)9}sNJiSS0Av)Vb%W|y*u z#U(+UP2qVM7Q|Xv6gU_V0xd$ii(HsB1H_`)#!GDb^6<(Z=0P|{Oo#F@1U9stQAoeS zWSpeVVtB$_c&>g7h%v_0U_^|+_D+pYRcK2GOfN1h7Lz;4q6x#64Z3_Msizp2z!D}8 zqh`1%)T{jJ_dOZVxU4%q|B4dA1fT-c%81(b^3))KR3nK@BH>} z|DEBJI|lp-=`YOilT*D8sV5ap{R@*kuKrGczhBHw(Cwn9p#k?_yV<_@1xhccZpjXed4PfrL- z+$UTtAuYi{l_B&O>s=lQR|nOjHK}_XT?$Qf{td$qv_%=h1FCy|u3K6QZ+CdOUu|)Q zlcZ1T_MS6WSg14DVDUaPJ0Jd`3)qygu&~lb!mI6WJ#CL4zh5+Nb@f)8D-Q~N&IE!-&t#0>kr%B_Ve_; zmDh@pR1{`}hFy3{(0Q2oS2k}aWw`H>`W#kRx1Ei&&3SNB#fR!&4^>C-yOi>$Y91bi zw_96#oPMV7nKyh1;RwD4kANqtxhlS9zJw}x7W@(+mvBHgR#|<|6@P=*z&GL{GVHY+ zdPru*O~4}XnX7oglmkx6`#t;=VI*Pw!oqUupDYiBm&pqTx{!%s5CKW}a!RrAUE1I| zA=mlKv)to}LNFaZFLOYEgny$T)`qc+C8Z=-FrKfnhAQlLF5k}si${msZF7@AJ-po{ zUo(p+0wSN6CuwYw5^S2dFQf}KfL02T+OEb z>Dh%VxS}kaNZXD|h&X+vq^pLP@&%j>lzv@6&ZF`C{4jGC-aU8aEb&r)zsk6t9PPE| zPad|XPal_Zm?sJEfLib2L$%+$!zJK$Y%FWO6geIDl#(dp*p;{)UN0~A+g9M6=g-XC zN*f(tP5XHfbsoRBLTdmLW4g?7_6qPJZ$JAFXG2lM3Cl-t$GeHb!@lTg+WUX}@BiQS zXJ7lX_WJ9ux3@q4#k83+SsT;=F5p*I`A7AAJaE_N+PWNSXUDs3XX8aXKG-V-AH^12 zb)NB>7^jR%-d93_?gq~L`A?&8?Jy5bd&1#%c_yS)x6rS?}6yRbFkiCJb&1Bwt`zudK3*fImD=* z*ILUut8=_=+^REgZmixYg{OVb`kL@<>$RUNp?Ug2NbGDIGzngwnF($;Kj|w4mo~V^ z>+JshH-j6TjkZ|(qqViHh0Vu-|GB`p@PgT^fVHe~{h12wf%hgSDQK74%F@kxe@v*w z;IG4st2H(iyf!(1yL$u9b&sC=_g`;c{`D`nx88ay^ag#KPQNHODBAnph~Y*leFC$s zfpv=P!?wHqBKt>16`4}FX0QeV(`bf-juxz>uQOSnb8|c_gJZLfC(yUhpM$-f^mVqq zcJE&3)>7d;q5gRpwV{q{DZe+jUgUGX%>+KjvS0gjU5jD@MlQ2nf^#MpgAdZ)Jg0P6 z%y<|#UU+C6k3p9+|3-&<7~{F%tErjL(UIk>O+>4xI!iF~o{G}NzGmRn zsvrKamJ7e8ytJqA5jqrH<=id(9vVX*DZM8%cOtY1H*Cya)))w3x4*m9UIh32+1LN9 z{m~!&QTxW%znS^p$o#!3rO$(pAGRk?UbMa4(7wadw!OXE);G2SZ`+MA$N4$qQS@rD z6s(j6&dU;3kP!zS170C~FXdkPJ|isP>Qa0C{@wPu&)pB4h32MD#&A4*L%NbY({=ur z^Q{PIwB;gr=w9aR&YiodEBuT#TchE^o4qW)haz$#u)n^(nKot~)7G{1^@5q$Wr=g5co_MtbNxcgtwqYIv(rv{c@~vYDBqQBT_6X_BsXA8 z<(#p_g}IE;d_L#fjletEiExcPykER<1{S68UddUE7XuRhzd8!O?BCQC`lLyaO6tmA>?2RC4(_~OtQ z^MOaI`tjYl$LMP*d=bM8eKQaJoKW(l9$83IcIRnCOTbH0##u+&&UpEv<{g~kztLL8 z^$f4O0`AIiJpCnC!_yfvGMh3=NW01qyxP^$7g3JzsB6pD}6>X#(G<_IhdXaxR8r zpVsH9XMgVci;_I%?}y*}p{wfr@z)Qxr6kYe4N>};_EtHr(gCIT(WR`wf*{U z|7Lsr?YBx{;rLA(9Eu1E1KwUcVUYH>vuOx}_?2J(O8dwE@E=!r!`pZ66cH~b5U+NH zK&s#?JVk&N`qRJH=is@^@1F8z<*Qp)kNe%L`&X2NRa}u=1S}t2;gvh7C_nofY0SXF zMtjgwtalYze7JksEU&ke(aX8WMwjK+i){El{P@H6{g2;mTVXu2zYFnYRo(>_$=&l~ zvO><*KHOq4KR+xkkbX_Zpla!_Xr2s;Y@*N}7&ndw` z9F~xyyZp1L?N-wSYM2XSWZo1go;L-eeikEm#jGLx7!vtx^jYMvPI5MhO~pwzCy21Y zDoZ0urL?m%IL6<&=l`@>`Gi0SwD66}Hx9)>r(cuPQ|aqPm=|X;q~Bpy&K$~}m$iY1 z7Dllu%lKFLq}vgD}@82WK?~*XcT4r(f9g^Yi%n?H>{9 z@E0(laD}k{hSQ*i&I9~K>4)>c@=8GAJ6%S@UcTaiMaeVXW@aX8(~UmD(+m{KtGMWa zGSJS@yS&HhHCbvyP0+^5wPIYe)9yblO@2x6A*kDVOn2^mu1(F~X%kcZJfYDMmcJt< z3>}-CDPbMO5T$?+V-;#{hzI#uc$LXgrcKT)WPgoE2p^TPB{-WSIGvm;LG97ue##wd zE33EL)ZDG`Qgdm?Xv%QLSm<>6=p2?VM9=t+5}M^(+VQCu7oOs*ZM=Bc)?PerhX*_1 z6S@ZmZ!uwg4`m2-d{|?s z4BE>7tf#7e6p4=!EWHUM&W$7JYimif9D-^HAMNBJ;1Ar!X0Ddgx}^s z+cIAl;GCz5-{$ZlV|8AN0v=tIi2E6@_uudp9G9>VEE>-nHqCzlj5=0+xJdqStEFGULCh@-z}cJ!kHiK2e)NkFu9bx znXmB3Sq{ZdgSQ%UKtQQ@vY#=g{LAmmqk;*jDS*lXT&B448WZ=G4K9VgJUZGAj-bR#QQDB_HP%@>0n^~?^ICu9sW%(EH?b5v zH=Ff4nW8Q--7oWfBKVJ|#Y|r(;PuscJ3d%%2YcIr)2+6#DTLukg}67@;DMrGdPW#h z%DcYq3Bn0x-+k}h_Rc%sDSF}jB}xy^N?1NSQ=#MT-hC~2=w{w0@D7a4&L{6`dFs9K zxi7S(6`oqwH1ELSQifQkLZgl)zpF8MC zdy29cPMB%SH*d8sfBB2;%{M>S?!WPR+H|iJc<7j9?svC0^13+@mOpTvvPM&%d85p7 z_8#L#YXQyZa~k}WdgnsFSJM9*ckX747c-CcreJ~)zI%cSd4F+s)Sf(kSYE z3eOHS)VNhh%FI1aUCVlDnP(o)vkpJzUFbo$Y2ZO={g02mtZ^8d<_XG6)OnW~*NiQ% z!AT(=(R{cuFihcAW0tkDzqi&tc>mkMNtY>OI_=U1aGy03{K7EfBrr0PGI)gXjC*x) z+Fm?)(AL&oq&PT#sPM=|)-!sJ4)idAGU9N^INrl-QC$~@4oZ>_Rja;ZI2&6 zY9D_1VSD!MdEmzRSg&VIzg}l}^$@QUZ8zkdIX_U7l_Y_GrZ zMxE1yrcufmOLPHk;X(E0n{T$)?gy`CUeGh)?s$6%@wXD(L5@MmLlMGDiIO2eP;`P^ z#N6X!jQbb9@P$&;P-Y2RxVy_Mr}Iyg5ft|!kL}@u$5|Wiw?~h8qitqQF~miyoUh6Y zo5F<0Iv%9cPZXUZ6(Sc(Ofh~^uCd+P-p(9` zPNzN2`?_=YZYiC*0twybsXvqFqeW|Y&Ep@0GlauCZ!sL07Zt~Or{Tj=y8b)Q?BRn) z?dg-}o0o)vx1o9cIFEpIpBC+D5Jmi3mw zD%y|lF_&nJbI;Khd@-oC8knx@o|aV({E@IKta|SaZ5!N&Ir{s#m;3k`Z=)zqf%WzEt@h;U z^Y&tGBk+BYxh%3)sot&n>Q}Gts+^ykwDkx3E`9o@Z$C{rKTG;-{Xbh>gMRt{`{ z@U`OWI$ft<@-#6w-QM`p7ux54{mX4BoBukDIs^kVgm7Ml$Zv!UyH*dGE z{^nQPSAXlbiuppMA)JnwA$_PV-xZ$!pggFz|IYowf%)ZMe|UwolDGatNPC`ooc}^Q zK9dIbuhb!7f;v+)s4G{M*MIp49qL4=?z{3m|NO4P^N(dMMHc1F#!fb}AAit3ejH|1 zIEkYWA&hj!22n%cS*u`NOL$TJMwkgB`fsffdW0gY+_rOJVoGQef-a=ND5m;~P?oh! zD4lmPJ=%o9!d%$6VrVeigelrxLJ-fwm|#SG*W)THc`+s>;LF&!=b?7@jnHW}<1BAj zg0qUsy%L(#zuNd?5+_*{XXE0x^1VkWC1x`#Bd+$^$>%u+x!@|Fn6`~7n}n$myu!^a+r6=a&NVbj4!7U zX9zLaAvBw4qZ8@-5W%Rrx^QA>h}C;|n-K!XWUPc@<4L;LP*;BC%d6A2v+=YPU&c=x z@ERBc*(yZV#^biTvsP>yAupbUm2a;T3=x9lGh>4v8k^v;m%3BHYLt-nt)t z_f8v~TyA4i(}4lrcPAwrv=YjaC? z+vKb;mp9wuLgp@c2s#Nrx3@RiM<2e|K6wB8ZGU$sV@}!K&vOxQ>*8duJVYq>v_W{e zk)hzVzzbnFFQd^~BS|&weO!bDEk#VhiFI#|t*yM5{Pr8X8hI=VLH5QQpDQoP08|O= zl|or-kM_kcem*euvaPQ_3%sX(u#*g9#)`*Qd0CCL<2`4JJZ$@!v$13tpPJ9O&!mmx z72<9rZ54VmjSHNfmN($Uv~Z4neP3k!DP{5ULb_Gx!_-9qI5Gy_tj7VY;mxzh47|Vx z3>7G;>O8PIA88`+Hj_RDCe!xwtW`X{y-g|iCgv(%4=qPXOTm${gG&w$w%h)}PTtAB zt&~|EFJ!oD|0K*`c|(EcE4(%I>ZI*tF2O3LN$ndl&l${G2f|?s zK~VfgwTE&L{_gv$Za4{s(2%{|z4j-6^2hC+?|-M12ycJ>OYO!Dh5}=?UhS873zssC z7uqOAMpux-uj9e%ZG@8HqU~kQo!!<$f@Y2~Mrg>%@j+8Q1=)s9RdmlZ1*dAnGe2{g$n|9Q>kFT=M zf>R7tjXzqGb#a;elvRu*I{t^FE&NXZhMbue)p;_5(YGcr^)utR@Tf>#xlJ~H`do4weNrbn-$^Y_T4u_M{d?ShQlt-_uJ9l zTAk}wN`?t_<5y1F|M)-r5AA>XU;kz3g0Q69?fu}3!^6GePs&S)r&oUe=Rf|F_HX{p zA7))YZjYZlZI2&4>2iSN0~5}hD(|6u=Pk6H-@L7a*JDI8bETkwqbR8nKuSV5;}Ox()yV!N5X-M)FF!XuJbFtpHa9;D88Ern2cr19_# zWD68clJhsq5GO-NRzR^lP!t+7>jS^nOek!bC z@(OQCsm{1U$lWZxQg~Ll!SoydV;=Vt@7Z@TsR9(-NFp=faB3N z@HBG`Jd=cD#OoL{@9G~|q=;0v|Fn%E28E#Uvd)A+Pxw&jU`H5abVW2gA4()R)1eRcCH!7JvvdQTC_St!Vp2l5H=dVgo zPR;q%m0S5JoQZcYc=ai3F3L`LTHdYl^Tmkd0ZFFY{*V&#Ye6b5%jr z?>Aif)28(M>YLO{8KfWl_1B*UHT(RVuIpz{R^PSa>pEShU*ZIJ-hBOD`_kY0O1t&i zy|T!JZ-cRm__Mq^4-(!9VLS;@TAo{MzZRzbE5GrT_Qw7DVYY1Y!;B=~fGP1;o>qmV z^GUiR4e*^jg##h)LhDz!@hX4rcU0M5_=KpqsVw+D1iO12_43`Wd{>_o9H0EILV6qh z?*H|B^+Ukrk886Az|h2GUNOZFOK; zdZ|Jgrjp0nZkW#Om9Eoux=z2C>DuG#uPdQXS6>IIsOEr<{w0&Q(Bhty z-AfGyVqLXktywB^w*(-#wtU$|>HuumxgeK^` z=w%s!phY&gXxliU>Uha6Of#GR!$D%lFw?=KxVE z5JFQ7_Ko|{C;_=EWeb^?x(KUlK1+GxLd%bvP-xf!{Vk&-N`SNd%oBldSI(5@SMqD_ ztMlWwzVMs69Sp>M5 zFT88`4#E~RUkJR}`PDW&);$|a5S#Z8cGt>FhX)j448Fkp5w`B^Y}Y*F;qU}t2Y-jx zAuMth${8L9|CBu7qn{z>Q2XN&<`FusEH9VkIHeasWe<5YTJtDOcJYOoj}qz!9*SSf zdGVX+ z(@@Ihb*P_0Mq%=ogn0~HS6ILjnBy-~Mqrl!U;a8%Z*;nNwo;~~-4_?mrR$*v3*Lq@ zmL>SU%(@ESdUBAudCyI?(ZGJe3OFuC&T92N{eLOU^=XyOtB)tt$oO0yQFKiP_Hc_` zVGi^vJY&}F>gvt*#_MmCfblSWIXXN@os=beHFpvZ$>X%66zbFI;}C`ML@6PT4)@YN zXQyaJ>c9)9zOIZgM;`cYj#6Iwc2<2lZ>xbZ9vG)7XMb2`S*R5-1(_Wbe3?ZXe>sd45tVa-qsmB$QNfJZN!lXF;}K6q)N@N4O3ye~30 zcy{**u7z-S22T%#XUsc(=wnS0AJ`6@1vm<337`wtrhW2u++&X=ibdc!uTpaGU>zP) zCcHNo6LZdcCi^9LZqFHT`?Y@UM=3uUDcHNgzl%d>WRW@R~OtYMzLUAc19Uc7i#b4d9Bf6vd~$}6u* zA%?y%H~W< z9yjF~JemIPwrwF8kDamB1@aeX3~0c>%l5tRek*xVS3|osR_%@_zoG{-^)B{ZIe%|GPbV z`m|u-yWjm@c?DG%!psLxx<`+m)VV&!W^rk$=oeVv33Kb#oeCdF`LMMm6zz8Ube4DF z7JLOmjF;6fbcE3-9P9nPtow~kVPc)Hw3T&voVM|5TrB0y;)3%e$BU-z>}<8CPhX_( z4~r)8@&(rq9zIIjpBJ4J!VZj=(d=25C#VyQxks_${rBJhuswgVk@_x*j^l++(q?nW zJF7gMQU`eK?+2^`hb0Ti8)e*bbrnr79MEAWC?j>LkL)CC{FV9XUS}8RV+xx}pM>?B znF?Lb`#j<(3d?vn^-zL=J#q~=`SzWgZ8^BI3`SB%=flWrC{}06GgE$w9iCanVK(DY z=LOCM&eI0tfv+*H6g%j>#!_7MbEx{6oBBY3gXhy$<8}}{K-pz%yMZuXk6c5(^IAGW zD+`ghy|tUU+Ryjdx-2I$3-HW4tN0E|(Z%#F7&~3?{`JsPTlK#$Vkz`Zfw?NFX)ptt*@am3Jjgsyr0dh&yUv&s*4UY*nTzxnd<@1-U$lvll5sX}^?7wE zSE_l)ck~edq@DT%cXhZ!qg{PLIDTVMKOn_ZZ1uY!<; zD)(fJh6F)}gmj$NG4!YSO*vQhJF?E_;65VZ-c{bKkDjlH#^8oJ>XrI}NkJ2o~5pZf?gOQ{~e+$KGn zgfz1YT0;24pj5rdk3qsSD^{R z1opAWVB~%MDvK}7Xr9$~^%=ulywq6N5FVDLT^J9e+XXSLpEnjpp*EHn$S^|==hO#% zVku{wjA?C3^Q`70j0Q#@xfiYpQ&eFQ!w3+jbVXrj7)tS%wt>?U>Rh$ieL#f?77l7W z8-^NdmS4p1lKNgJJ9Q3$CiEDW}hWx?N-KEHay54D4wb!g~2SU8n2x zitq z@{9^SB#^U#MsIAKSro(Zgg70SQ%JDr?X=8hmQa@W3i^d^D~HuGI__QcvUe~v>*72u zB8=@DVV3afLW>DI3AT88d5^+@pokEtZ@%+p`cc->DM#PXr=qi06vqGPOVOXuE5nH{ zccD@?|H&a77TRlM^hbVeI=={A3N1#13C6l7#c{hl+sV7fd56%3XBZyMcJ8tr9qhEN z&9(ITxV&aYrkr0xa7W0l@AC7ap3dh$F+wnykCfK=fYeiUr4_wH{q!OCLVs&KG8fuFK=LZ>A~d>t?{n?e9ZH1d+@CF)%=(;g ze|h;LB#!-eVf-(mq0s@D1Zr<^48P%E3PFJEH9 z>vp!c+w*77n$UY)@PeOmUYofXu6ZUb%S$CNBTxoIrIbouZS~ywAUAH@EWr%^1zbzU zktY>}sf!>9Pa&13N#;Nq2ZzpW>SrT4`%UPxNlL%Wdxgr%GvOI4OkH>j5KF*IYaO4{3v&MIL(zZv5)ge8H0_bTyR6E zS^QtB!?O;L%q36w!jZ{R*q%}ZQRrqKDHAe8fq7xgoF6w*g5mwWgBnkLu|^Bz@-BEf zJKk=aYfmb~8qcoom0@*c?tyoPb!0d&7<@21s_yQ^;asgTVatSGJ39igSu5r%V^U?i z^!rLE9~i(t4v$W?@u`J2k+D@~ZB+Wya|)#W<{OB5cIwlK@sXx7oiQColh zIIy@|1_sWh>TNXN8M)vTo=y~WF6W$4f;ktBXPvW@gdd%nUdq@lr*5HN?N8v%!C1pX zQpT{ZD_Xv+?4WTFF!8vv20#<|6~MOktz<4N}0N~ z)x9v_7x+I-s~%EV!uLhLCMZuAYV5{_LNC%EVG@V42P^oY7<^@HE(3=Pfyd?G z?{3OJ$p!ytAEj4ci?Hvxz2$&olY_})R9+i+?2ucbH z=N^Jb^cS8j92uOsvGJmP@cz3Q*S*lRsdkz+pQdjVbEV`Ats2c3@*3XX->xyIRHKA8 z7RJST|LB8v+K2CdKlM!3d~9xQwDpaw$>1)EPB36?dAA!hPzqA=wWIYSGfYg6Bb@R?g>&~u|ala@=# z;fzWK6H80Wf!EPG*Xg5_x4XlGw1;zc<~Ajm^MQ792^WY5IX=vsp7V6e+=Ry9o$xA* zFmBzt6_}h4%nOtID*f7TAAI;>d-(8Cl|ddKnV zJ!7lQJOI(1k_FUDS9 zxVYd~%3Nasc9dx@%op6wD-Jw(zm%rIoBGFVkq0eY2cMbi;@2~_#*(5-$VQ4h^-*{_-S)}`0Zs~o0r5iOuR??` z!t9(Mh2aU~|K@9Nw9mi&g?2NWc@{;5^a}aqy+ZmOsX^|!+YzJt`7EMR`TXZ;JqU5h z|2F4WWxbNG-tSrKQ(N*W*7sxp!4WCw#dOE;qUbs2bJN%c+8gUzMP0 zEe!7a4}~`TussVSeIT^q5Jo~qj9A~OxG*u=sy~P_>qO&)$;J>2zS~e}13`dI0Rpeh z7$8b1n|p1+v|-8!iK^fAj$KYyp0R{gZz=4JhsR_Qw?gF;Im2ns#xL{_uAvgzWY zE1cY`_F_2FHq4)muXhODFi9AQvP#K@0O9RI!7wMOr-U^6m3wG1ffH*p7Jp^o7^aPt zV_ABZ1rec8XN-B%>7Ra;aw`l{Z(_Id)MuMcZDb|N0`e0jSK7mKD>w2+w-l0ilYtM6 zg*h^g%IQ$${z$=zvYd-HV9<;Q3ufoE6$5h4;y<5xALCRC#sIChD6PEN(iUS>8(K2{X={jAfU#N8L@%2|oh02PS4iZfIgXyz(207~}nH@UJx`8z-bF%1Ny?c7k#iv?g}=W{BAML ziqr2Z|7t_54#pkjDPDO)qemz#hRQHTSQ*|2B}B~g64s)Lx$r#d)^FYr4&*;S-EGgF zKB`bk1pe|AFH{~Kgb2p#vQ6Y!DNuM~lt+n_HVqLR;6w5~b@eb}p^Imf77RU=(PBqR~H$>mjv^vCv+aoH1@&;3AN@TsB(`$vJ7)dAw>~0(Z)wIPbp(^ z+9B+#ZFJH>@ts$inwe@Vt2fG{fl^|0d@k)bR-x75WtE{1+S>);>4$A>DfS3o2SRe~ z^NdjapdIXOHD@Gw4~!g#_oGxIbj1S+X*4r4m$p()cI6VDi*jOVd8w3f=78eL`6k_C z?6`P5=ihdLWq7%B7ToGKjCc)aWSo_NvRmmpfPbRk)4U362)@#R68H)MxV&^d~u*Rztlz86oKxZe#GYJ=0 zVbv&@Cn%T$qoqhOmf@~4*Z5Fpi(O_tWEcuIN6Q_9h(C)HDI= zOqxU(7(O#?$9sC8AXkVdhEs&(6jv9g`vpg%)?fY@i3!c=EFkaKnxYJ;`Br!O_A317 zS@_(HGyb#qxr}|`hrmvUoA9RQ=JYUM!?TA+6k@S^lBFCd;=(*oKpI2+VLgA=b_4s* zpFb-vf_wLbyz4?@;p2SHFD$jiT;-vdalfpvk%!e*iYRB`cEuM@oa{L+oK?i?UK>6G zv#+j{b2V2k@Y@BJ6O%$n2`l!zZLVkD0|(Ba0~fqq@U%ix!CfoMH%s|Nc+3lrvL5X7 z!W14+LU|@^4z z_ssoi;D~~3hzB76srEYu>?Czwc|T-*ji%XPx^YyIylKH1x6V7Xf*HQW~ zJetqo7$NB?Sj`LAAIYX;EaN&px73Em=QBQOYt}186eW#MV`mHrz}4A3Fcwq(Os$!L zf?fSQGv?=bf@UqG74Sm76bukx6M)y=DPuPhI5NJIp)=Jt_>Ex$9Qcwl7EQG8%f61M z(+DLKTKcjSkz>;<`LvE-W{nP4Slp%5FO22o=~;X6{7L3uE3k1~`?1yF+vOW~g8#Y~ z%<{@|yLIPw8%^Ca)3c$CCxN;3^mnS=zI8i!(8uh{GL|F3>!X4B+Jl?Nz&4}7(J}Zw zYqSg~tiJ)Acf8H3jVBrOPc}-@Gq-c2K{rBE2eE9nP*9wn< zX`Xxbq1{uJ!c28wDtJDyYpkYgZYWX5Q_gYL^5gcw2k*4+eCJ#3o8SIc+uq$Z6$MLp zgzeq!QZ(^~)D}312P#G7yYIi({^$??u>HsX@E_XqXD`~$-fny6op;;Uzwxd1-g_Sw zd^>-Ow;yAO#l_{K^}JVWtz}JuoteN5Z$5GYV~78+F4or8+eaUN+&=o~K@UF{L^_Z! zc)uHmFsALt1lTj zf4rE;3eXW_LqWK+L#bllepqJ|J$ts6@wF!5LNI~nv0kl5JXXhX_S2nD%Kbbu&b8;y z8h61LT~U&X;N9er@HKcpeYQQ%&-AhWt8(S*GAyv4m-A0v3LQo)BKOo@pIj#N_aN;C zvkMEe%~@t>&*O(r+S4b`%Aksj$$OM~olbWnXZMv;&&yz`%Snny2oHc481SDIkbSJr zi~jKvL+>dct#e~%t}9ewe&aQ?x#qL*$xJDJ{C@WIMcY{4tmhP?6kn8D>PFKkr0|(w zmT|_`)>c<`rw(nPNE*md(C-c-DJyk2%MniI?Jj(z@T)g&tY&`TXWq*~5^E2G8+cfh zA!|OAEaSo>5RQdA;63wget5&X&>`bUxysuQoG&cQmoj!`WwmIjGVt%#13Wqxygcxf zw{Fn_{INN3&zKrJFy?o8{$0UZ--n=Edh63g8HF$E->stp9)OaM!daEiN6%B&Rhfgb zJ+F6NsRvvt#Z|w5Z2)k%8MXmVenqN`&wPBGYB>Yg+XP((X}rt=PNhr zKcBXs9$x*f?_t#I6Os7zd!-^C`9px}X8%68f0d<(HDv|GM8BWh2$sER>gvR-myiek z&u1^o=IZ!FSi{ZsG#l5CpM2aN$UcTaF>-xE*o{vwT1W8 zK+z<0i#k|uA+UrVhhf&WX(pRCR@&9pG{!yOwb=&NC&tpoMo1$T;L5-tR{qpyun9TJ zs;h)=$y0p{!3-0E>8p^0VagHE3VV=t7t{n1**xjOtm|~0uG23}`juCF^$lMV z`qIDsRO#xiNz< zl>tZk_-QD$wDD{=<3!+bp29*W$1Nm6GO;r&jkuAIW|F87LUkPe^6%&Pou@!(w3 zWZ}rfQU-B8?{%fg&BKXnsW7h0C8vS)j0)2uJgSL4<@vZIpUo| zS*0j*#VCjX=l<)TE9Dj1-}y!cLlPCLIA4&!)*PY`%53-MDq9thnU?lP9Mv_=SP)R_uBR z9uM~S+S-e!8DD3A@TBP0=q$~#PXOv^f_K;y+Un)kamk#f?9mnU^!XhA!H3hil3GbVU*%E3AVD{z2k z2ZyCx%LV@otnqg?*V?n^kFpQgueE@`q_Fv9tX{ETKdLe6Fkw#scCBkLdz`V*Bl-i1OJ#F&y_6}F zGtN}&b5H58zW%i4*gK`<$$A{mn&mNvXQw>j-S*_kliHswE@a)0Q)Z{3fw!~F`|}qM z``ib2zayTnC^Y+_!G43M4mhDi@tbmkB8<>bs6}lZ9h**j)t7EpWhlC4ETS?4#hezBg=vSE25@z@LJ;hd^Z zyHz0yg?FXMrWoOs>wSGIMQMfHgfjyJf$j5@seT@a%HDM*Rra*Tvcj%T3V{Z`y5Yyj zD4ZD_9Q*_~SYPAQE5XA{foB3~p;cR*6}6nPT3C54c-WbU$(Qx#Og3j~Ig^e8jnamf z^<{vTR|uFDmexM1JS7A7uP%kQ&A0`Q$_sCRZ)$zjEagh26rH?GgBuwZO zPQgbJNRdXd%QME=Mn@F6p*LuQvy`4beO_aE=k~q8`AYTu+4Hsb{P}v@*w}85A3tsD zYdlh4Wi8ESjAt?@$HAFrZ6@Crgt^VyoX*(K%w+7Rv#%{(8>_3KF?Rzy3x$g)RC#*}*Ef@V9bf?cDp^Nx7e0i716?5ZP=4WYjVgSa%IgY5z^j?>Qg~hB zmGY!Ns{8|mLCJ;k+4(p!hfbG{ORfPw_c5mMDqNF-7!Ww$3Ju%d>Po=O>27W9_+A(Nsg<4vZ$;Mu!i%lybU;Prj)FxG(s7=89$ z(Pwg^jK|=9=e;x6{yqa!pIrVj5XR{0rCdFqFW#^EuCA&_9r^6?DDd0mT(838JJ0LI z3tpbQ@hCmx_rcc{CNPly6{dFbO=vwi0 zovza_VHyjey!-Z>?d>oBT3foYYNutpmQO;TzNv$rY#+z-g>nPab|;Mbtvg}V=fnJF z;{~rl(U5fCc=TU&?pEHdLxn4oyZLwtncF<(xzF6o-TVdN=UZ<3zcUx^_*aCW?$+=6 zUd&GzmfV0`Yg3O$a(O<;n54)eAU;zt@2K7V-S+gwv-aMH@3;3Kyw{#*<9BLvRLns( z3Hg+tz`%wMK~yB7Rl>Ji+JzvOr&Wh#q>T`>h=7;SFFmv#(QjFzy39K-!7|67n0*aNKJ`_V~+|vR?-=>w;(`MDE3;iPz zD6wwB#1I(O7#8!JT;?w2=mZNc%nfTrvqyl25hlB}qGq!>>dV)dJQ zg1`EnWZdgnGK>8VruEOJtXqYR6k{n79I;q-mRfmr<+);NtkYie4aUrMA5%i4?qP6b z<3|&Bovzb$`b9~W>b<&tIC(y}is0uO2Gi%0r2elYoTq)HzgyiD)@I&f=V6sE6AjAR|B{81tTc1Suo!xP%Y~ z`TpsKn{WgTg6jz<@f9U7LHqLDHL!~H9$J8wX-^ld;Dc<4LnE#f5OszOnuCU?ZJra< zl~5!-Coo3a6o{rM+lHFb%M?)->63878yjmWk;Oj2snMgWd%hyqhJ$+vm?7m$2Tr^f6~S9^PSpqaE(=WL(cHY!u7?QC=FMcLar#6BHUl z86%2}ZgD?7ztSeAyEnk)CY!2vIzdK6dR!EB6F7Zyu8?N#|LZe>BA3dOv;)(?dth^|4S+H z@~G|athM#ECv9gtV;lHeUb<19ImQn2N$G;`a)!_9%B>Pom(VRd0%)C{oeq5R8ksHl zz(*16lz=+CmXJiBd*jVgoDp_y?`*Zb-L1f1_dasY%Cl!r3nu307Bb)3>3pt}_Wb$t zw!XezLLR)7Fjun_3R7Ld_A31*ct7Vsaly)2C^oP$UL$#WECk#wf>9Cmz#SQhW^!Q4WA#XRGYl z0@d31)D!Y7Lqmv~zSW*58Laip*+eOT7*64xGbi}hzz!T^9(OX&jNo`zJ$d>tYxzZu zI{_w-DPy9pfK06^ibaY~d}t|t(wMHCPBT=M{`4@T;3c1_m+~84VJv12$~!Tz0+^YF8hL0XSXy5X|F6r7~qA$Tt<_N9<^mx0;C>Mt(^I7mayD>hvptwo{W&Q134EKDkx$)pl#wOV@y2@I!=<|%zB z@579VIUsbLpTChZr}G?4@puSapYCT(9%YTbXlrXv^DKBjuwD2m@A3q4E)=i0&CMs7 z!)JvbE1c!QZfFosCQ94Dbl~q8e#|`fb9tPVv)eY-H`=r8H=WP56jNB_jfxvL!<$$s?YtMO;1gG{#&!0XHJcS-i z%?4*s>QW9-?Dc(5_u}pQMdkAfGiK-oT+fiec|}uGi-Gar@vF1hcrjAG+Upy`skD1` zVKsdg`t>mDRXrDhn@2UDlT#C^lh?~`#!L9!)6A>gqOrcwJHQ zfoXeXiYwp8@_qG2%6si@TdFXK{k$oP4d)|)XC6zGXfw0n2SUS2u@u@co$8uj(Bf1^SmUS3jGcg3X3 zdZ1)65AbF8-s-s61@Te5_TBhP<&BkhdDnH%&@02{^ULI6^s(0t_A~$a zPHBuT;{kgAL=ot8!JK-p%3**N{7c4CpBejsCziP;4P^*i84Daz3vYq^JI zzVfI_8F-$Wo=Takn(NH@rG9sX8$~U7RVn@Qy9~t8sT%i_nzrJB^Qm9PoFVaU)_oZi zC*NW4sIjT2J;zxSDZ~8nG_!W>1k{0!`@9^Mv*4fqb0o>%jPriS8RgSv)_nyC( zQ?K;z`J$g-##QiG&#zvR(4ngf>=(`hb9q$nUA_vQc7EW~(2||3TSh*euT1S#e$mFd zdQqzG-~Et!*`NOY(W#z)Hp|s_AD`a-!C!yfskc*~K5g?~bp356JB4e-*LAv1zl3RK zd9J%Z1+-@o6cLf9+3V6H+u{_=@09SK4o3L$(Irh0yMq20TCKg_}H5Mfq!awb7k z^)G+nD6)_FBn|RZzA(&P>E(Nn{1rj+jxuai`gi~GpWl^Frn*zl5LpDaTcdVH3A0ko zNZIvSed+fq`I5dM^lRCCe)Q<0_Tb5bwz0p__71ag2s5odWUOM}hj?RzE9_8+zq&AT zMVN{>T@k$ySsT>OC^%zE2%&C)?$GCCN?DkO(^7U7QL#=$ht`T>-;zybYqbA_DxdSlnsD3fS3Ip zO3VW6>vWy2)8Bsjl~R2DM9dS^1uvsrKhK2zsQZUg-O`k+=b@nWyJ$}?G|D+QU;5%3 z?JK|Wg?97iavr0%gsI)*tFF)!^bOr4+#_TvrAu%*nhf`&7e!lguRIy@S7&jB4xwpf zg$ne4_e^PHKo8G1jg2V1f z)cFbmBnpONZi){;Q=N0>9=hha_U!I#HQwUxIVWbIWN{{$b7=@)X2Y8;EG`v2)0WB5 z+(}^qOV~lUKxlc`_I9@`eB#IuA@f|y=g~zV`KqkyDeQ#ObMGj8QH7dWSZ#Alyp5LI zMEDAVSspGzf{lzXr1`Vq`LruMMY>btm;QB+3H=KlJ=+bhvYoFzG-D|aDh$_H+IHSv zT^!^^-V~vu!!Ju9f`)hRkUsv>t5-bs!e_iP=R8Js+UCZiwz2lGIm3n5%cF-6`*;Nw zO6ixj82jFqv9vXO!O?zOUwc*pZHh$aFo7R@B!LT_j3?ph>aFx^q0dWRCwyfAO<`1q zGkBQ1V?HVr(b8hg4?!luw)#t$v%k}}_qN;SmhfgnXCkGgj_|WD9{O=NQdhjZFrr4|5VG9xR?@?g-^hGk16%;oRmjHazZlVohiKvL^E$ zzR*=XSN03m)Y$k;#(S!GOP21|NR~yd6Uqo>QZRyf=kjcCcMm-88XN1CH%2MY+IgKl z^zgy^Srgm2H&&qpo&7_|%rNQr@VNL==XmiFBharB)B1PuAVKbEsa{eg`gOR7MFRJf?jkp|kb!@)8`MbeuE+ z-ZF;i3y(HqTH!41wS49xkEZ~UgrO@XADAC=u45p95+(gwSXgPJrI0fxU=|$v)YjmN z^SzAwLEEV_ZVs}y>SsjRBM`=&pX_CKMJWxfz1oXpueZ6i)^_){fu-k%=5r{m2xRjUk3ge za-0X>ti5GSsPd+!!qo?n{Gt-#mz)^@EsiZP)K7earE z_64^vLO?fW(+0F>|KK3w6r7$uQ;ga-Q>0k4lyP&j(?z?`#ogWg;up$bHFIn&yLjxp z_x^{0myO`+%yst6_Qq*a`rzs^lH!Bl+QPS82_Wfj8Kq{8gMU1ec9zV*{lFc3<{8el z3{+F5;q4cCj6QXQboKE`!t3IvltXDq$)g>3GUGQe1gVSx@MT zvMD!j+@P=@FM}Cy!fTKxIB&oC@DIf!pt+$h_>$r?FZH9>j|Xz!T$lVO`KsL+|G}6W zGrV_=DSVVRXj3<2f&==TYO6j{L=E_pL7$xyC!D16Op3BZ8R8jd&2)npaFY3~nWQWY z9U>pgGi@OkQ}#jDX`M@#-`a|2E+uBx6HiHPbM^ABjGrqR&#q`yzd7je*q?t2H~p%w zR|)Luyu8|2a;~(?yw#Py)Rpg^E7#Q%`B_R-=T+Ip(arMQ3p_9m7tZkci}lcswe+*^ zQ3~F#%JS!(YNM;#c=dZwZl%HJk57ZPRGB|AdD=gJKIyaV|M6+i-@nTBvnJH_TJd$A zuG24D3T{}ub)$X$*Li#0Xd^Z{5Mz)op#Ua8CLuktwXbl8m)Rh(9=&}hjOMEIy$EfR zr*d{ium1A2et!o4*l!{>d7&ewFQR|m%NMM)R|Ff7Xeil zvQz<;yjN{Q;Ob&+@v08kKH&&XrYD`cR<;L)a1f3Mp8O1L2PiJ|SEf7uISR zr@T-?Ieo~xFO#Q29EQo@c8}>WSl&^-3nO4-hl!9d0fze|8y^A`42^u+YJ7?*HF1b} z2)%j-%#b#^SJv!hnVGWF5DKJj0d;xR2g1HE?ZsqurPrxGhCv)A^h^6N`xu~N_LAol zAz~&#m`3G$50kBZm>k3D9o|^QXyi99v%&mg=rAVcm{*rM)E9lLHl)u&HV&A+&g^x; z+E{I((w5Ad@pWGv=E@kbyu~z)nAf~t%tH!RpSFXKLAcL@-7sh;;>Ta7>vWxd0n#s| z;tT%zn@T@i_Gf?pW$G;w_A@6n4z5A!w6f@HF0}L2P^Xo-TR55^t_&ZBFWSAkOYQS- z-75=biYuGZt{ft)3!Ndn$Zv)Wgs;k1M$yaQdK-Ude4t}!4vW`*)`ZRWac!yx_k9l9 ziv2MLMN@Nmr-YQL7axE=U7$H(S_pdwLMrd0vtUvJZMtKm0{A)$g0RtqWPW@y@S>X>L#;{-;tZDevG_3@5SuabM% z9O15poE>)ML2!OdL2{D1(x5OL&b~3#uU;Ost&OK`Yx{Z4_tXUIYv%y*Ch+cgJ3HQL zM@Qku&W`dPPwvSY8{5$ChQ(1g~Ij zeB9yp(;1t=97^~}e2h-@u#gl|6etBJ$=lzdj4?0jW;BGiBh(evjAb|r`uR3G0d~^Y z$(c4i*@bNv7wN}|&^|&bi99gdoHZwWsk6GQ7e+}0qZFaMahwrGF#q1W-)`Ui?$>hf zyxqS0dgkZ#Qhreq<9UUXB!DA8>|qQ$%w7t$mO5W%437`HaE>yw)-Tuytn6++Z0mug zq2L~2RyWt5*O)Uj>tjSg1`h2B@VmLP_9=3vXIE?fyD%(|(sunIxGn`==4W|zx!t^Z zJNdfjp7W`MCJU#U>t*tarZAT=Xz9mZg=7@=O315L=iv4AK>6EVQvBvUFqJXI3r|eU zW{s8}*cBDsP9)y!TrQx1Eg_rD&WF9$8Kq_AETiPL74OJ4!y@ zeH4;I+28O#^ze51KB(A46=sd$d)(A8_s+N4qemat9HVX4t$jKAFp~Al6WUx*D1krysL+S7FuD`C zIN0B4PoI34@^{-raL&uj;pY0&wi_6+o}JwXj<&X5v)1pd>DZC%ac6FBvic zo=QFPiLwT=feK9V<9OHk-#m+X%xr9K zwnJV@87uU~SxMjppTVn}hcOR3e9HFjUfP>Ie8y=I-p*VNBT5@ z_kj#W9_4m91%r{RkiAez%5@JN0R#GW@7}$F8{?-Rcs_>O-qTidrH|-fZ~ss!#}*cy zKLyV-)}g@aMmu$cMDRbwQF&{o9()L6B8uAXwGq?_jP0R& z7Z&Hsvv4wNO_`m3<1xEZPhU%xlFK~HW9}$(x`J?U2CmTGj3X%2MFS#V>F1?s6FyD- z&Jp8*N!e#?$Qhks1}5iu--Rc0uPeRur^^HT{B+)|WHuQu@REO5SBD>0ns_xv{XM_? zmG4=5zSmwO^g=&NDVz2BS^ivJ@76!>U0rUd1MM3;(>_YC?typFgjwF$*s8TxW0m=+ zK3F>b%lrD_^V4>JmR1g~o<7a<=dVG^l9cfWu6pkCGiCi%lM?DmpFjEjnXBsj^w-~L z`r$G7%U)K{wc_hKU8i5NG&C{VZoctad-DrlXfq4*;l4tMC>Da;EqqpD*p*=Z@U_{9 zgm6(}hOh z`sHvK#gtR~*kr9uMe-x2{b2CUsO4wxLfVChS16KP#;6#qG)jAH;=OxW#MAj#gdzk2tf$k?aB|u? zP=37((_MAvxlKDp3!^85A@3}ka&`6og-Oh&5tCWoTd7l+6=e&5U?YL~>&zQr6bqg( z0C`U7g~2gj%E16(J}`zDdGETg_~q^&M$4Q~pbG8dxA8J>j5~`-P2B~DDTmh@W{rzH zYr#R7#J-6rpa|nf=-B6>zGr*~4BTnP7jIKckpAYLwt{Zw85FZsLZc2Rm|50I@|IFE zzin=Kp1FsSQ>QsP%?7s=W7U34(nU5CLIwc*>vWy2)8BIX#q{_>+kU~*6;=LgOet~D z?cmuOgR4qPu#rSy(LH~iL11G)*%lWj+v~62X>$uaOS%xl##31(+z4$eA=lML+{V<# zkstwX_e`~D8G7Lz!VDX0&0vM^J@lc%5hinmvI{vtC-5Hl4XLbVQ=WwWmG@2fg%S#e zCKbP-{k7o^J+q+=9W2_YUIMVtVYCg6)lLGtfwDzi=!!n-kN#4c5JXeV5Pk>~rff9I z*$f0yi%To**4;NsVKp>FIL(Xv#3;03p|XS<9O6-d)?b!4$MoECo-OA-`YMFfMCk8n zDH7cygdP%h@bb9o<5|}kAcK){4qe5sQ81Q(E6iR$`)jAhk3ga}@_EKPfiR(maO(<* z$%)z2OOe(UX8xU>Y&4+<55lKO6menD>UsD005DykOVF+Ct@Y=1eh^{m-28OAefLhA zpBL^*$inH2n{y)O+vF7GPY=7;%L#vSvfVb;9%UZ)%0q^56RkIw=FHsjB3jP)64Ddi zZf$Qi=N@%lghI6o<_2eglwdla&Id7ngf+nX>60hzS$IyuuKTauuaJtY=?TOsqj(bR z?jE$w&F%L5*?QaC?+5T3dvm|KvQpu*v_+o?)aDl!E6f}Cs~&~N72@nq{^UQkci;J5 zc(bz-T=Dq2d^OyhLo%=cHy^_7jAa~4K=YCZ2OcQjDINlY#gO6L0#6LA2D~gmTURn= z9`ZdMO+JP|6a)L=Tb=WE(PpP-)8CoE*{2HAkawzRmKeT4B6 zK5#!{bXp!tUGXreJ1{4-XU1b>Bz)YkmiFz%{fr3 zt2a|__Je^_dy}K1er{bC78)n}f%CR0#A9#*rIGzd8*)}m_CGJ3sVJWme*J>-n>l+8-teuqaLB_9PQFN~?l;P6b#+^i5|lzg_! z6lwO+*~4U?aWgQwx_Z05^ConEc4ndG!d?hXVmJu@!x<|KOVeK-Oq4wE%uLpZGo|u1 z?dsl?ynuv|+~3_O#Su@kQX~a72vsj%_VuM78|yF1=#k>YUWtdHGq)(GX9IV`;}lle zXJwE0`s;7BTet7FaZ07Y07WG@7ZUgMXtTziA}?Lccpnw~qFdw!2qv#8N|u{9gR^el z4c=M`&RZy0v~0AGqQJe`xy6((w52&gfVF+MJUZv|tkz24AN@Jl-E7-C8-)vY_x9V? z7G)v)aM2z-dQjea)(Q_8>(0K7*Bb?Ir=73bv*h_t|LH%sfA{bHW82=|t###WtM&EG z)Jy3kG~R4mT3T%@%Qp(=uCA_Tt|@m{N^yxcp>N>GUL7w`a)C37RNom0z;}#AgNM@R zLbLhr_(({%9vU;ZGv=M%Q+QEqRlhd3+S=NBDKvPF*12|B1Kq25wmg&W+`d)(3@is$ zC?1RvFq*<@#g=|82#QUQAFbv6BMx*g1lw(2`>I3DE^3gKhIdwi+;NGOEdwFHG z##3lR9&0{4SY_PdBtMZR$#g{;WpFr$Op>ufBZdUfzW>$r;o& z;JGS`*YnrMT0NfUeyR{Ey5=T0o$w>pzdW%$Sv?#JP0W& zHKY_X`5W+b-s9QrGOiSyjAg(%8f{KW77;qX*dN27BI#*ziE;~z$_q6q9Ztx*s z%rFE~W_~DCmE+vlxzq{%oc9G*D3Zz;CS{NTNu4LncqN~_HD)Ob>}pNX*!16T{IX}- z0++*WE8#oz#c%DYGP8!juAX>jD(ed0)O*(3D&ZIKN#@O(H16h3wyvPcm(=Cm^5Dw& z!C!+x2?^n9b!y zd#VC|u*@p=2k-q=ul!fN{!v$@Prm%(CtTLG;_EtHr(d!(yS&(5d;86H_x|g3))&P_ zFm^EpHu3`;Ro*`#`sdu4!vtX9-+J@yvihmm(1o!3yM?&DS@(MCVGSX~5Dj$%siO;? ze-;n+GV-OrUjMNS9+X`Pa!m#?k11x(>;Ovm5(0R|kPHdqfIufJWQ=y5g-PDr*=!FU zKWHC6dDzzTeg9-H+hK|`))t755DORqiYFTaLLc##yWoMVJi>Ny#YEY-5vpN0g&Xp2 z39SZWhY03RdHpQ1E||0N)6UT_Bbag6>*UTb67P#GuI zKl(|aWI{odY zUpU3r6(#$HPesFinuIv~gf!R`{Xnk#hF1r#+L#xi4kC4a%kA4s?aRM@zkT`FK9`O6 zYzdMPyS}mQiYGLt!sX^QLU?C)l@)7fJvxoH)ftSrN->c4;cE%qG!G@b3La^$svd5vXj5i+ zV|A|_$_F$`xjj^yv20ZD1179pbhH3Xs1Un+ScZa@F@p1 zZewY?P+29AAz`g{fg2&;=JNhrc#_t()}GW^S(H?_ZoSqfrj|0!q5XNE;&6JJb^c=B zrBLYe(%No&_UJq9`|p0UogD9$pmb(NyT@yK%|j1=C>+^X@eM-NITwpC8jlEu@DFva zPsX$qmv|rZRRYSiG0$H-f7ZVFjjy%m&z`qiH*W`~Z{&V>mAe@{Km>TruNPz#MqFNc;A8+xNcn zo%VnJn}6G$s_WM65@0Vau4YYS{=z@;j#!vq46GC0W)3pWJnYUdPST$Ag+lR4iPNvl z@n{bVMc}267$+VcCwZ^d5f+jsPVVti+T3{7gxo4+NO-3b&SFmG9tvExvvw)+K;YlG zTa=Vz8H)~+a6#rcJh}NMKo>rYkRKf2C5`FQ;!0awTrTASMUl{f!>;6`aOvkA9R;4A zwZpyjc5=AYc6K+?U!IXS+SL5LHamYSurgi>F5^wHwY0L@7FX`4uF1B$wUzl64mI$a zHNX;GKY1}aL#WP?`eY3;COa%8Ve#Mi`tZxZjb{jts?{6!vp(*njXfOc;r?EG@#1O5 zEA2Zu4{Y2iWf?*3$;m+p`1cNk&=V;kyl2*#vF3R;Ji-GYV>VkMjGQX6RlWK6&yqaK90Ln0FXYlbP&!I*(2ed>GtyxVzcTj<(x**3@X=Le!B| z9z2vjgb&BF6Lf+rcy?y4dj)FaOx7h@(Uq4XH3Tw)k9joh?yQxEV!EDnve0H1Udx={ zYcsRUsUv+HN;zPEOvp0(9v&?ei45K-s)UsjM((0*Z@tL6+N^z=Ft4)(%L?PvR~*qin6J!Ih2n=(|K>!{#+?`mP)BLIWbdvmbt9Y z+1bT(%U-qxE^f9jeBsyI7rywL?X}N+v6SZe%*ZcbnL2jb)5j0n?(TLe-w4zRg5lSN z#TzMax%$hi>&D8hHb1|T-@Lv~OTauc6Z|*aDKjxP6`dU5_kg>6cr~K zyU^I|owu_#2*icT=Lw2_Qi@&j(hEFEJP)VmZcyKcMs!xm<_X7KAWqGa4CeP^9 za(RTl42(U?9{us7_k#r|Zl?3K8d!bwPgK z&)S8D!L$9WeW&mBnZ0oBfvZejVW*|cK#%6;yRwU?a6rA_2%ZsUladCnBauUpD^S9a zO)v;}{f+zW{u{5Cr=#}3;S_K1_)O-6e8c`5T?V`G^2Wwy)=}0)#+gFSdY}YEQ=dJ3 z(Z2KD@3*HWSFpW=Lv!PL~OR-I7hFE*&#==AbLYIxk&s^zPU1 ze!1(j!%+Y3UeDuqwKZd1f4QgS^~ml1tF9X3@QF1hHK%>Nz0;L?T?Xhk<<`L=BMge| zgTUBf(R}9xUIf=Dufs6-&YHMt%cpIUDl?FxqQ2J~wKTFcy!MJ_)Qh0Ci z-;D&DUMs$?({=hKOG~#`8pYT0tuUq`uEmxh1VP}Cw#`=mkKc$(F^ORa zWh*P{VhlO~fMkmm$|shErPTBF7wx@|KWLA#IoZo5=Q0dB<=D$?{FH@hFYA;rLYR?M z5}K7hhtR7;D>R=_L%12|2MDtmvR7lE?oJ+)@;(7uSp$c_+aywaRovwK5w>9jI%9*W z31d`*t_!(3lMn_?A2a60!gHUca7#J3dX_Y-_|)Y+-ghOm$=etYOjbV&q7!59XyHIW zr!D$sJoU3eO=Zk5Sk<2V^=D~FuvqbrQl0{SqoC&d0%^kN5r5M zfTc=GLYuoff8nYQgx;7d8#4;kJ{`JQv8$P&G-|FhO;lV-b-{c8>sOMKyz25VI z3c%mplX+!jzJ2v~e!cz1Z@kqO=AAtucc)SCtc^OFiB6+^Hk>8EzuH_AzOvX?Za3QK zG|fg`=plF>y(pTKdMjjAXp+!U+HVtX(_f*u^2cj}a6}&ol6YTHY@kPkA?PeREH6PB z`i;Jpq9E-hz&hCPN(?lG)p=L0bgyYbg>HS_&!R%}(D^QS$@pE-79j-*Fh^&Xn$TOr zL!s>#CuLwVJtO240fsT~5-)vcdE!sfsiIS^bnzuVN4PfvAmzJ{?>nwAay#3brMwX4 ztwPO>O@#S9q_B!}?icF>W4M{tB}=oAQ()pZr$}lKdVWPnqQf_Oi{)&6V;h9AWV# z&WQpyg!7biJxpCsFE4l6#~*yJz4N_qwf+6As)v<70oCr_PR$uu>qal#+8QrO7!Kz2 z!5j_*)p!J+Nnn9OW@(AiXEJ={QTy~i?R#@f8kBTYZKBt z8;W9-my9se6l+x_yi&?VSLcCU)(dYLhxgyOal7$cv99pK7lh8?my7St+)&~XmT#;- zOBpBSMaJNZMgKIV!UzvQiZTXX;YkbD11IAvX;aoyN_lyH)D{=IwK>DLlhdO*tH>NX z->xeOjZbjfl4iqKd_{hj{xYSV5sQsdBXz6&^#!r!RwdmaxSJklp;>VZ>f@Y>yL>YYvTHO(olOWE{z zaEJ#JMjqxCxS%zna1+`LjLyU}_Sw8B7+H1zx46azn`i_h=J=_V*6?X$gVC4~&A%yH zedo@dxOwA-y~OYiJh1VL%{%ZTXoVxq2=9wZ zSfM9C_Q0!?Im()x>46Ld%(#c)mfz2wK95I_o(O*r)#gE1zkxiH1^{#&td=Rjpw<2S z;=B4zKH3TY;SA2gkm#gOuk-n{fRaW8aFca6G9d8xr|yBrj1j;6-0$n+p7K#EYz6rM znUVI< z%$o$~!qZF@sx|pZ-zW>ZMOnZkWkC3Jwp&@;FZu#LQ>G18Y8zuq`ORiqxZP2{A&pad zW)->&Wb=e-{tsM=#5d#%VCN0ix{zzYP4E#K4sF1w+UazzjIhRAzN^jXc?bu+xw)-t z%k#32CzE6n`V1_=4eABf7~9hWP90N!DIa;6d~7xY2IQk`jECSRO~&Ykmod+H7yJjV zX*hAGuFX0Nt`!n}jdBIf|lo#zW-s?WM`3+7KDer+N-2Vg87i8!5 zA6U}orY|Zd;j1Tu&)?_zmrQVlYs1%dx=vrGBzif!yc8?1+>NRPBg=jRVv~nD=k7}L z09|7uup?q3>_}?V>TzTFh6OYPdt0mWpOXm|<>-zH7{r=;wYdN2L9Fep$I;nw40F~4 z0;~j8&VXRihesG81lgsBa74Hzn5h|}s>VoyFo1&LOag)#G;N~2^kKlD@K7T!MkGGz z3(VR=h)SX~!;~j5Xr+QN(ockH^l|5U$8Av=2y-a)EVPNy=Q$6jZZ`{Xb`#~Il?4<` zTFf88L3!AP1}v>S14dLnfI0sm^zdn8n!ZpMLVWfW&o+c1TAt%TNS<_ySGz$Pm5rjv z#j1BlV(x?`$@j89zy?L61#Gno53v(HXHn%{r+`rPl7JgVHDF@Hm|$uFM|GwEp#CX8 zWg!^h{l++;G&xc}+6t^#C?WVDSfThrP~<%XN0cV~rr#_!Y@AfPEPU&IhZmwuwcR`T zR0BdU3EZQt2!&kwVOU@Q1P0&@i$P$V-g$y64ZKd*={o&Oq_52I^@F#+_eYhJpE_jyzxCnYd=@2o6N!0(K1EkEoYhg>y}KOW{q8qo zZmuS}o(2cXKoJK|p`P3vl6=nhB(LDbfZ`S}t!}q#UNTM?FO|VNoc&nv6Iy~{1;tG& zAcnDj22`7Fj$5rK@8d>R7`3S+#V;{q>m&h6+}!Nq%=`2fG85ogD( z=ymtB*zO6oCu*l!VVE7qL3ca$`z^JF-TN3j;H%jmz85=_5lSZU1Q?swGZch)2mpO+9#M5JrqpU5pXl80E@b zl&3hiW-=znr(=weY$GW8U(}b0^11M?mdtUEfd!){p@~qw^rPQv>vNDj=>_JtnPDiibjdrUY zjrxpbGQ9Ti>e<=Zk}Pl-i%ZM#)?43{k3NhiPo7y`oSU7o z;uOOi9z7T}z$KJVX|zCropZ`Y$+4*zv*8OPBe3<%RpL9ih0Mj-O?Xq~87TF}g2rq{ z?=wb(XkzEJ@O7eOBM4#q@cO}%ao6dV2|o>2%VEODk#V6PGA?26 zFg9Mq-X7tc*42v3n46imHyQKLN??s&zu(rF=e%d0l*^O$b6h&jlbCIz`wg%qd0CPjrO|PE|uhRHMQ5b6&8~TAq)7t8T z_~89t#X-L(9Ko0ZJvd8HYVM;f$KwTsd!sQcSWF0Jcp$Y6qk3ae_vbxcc!(lh6&YnLAxcj|Ua5kC^@!+85@R{(CahRASl%iy7!DDJ-+UE^6G*0Z` z9}#TqF@+~+xuQ8;(wcI_8!A~Du{PoCC3{4TfPajQK1?@+o5L9SG46`Sj2U>k*i46U zUi4U(nrGOIDMt zYE0pMxwa$(UOza)s@dL-c6&!xQ}quEp9MGi0v%Id7=xiRdW?O0M3tSyzp$bvfMD%ywu!;CcsbdKmbsfkTb4EwK9zMS2~*Z!IO#ofuTOXuKZz|!Pej_K$&er4BEeu|_^__W)VRqpCqcT~mVszST!k2qC zCiMD!%M2JDSOl|C2CpuR7kIc(F87cz_)geHjOuux!k;osUq3o+XvMJlTetTS>t^Nx zMl{Z5!YIsKMJ_`5j!^~~1y4m}8|WIIL*??cahc5-v>9U$_}l9dF7e2QYR*O5+S)c9 zq)u=I{06CkQDL~qOK78{+3Qd4LC2LXacl5C7x#EhPT%9k;63LRZumYO(;Vbo@Rv{4 z`9$T(+?pAJJA5tALsy*x8bdXd%(~v2n?y7CO&PUX#c*PM4_x6zz>Ko^&Nwix@D-lh zn5}UmBq8*NelfbOE@KGZ@SMEXkEy;iZc$#si+j+k!bnIR^wILBU`6AQcX$t;13qxB zSQ^AI9CO4*o-0e(MU2x#5<+hRZF4^d{h;qzhaTt?oFr@^ycqa`_rL_a$uq7n`lm6O zi_-MiDd7Q4&bi9iF!qJsi;T>rgwc@afsJZ?DT`0uqio(mE?1Ln-0!prW8E>lXd^l{4D2F`6zu$YQ3dt+ z3zfW-5+8W3|9uG!erGDmzRLR9VwH*#|GDW4%lRi1UbOpP;)3g48@{g7b^1Cb5$nZU zH)G}QEysRGxYb-&8VDy!n*Ppb<_QxM)x3Sh%Ed!psUrrQa}}Au(+j>Y)~K z+q*mQ;e(Ik`TBDkx;QkHa2hO*sgB*UC@a_*!j3F^2&oM)J``hwCxF3{-^@yjY<8K@ zC-3YQ)8x693@(EmTs(*I6-<=pNCal)7J_rf3iDqLXeuLciEAGr&=-I45Nh{wZ*ae^_vh6DEBaqAs{3J8CJO{(lC}?c&Ayv+l?a$ zOb+#&+wix8}ccjHAf)l&;3IWmY>N)*F83s%pa!c>}oHm}T zKH9!7!Sv!J=hJn%PS@!xPhXwk>wAA(!xz*nDd86N$r}|!lcCX8^szfui)D;9>_Enwq0{YXA>E8>Z6a>0%!~Jq zi!b11ELyIzykk~nv*7|Iy{q#k4HoPfZU==1yc_Uz6~?)n z73D7%W3RFCdl&*RilLlkfRG_jVDR3F^I(MFeH8PAY*S~{?lZMvQsvZjVPw#I8dvXx z)i@2|EpcUxpltB`ZNt6Z>wuOnopM+97nN)hs$wvJ59^Jj2Q-$p^>WRR$Ly4e&G2;xVy7x?(N#M3$KiFx#s)e z7+zt8cbMfl^^JMBwYe5+tItJKPypA2?ZQXg+gp+Np3wxF>uD57PhxJ;sA2 zjnd2?Le>opP3j)wMn8w*MDzaP!;g%kgm+t5><|N9Vp9f6j8tRcP!bMGn}CP z%*m2)oA9V3oJnYdIRi!O{1jugW_uuR&3L8vL(y1Ts@oq_Qjn6oxJS3gFy7{=2PI)|~Rf|pKX z-i8(C5N+aYVV|d`d|s2OkH8zR!m9FB@c0z1gim$F`@mh!hhzK?k1$RUZmc+qQm|K9 zHgYS^@UYsiz9*d>jb3{*2*-%$3dVYH9q(26f<1DD2h7QH&D&g;LI3ccR{0n>1b5bZ zv;`W6Vts64+O$TQ^*-xAJh(7&aZVyM61@RoG*3LM?EcVk!c zt*!Pq_e4AU2VN86C4;O1t#SkujWOef@e1An-v`(624{Uqd*Lg)yE~?nj1}#4I6WoW zk5?D;p0(=y!hCw0RSCN({-rUsx0`U1O+owpzV!gieRvl}FO1iFs$)lOhIbKSj-~zc z=j)n#d(mliZLEV1!z-8*X`sMh0i;sy^QGVLmjodAqala30aqpJwXDHA`pX=;r~Bp~ z`~uX)A3rjOKV7EoabKW%kw=xXaTj?MLkfJ3dqsU1#ONn7mvtQa!w3WX;1|G#;~s!5 z`kq2pgDe0aMb2~hNAX|AtI^PWS8I@Ak!8^bkl+{0A!JADb$@uE|7Z*0K^bFYEbdVk zuw=d`&O(OsA}# zvET;u1w14lWe{QzIAJWs=!M?Nv`;W)9IcPS2rC?>F7!R{V&)fpzVce5e(Dnps1Mw( z*K3-CY!1$T0S_D6)IK(bfWydO7+x6{@RNMt6^T#uTWmytCb7N%$GOK?k&Sm#j)UK4 zf8kfw#|id@=b-UI@8!jB))kf%6LwDdY1n=0%5s5S@oviVlutPrO)s@3z`MOK*=#S` z9mWeDkIqSJ4wsu{6y;`_`c9=N!Kmme=?!iT+T?G8_loQD($#%F$@iJRT)%yZ7k{6* z_g`9qI$aySuG4k;8YLFkE3e#&<=b~+qRe7VgjMETT)f|C?A#Ow%j2>B{& zVbjoJduB$995J{gY9gK}DfkM%(|5BeBw{W;^mzdxcPW-f@>7?MUb;QFr7tiA@)crH zmIu?zgCN-njbUh97ea)d^S+*6sGb&wQm;La)y?&2_c}zF(4tI2h?vTmm^U6r8I~q@ z1tM_x94Ik+s$*f7Ztl6u)8Y4&VCpbX;Dg}k`t&`$h7b%=f#&BD2)HoR3~9kaKk@+h z+|lAQ$^>7|FF<+6g4jFQDM$AZhPdZ2iCU=XZ3{{;Z-Bv~(;i`BwBD_!dJ!%rbg=^n zB_jqw!%2ccD(_Gr7Vhl0s-q}K!w`ZB43L3A@TY9M*GtIbJB%EGL0{Zg+6~T_>BG1I zoCk@2FPNQ*dtq3U(C@{S77q3nWC&q_5Xgl!bFm7-Y zcvA_xR)GP6T>oI-4Y6>iI%tXeu6Bd#D1T5|kbpIbye>=i(ogc>wZ$TXom=1>{a|rJ zee}bEE`?LC+63Nu$D@^<2tMkw7FQSruhVt9PG5QY8X3O+X$cPcMaeY#4@uBDeefRN zpu?o(hvF&XCoF_hX}|&XhgK95HjZ->IEw%Sm#=mwx}7}0o*m2+6T@-y=3Fc;)cqZ0 zC5vn}5kOC2C-7ogoOB%?gJF!iP~=|>_}qjVn4VoM+TjT(BH-=tDw65H+J_=5c{;p= zow9^f$sNDBLzMFb#;oAauvMI2a^QN|`OSG5Ij#X z=wYbH(MjbPh6gJ$y$fFpI<*724Vi+A`cv5qY!0K>*|u?t&~Jvjm0Ua%FFwKJN&H(d zNBQd={3_%8tRLNW(;f#BSYm8M&rr@5f*m#Ky<@=-xNrs-3iaWUlG>wj5%1Rx<)f~n zIO?qnSGGJ(BpWYB2F94+{GXmfy5Z#l{6|JnbP#$CCEticKTcOLD5zhQt31d=r^k5Q ziNA|S=hAjG%9T<~O9sXprCy(nvfjl|gaHOm5s4$l74RDzatKD_qhwym5(SPR*J0#9 ziH&j<*?}{+kbBwHU28OamJDa-AiLx_a(Gs#SIWa#p@n<~4lFG##%piB8B5E{-mrxn z0&Y?M?%tN>PRsHjyT;kwjJL?<)_Od7^w>DEva;-OTU87$rSibAK=|f!<8i;&)ZE+A zXG;yhOA6UnC?w?`}QmG`s;rZ)73eTCyGLc4P>4R&(Dr? z&R?pJ(2!HfY9pdOc=I&(w0>ys+7P+Bw;c~3KJ>UUukp4(vCUlP{2xMYrtuHC7H<%Y z786k};Wb#Zk{<7=AsboP(8iq7;A_72TH7|z0S9Oj>k~G@VGLnh+pT7-udmU4&G&NB zTgkiNNrpHTOb3R?7gx?Z=I!M<=kXp2W~0FwVr*PQY0G&(C>ndh(~m#C7n>XFg5!|r z1xD{Q>SQQX#_Uq_2jknZ@Uf!4O{s0HXIPs+1GUc3IN{NAc6u1C)^7CnG5j9pywmuA z+w1GAvG(*)Y;LZ39CD-Fhz)s!`P6WWwp%4caoMIhNsV@d~7;&}HV3_ylV{4Bdi>KY@zwjZNa2Nw`{IMAAGPhS$L-$OT?vhY2|XIgM1TqWmpakdxZ z1zZW?h5?8Rot`SK2IN0S&x?& z_?UVQWE*r3HZn-=0RQ0w2T4(M25V9x?_ahJl(8v*;Hn zhu_RS=&t9ocn|%d4R|*Z`g3jCu195apxzW&Wmt&OE|9{;3i!fm7vB&$;2n_t`l@@6r~| z2}BM{na3MiCAT0GK{r&OU{&&S=sGaAJgG6xO-gL!Ny9T^h(R40m-h&pOS=d&*lf1M zS9IU~%kjN3pcH@fM^~ZS08Y$(Z?>XL=SW*hnWF z1b!I3@IC`Dh2BXZ(zBeusTa|2wXHBh!LPwZ+KK+fv|bGcZ+On!uy-3e7~u&xrY3oA zpbMex+;>H~Fq*-Wy%`)lp|ASx@Sgf@8Cc~Ox+un}m{SzYJ&a<6{l$=1;0JIj^l#*$ z-QY`>fmbCsOen~d>6uGxw1GZb3f6Pr=cKCKT*HHJBz;#M)RVZ&TZ44&l@rcw?THVzMH6;gK6mi=*3K4;MaD02kB^K0Xz{9 zympPO9f%Y|PRoL@fs=;iBQQ(^{Q8@{g7b^02m@zP}6 zdi`!J-R2;0b_j~>;L;_E;eY?9%eRz^?O_e`({M4P+pu!7n0zQY?LMCgwK#I_u|aBEkK zUM;M+_S$=K#Li~-P5oilwFDG)Ezvg=T)YdDFClb_SyCMW70;8ICgZ1Rxwsee6XUf) zOpK1EBWMs-F$F=4R)cp0yA(QLz60Zynd@NTkX`e87-Aew2?0azAfod)4P|Pp7LP1A zSOj1UL-?>Tfgmy{lTQnES_Hyey{j5QRYD2yqZ}4hw3#}*dq-vQF2VtAb{~*u2KT5d zg%AW73{)e=1-$>wa<1=^I18*ng2XHBXYng<=B>^jqj(Vo|=qKmCp|HfrMgle{6o4CW&M=W_G*n?$ zfFk&#kSc_6m1se4N;r=p*oV66x840Euwt}B!2$kLKVwWtDYsXPY?OM$yg%r(3*F7Q zPS@!=eRb(yo#CrkaJ{@3Dd_QUOP`x(PzL|MC{5|58}Q)b@5O_`!=gBT4!)beiG~(D z{pDmj?@!Tr@jUorvEYQJ`kaG+vq#v8kw5=b|xxBgQ82 z>KRwxF!UXY&rC#p7SD}4F;!l0J26(M8odY4PmgwB%(-GH%#m}b4}~ckUXD*yj_Mh+ z(i6i_EB5xb#NQ4CBaAR98(?5MKGryP_v|%rh$oW`fM?=|k`X0$`Ham=$pzw*gi%Bn zHH@O!=S8uzm}j|LJUz_lvpS5Yg%OPnC>qC;c5JSH61#gS`jJJ&qxCmBE=dmnhw3>$ z5gby{Z9~FvJx0c=R+tbKU}9?8#zNp_j|+`0@`c9~Sw>@(N?i&dOxvUt)Py}F1RUWN zr=}&}4!rCvdkXK6y@oC`gcZ2VJ?bn84;WjAmQ){6USVk99tv2(`{3C%ta`^KGb1C6 z43D`Sl+%P$L$QcbgmFWWTW{1gzVk6v!N@Qwd_4%xU*nu9hp$BWBe@3!9Xr1}oivVY zZEsnYef#b2#;dQrZo?PeUXvxx1)6f-&oqY3=2~oTt*ZW`C~;m8^J`yY+-}FX0E<^4 zA@@)ejtTY{yLz3iD2$(YoPpb=DZyFzgCdL2e+S*2Xg8HlIB)_ks9%I2^8g5^mwZ?pmPA+Kd3Fnt{ z^-?%|c`h2&hu#qOaYEyScOJ6nakK?*!Z^|=Waw%YoGg1@69y7Fb3*V>!xZ=oY_)#4 zN(l0jxz%6RISUIbvAn!ue5S9^LJ~^dzVMlIjG(<;dpT+53RhXffUjCT#NPI*o^=EV z4DzBOf)(pUycOXWc=TXQA#C4~>SWHBg>y4A^HHCfRf*^E^y&TB-dPt-8ji)q<(OYw z(YR}V2$zw+r-UnGYDcHJ8O_}d(?|^alVw8dYkmkf2~9XUmf=t7!lm#G*yB-$LjPFx za|Rh6FNDlI5U#S0!ZXq55*l8N6Kg8q1xFC9L|ZS;kMx-e?6Y`ER<(#nfwKe4% zj$1ch)f#(Aur8Zsf*(hkd(h@n+NdVu^*B1F@fR)&WLAE&W@%~N`}pC7H*0&=v1}N{OIB+? zwFToe@(@Na*2+cLIA}CHi@KOY@QQk^ZjUU^>tZhBVQKF%y9rSJT`M@R>328aw~_0*g{tf*itotkhYb^S*z&4K|Vt z${lDW^gMYWnf%9ZUf@n<_508PUbQj5IxTq4#qB#c;?C_Gn*W4qOyf&QG>FJX zz|UoCEc4y;{(>)AhoS~rF4GtSbBu^}@lU>EL`1&j^@_#y*Zu4Is3$)oi(L>cn{JkcxW8 zGP%Z_vH>>b@|SJOaR(piBRU$lxq!PqsLS(0&#ALGqQY%fkv3pqY*L%4!((f{o{4vO zj@KA6Cj1GSoHA6(+^i3fi!4v;RdA4cNXRG9Y~XEv4y_bzxBlvo5$V>fJ&dnT)9Cz!)JT8OpEohm#le6^bzod)&3sPK#0Rz!amR9vEh^;~YU8Ar{8Y`xte+ z%SKH{P=J|}FT<&bF$Kt}EWuul2TZ8+`gCZ}D zTgemHT}<74B5QbKg?^)S|C|5j&*J~^@BdwV|9juI5(B=55sHN+J6tg&Adk4+y672n z-U?R?Bft;Y#S71b6&nvw3PHD_`zSzATo;NM{_%{qv8e-N8XFuagT*po4e38^VJ9w% z0}N!qmgn|_Rv(gQrM$#hkkJ0*)r9mL@HBtEP#z&K;5|TDUP$YG_^~*M%H_N-cI2a& zfe)!nLc}@TSbBkB2th$IRl;iu4;hSd?6#HkV#8R5>e=rj3q(|Fc+nLKJY^SrIG+k0 z&)HVUBq&KSo){kRwBd2V4Y`0bJJnb7OgtS>h++s4FV*Ls;un)(xv{ywQe7 z%POO!KBk$()_d&iXA>KEy1TO#o0}WzJ4RW-MR?1B|6`M7 z^%-N;f!f93MJ#-eh$~b9yvJ1(PY^4{%S9InB!v42&46>oGEsh6?69 zo-o{JtR3!LFv@d0K){0UxZ;{Oi7~1f-O}QkmG#J94ku5N8pe$!SjzJ2U1H56(@#?`C&bl5$ z+U;96T?a6P#-%sQnP>yvDy(f)oi2E*y=XMI&{N>G4t+PD*S+aM2sZe|*nnm+Mz?O> zw2`GHTHF?{-~~h(lvSx#JQjFUH5d=Im-&MSFR~JJ$07XHZr0(;-^iCDJCw-??`1?Cm%2l5>7=Uw`ZzQ#HLjXU@87-GW;q4pS0?s>fRK4DEU4#G?EvIBOOzul9J zGJ^rp`Uib4df}(Q$nrR_5+qeOIKVvsMhHanKNA(blR)v9VTh-l?G7}k?Qze#pa~*<|f?f$mWr<7cCvV255tKL=$1c*cb`BZHGy<4b|M&!!I> z#Wc>)C5%)>-_i4Mjwdt=oP+15ER%I&l%jqT{lN2)cc~X+7N4ohqRhla=#$&5XOzLk zI1tVg-4yenr#XNe&OD($%iN;TMSr;%hfL6a;0+$bLv@QT>kk~JZ)x1h%kqg{xWY-n z0ouT4Zy)dQcI-9tYKj(P^y1upE0;q`d!S+sgBEsVsl#E22tStyYgLQ4G@pjd#w#1Lqx z595u){_&?e&tULkrZ7S?deuuAqY|Pp+`x3byHLV6jL;!v#I*TtL!#b=A){oXnd}ba z(B)L1q_OKj3kHONa|!lz6=N1kmQ;KYdmp#@u<#7yr7hk~DSe^qbw_RbfM@(xkWw;E4;&>UlXHO-3T7Q$*>-bA)C6=cm)$LgacqD7NLAB zG<*&Qk0|VtMFGMJyUBB$97dD(1#9Mw%Pq$00!UR@+;pfA1;F3KyO^OoQB0yY6B zX{}l$gGb>Q`adE$`-`r=%DV|YXz0<*~OXW~5 zb-~k6ghF%i)_{-L&^1_e(s+y`@RIWMRDA#KZ^rk&_a{-AF8Mw*S}&Ma(L0pa?tzg)A^ap?q+(uey&@siXek^)-r-#AncuP%Q~6`sW3BaUPRyoS*GSx3g!j z4DgI|P-f?DM17VW_nZrXw~%8CcvNKN!1Z1)K5G!1XIrRiD3*pB$Ol=SNoEy zGNhXo_Lq1PZK(d|YWuE+{Y-Vu$MVYEXw0stePzLgGp(9}F}%K^axfsE0OZ0DiY!5> zI^n!zDh#41x5Vgm!Jjd1NnX_N40i^{Px&L4xbSVPa<Ey%QXz>GIO8xc$njF;T9@h~R($ zPFNpDc$%CG$NKHq-CXy(oR7nqV?w29cQ}h?SLI%)o`!I~8WXwzSFg(%HC?bw^GPz~ z=}N2nmF1|_SFCj8JP?dvz=aTgy>3&#FZJ$B%q=Wg zQEP84`U(DA9%=q<#m>%#`hFs~33eF!N{cZ%Ij8&+T92@iNpkdlJDxs&r2M;r=alC? zVMl2*UL%CDOxf&0^sgKHnjgq_v}b%21E=J6(H0e`=PieGeE#%d-231?8^i9tayM?Q z+=!asUcyK=g5q4XNOTsM;O)koZSL(z#?*WX(cdG{#Lkx5p|yzc2^e~_m*=r?3!LCw zFy_DL$IvjL<)+lGJZ}qw8uS6WRuX=JV?Lwp_|)enffwxbhsJV79kfTeH3r8lX7n!e zO?7eh(g;`52;}6Qt?l^m{SV^F)2BhCgB!PQM}1~Nup{&##-o~KXU(zUq_L&x8MR|l zv*cLtX^XyqBPYVEigB1SkB>RD|48{pZ7`d#QJyoenE#^t$NkvdS~rXujahqvVbmTP zt>`(1HO*0^ci{xI0iz(an)Md&BlIL;@;q+B5v{V+ykhRsH{gm<91pu;wQE%GYMyCL zlRQW~Q}oQ9#9AA$n84_T#}c@Y2QBZXp?7Z_*Jyk>L9W8m<9;{R=o;d@QhQI7egWzENi$7xvfSq)R~4n-?= zy>`XZ4@30vL55ImcbcLh{TNZX?cI%d^zb9kBj~9^zN=2cU4oBO)3cg44dKCLY>J*d zTV1uW#1Ud(03u9QVL zp#hAcXg=*f;VjbJjEYFf`+#bEa$GdGn%;8tJaewwAxvLi-_dtWie|uvMN=hjQ9ee- zr6tkp>FId%_-TCb;XToqrf4xVi!jf~8OWTX{=i1KsDB>)LpzY8rJ{ec^5InuQuk!up-xwn>V5R;CkG5O4Z^Y|wyl%td5N8ca zMqmTP!-o&z;iE@-6ZsBU4cQ39SP;1gUQ2oK94bZ^QLonx6WR`7X>00^a%?c1VrWHn z1%^EHCJ{a7JH|BhHOQK@n|t)zI*mb}$ZY+9|MDJvB5~g`vNKaAn<_FaGIBN{!r8cs zj)plwn_Q+#%Ga#Z&^_h}Itp;u>jTLsM zzWP6I4w8qvc>m=GznNat^PBlze)iA3^j}`TXG)Cy?dkLC`6@2B&b8s|I$fu)Nn!ys zRjb6(jhituuLY!-5Dbmj_Xy3J^JZkqX#;ueQ=IgqAB0E&aCQ zkouK}ok1qh%8P-=#uos{Gn9L}@7*n0@F|nuwV_C3Y~eu95&B3Lvd%Ro`i>$1UXOyv zKv$yg1$-3U^Q7iHP-rG*ON5`CX>kif)3 z2IYVo!FYIVvW=-kWQRHm0|aP2(8W$P6qVk+4}2wzvY@jdF1UIu@J>@*2uJJ`1%`N~ zQ3T2#pI4?bc|Ixlu{gEiQ*|tA~JVMQl`t*;*v!- z{Epq3gbH@ugUgFcwW(+ubRW70ZG`^5poJ_r;WGSyev1!@>u}b{*ywrOSedt1Mbcap z3UJ2sRt8{fUNN83cjz>{45duL@8H)w^Uh>dL$&6QEd0d-37bnF;HxMm#zuHA!`8u% z8H3!Uf!x62nouw4`Nh~22f*__i+lP<$U$HtuH^g4w?~2yYA7>NW}sSH~271uvA_Q3`iII_J)9OT@u<*ASsmTXQzFiq2qI=$|Z-5 znyf4d4i)p+IOn_^$p|WMXpE3@7?6MieEi6=TyzXw{{$l84d;#Qr$I^WLwVJhS&H%U zym)n8Wlsy9g31NE``L|Lc#&mYl#5r5yHEa0*Wa-)9NugiD6+{{iQz5t0TgMwtSWw#z)>A2Ij+~8aq7x zCM2=}&m)PoY#z!T)m9d19@J~IQLE3WT^Sw;r4lmA_Vz|>tUrsrolP4c&d)AmY57)^ zr)xH9KYjWzc6TuzjXN|Q;pE1rP(}&2PJpB4h{k$)x)F;Dw_L?~du(LQG6yJfx3l9GnzPDDyzF^q$H@=H{Fw zyh~yzad2c54;T!Em+IGM+`s>^`oC{48Q{IUvlIJj%iJ8h^YI{(9M|v0gZrOYNk5_X zptxn7F{*lp^$vzKjAwZBVR&Sh{Nmzb+`fG~N`iwrA{vI`JiRKRbK~Qju`+EsiE#vc z!y}N;h$y#Fh7}68q%+{CM&Am3@HlCj5lFav&}-U|VL4iDLP2k3p8k#wk4>LZ(jzBB zkML?>a}~x#l-wAeY-}5zVeF3f6)qh@C4eYDphVOGHE9Y zWaj@6UTm75(42$)j+%QeSXWdphFmrSCf&yXz@{*0YZ3`1%{9)L+TGbUzhM&ro6=N7 zDper_O2CbcahA1(2YBcb3XpKQ7(i$vbJ3xzGzLJhpj|`o6Yx;IP)UNf)>nczXN+MG zfj<#K5-(PaUu=jN85JLZR*YaYB=IhZNsAW@5jMC^y$-_5l2Dgv0K$mMTJK0};nLu2 zI>ta{@UF&tNH~6a(1}Nn?#GkI4>d=JV$p^u&8>;D*AwvCTwjEvsLX2K(Z458o*J() z*s-?2YvcuBCgc&!4DI5p%N(QLZ#p7a>ze1G|9vj>eet z8-MbXe~e%L@?Fh=o)y0sckoz7uh8osXwK~kcMoG`24m0-w+YWJ*5A|9Q=%ucF;lOp zOh)0th6(s7o)Q=lIM3?Nom=8*bDj?vRPbhEjR9mDOJiGOS(k1nYD#=*bC-e^Q;n};p z+m6Rio{2Yzj%l3=Tr)JH=BV)6YibypAqqvxPpB9F0XOD7{0L)5vDT&!-XN`K&_eK; z{LEL&zLccTRQRj6(7VBSI-`BC4cN_ z{xDAE3UUmQ14`~IIAfiI>R^)$#wutW;{;A2zfn2zI~^!=H}r|n+sJin{z85(bO5wB zjZK3#D5dNRr>Ae3hd(GW&*(XDrC#JmJvQEfmuw7XQv-9v8`lOhx%D@K4|*@~8}BUI zPaCL>GJ!Ssq4V^UHo8pp0h~>lJ>_;TXel01v>)8H?5ez+1q%P6y*VDV8y!^g6IZB2 zyQ!bLO#k$NvgkAOi!hyRrlCyQg#2x}S7iYr<`af+8+FxRyu&lZBi?yAE{s1q9NJAg z7=PdofAv|Dz!SWob`2XkKKgytNIeJdyjjq*e&@o_%SFa(~B#0q|dQLbkXzd|jvO^fgKFtWv!a%eS;}T^NL7fI4#xm=+7E z6A2X#%cooB6=Dn==sBta@K7QoB0D>A;V)dC3sMGO!QQ1cqWD;_+0Xm2mPsMwWi!v%{UUeNmm)5ge0 z_&e9;Mj+@a4{xasm@dqhci25u(c%uqM|sJBV19UP9lNYFWaPUDrG!YNUW7&B8^ieN z8v-#NMQXYkD1Bqm2jjH2nHJhM$R(|yBG$%2l) z03ELoFvv4Ng&e~$?jZzm z`5CPS_q6DxE_U|lUkY~0k6{gCoHMJ4Q{nWel^2O0>Zk=m#uH(T1upPsp=Bkngk~0* z?0jN}u>~-dMvQOr;SEXsz<~3^9LFD+>6t@1=@;P^@sLERNSQ1?T*!60PS@#=oxU=| z*AL$Q{-@+*XbQwjl*e@1gv@F1sozNXJaAB$pd7(4Wn&daEG_s@ zq7e23g|)r0+HKz>56UM(-q>ixH85PUi1uz@)95r>6?HZ7ZW_Jdq32Pao`}WyMl3JR#Lbn3s8*-NzmhL{bBA~&uz){U zK_K3Raf%HZC<58!;N8g7rGIQTp}!~(xPg)d)(-z>!E8l^ZlE+HMAYRa8%p5af(887 z@<#TFMLRIz93SA4VG^^C-r%55;D>?_BLwZh_&{H2KME4$6nlk>_p@WwXR3(*@IG~< zfh#wc&^J7R@RBY5JQ{TM|K_P1kye@|n`SxYFrPgSpAFia>OHeMimjMykJ zS+1%+3_UF4kS$<5^iBL}6s2@}iNp|_KTd*hbq;H0FEZYty#-7;^9;p$8l5iAI1g$| zyb;5ma*qyp@rCfTvlac`uKLXxVrn1kTICQb59K!S(5OfjU>s<7hF?NH!bpR0E6)MT zcHq@>>a%l@okmrc+HIp$kxpz(xwxb*l{a43J^C@K?gB%}GVU+s(PxblUO1fZ!vNYq zCBKk6p{(MEF3z<%Pw$lsi^hG8iSG4!P01B_e$kgR!z|AfD+%U=qoUnuJU|Wr-gsWr z8Yqq>Z%?9RRhg3K?9DR9_@K}yFXM+-&5qAn!@D0NL4|O96REt$3#7l_icU*-z&Tqg zf7~I+j)fb2%U6w=`M`T|aw^Z*U?)3@%=NYB@#vEeqbpirL$T)3+&pJ2)oftc-9ce} zzQDG*x3=?QJb5as^?g1f@;dP%qPQu zjZesgqGi37@E1=?&cSVeg>-ou2G68>S_u)$1npkyeN(a6P|w=_PMMzkC&1Zm-q zaA-(#1P_*z<9*E`&cQnu{B}Km7Uq{UKY$Nj_r17x@BP@>-H62nycRhdOmeH>CKBQK z3cW%8WiFvq#<1sbkCNepV1iH2IBRi7^1*U}{CZXJ3zKE_Hm433RY1z|41iLqg| zN$}_FCBil$-=dg&VJsFMILDK4-}C}`zN#^)2;L6OIjp%M+KnO}oGMROY}n)sDF__A zg0OcZcr*HJrebasUX9ct`ItGPzM+_&nW_6i$qPP@s19Mc=?QpusCJ$ZZcudb=%5{a z&2_%xfdmhNZW0n4??h-6?M9JLSXYO3KRy)PRi?&{IfQWr8pu57oGj`%7F~fJ;I%08V^yFT7gNTJ>9mhJ=MdRjetb+T5xg14$*LoEERiM zRn-4{&l~@Sn0L%q4Ss0OUu2j+3|B`79n&j3rKT!#4qG@?nXxz9r06unDCeKb*LnaW zw+W$OekvR}I_k%f@PzQOcv5m^Te&>pxk#wf(NW=^@bhpV9^Y4)qr%B0%{$SE(FxNQ zyqlJnZg}1uXpFnPJmb=54+=J0TN}cs{g_`^iG}4mnj012`F=cm@7 z8UjW%W|LaKUI^Zkv9huhckZmj%8f3 zpsTsrjb<~w*1=WQcn#tI(&9qkfwnj>Xr_XD*mH{V2_?(g9d98u-@K4>6t}ks2YPD0 zOy4*v0GuDMx@Z4g9EoaGbCfDPK&th$DTkvhi`udLWPk19- zgO++@llle?nV(+}uCdlVQ~OWilTRMS>e{Ap51NbT7GstQe!)~g&FKR@Ddap)HOn(3 z=hejq42(C73l|%va%1X1C!=?hKkA!4d5>h->*_aU>QXlDr_oI1ie}&q-RJB+@llLl zcv>QUj9C`Cj9raUtGS~&FW#Xsg5M!KBKwh`3&? zP;;-?c!tpk+%Dh@f5M0a{mrp~zaocbxIp+mZ6bH!sf8S515#0s@EUy$?{UEk2&>7s z^Na`%(2i8*@ou)ALW_1#x5rC;&W&Ls=5NS~z=jPiglUDI@Cte{VC1$4nNs(raZ`T! z0DNh;H2AcNLcIFo=4E_?I25{$6`Q9wAce1^SZ+v>gg~r>m@YVen z{qep>9;-mGSju;>pEShuTg>-RqBnn@ycy`e2I$KKqC6> zg`Ll15(9$Kz(no#4@1>^Fg6Tc7!=s`Sk;2CUTfH+1;${4Wd0)J1gYmcMBkr-?*p23 zDW(GXFEGp_F?AR$wOg5^M<`=Z7IGdF3txl^7It)r9Wm64al|o|#qbc~ zx>|^`FyNVcA|_5*hLwaY1SmXx2(?7LD8tyT9 zV`k4GwF$x83Q=7ML$uF|GYJ+59~g4dD3?kz1PfqFofy2vR1b_kLs6X?zLW|3$DoE` zjCNrJLePWBb8!8c1SQ6uw(^HSf^g)sLUhk(eo3I>)5D~NKD+f19$0vm)Njt+pbmD{ zvO5_Z!voO*8s+LjAqhUQGZ;YdOu&qAlHe9GoM|6&4!FzN zY>W%vL1T935-tm&5LmKM8pwOs={jAfKVJIE3|~L|-uE2p5W4QfCqw{729Z$mVr;N@ z#MlJ=hEG8cSY%?D@qyWGJY(8d#w=fLytdNlWlt^T#~_vq<0JDC%7ccP4vTK(;!@Y3 zPA7dN1s^2czxqyl2dTKnr|&|e`7Ihvf);Y$zXoNv4!#fSG7Y5rx?HF3LpKouP*{BP ztykjz{D1mC#^3zapNVFQ#$VuNfpU5S0SYNy^I#20|RIH!MS;+=SrsSUu}3igXQJ?^WIl10>4qZ;2uh`3yKP@cqt4?CosCv1Ba_ny06S>ceFmAEFdWuNiwq zogeEyaKQ^M&)lN#@bw9H`KsM)5;;C1OlIG_5`!d$&-BC?j-&nE*d@H%>A7T(OFdKH z1jj1_i28ydi@tcHj=h3dx=JoZRupcz(HhfyhXe!8%|KvhdVX;!@8y9$C7amrMSkvs z7lZ+#B<52{R-20HT0N%9=^aP-FRI~89ONTqH@-}is>;()QG~No+lDp1Ba$5u7OBIA z3gE3)ooi0-x8gu>1b4s%LRJnB<28VSWi{@9{9!!2|A}Zq)AAN`zun?|w&UO&sD-5) zmU(h_wD3-Kpd?y*{v;kh_(ZTi6ux6rK9Bm$oZeY*2q?=s$~QVZ9t#W0l5-^6gImMw z*e2woF3%T?D``MH?rp`!+T(1icV{EJ5q?zix9HG_<`$s6R9p6ZhS;ibH_w-`7oiQA zz!|`TzsJH;&3EB3h88@IY~0ouT4ut?Jgl+ym@?+bh?hZ#&+_D0+`4t!q4elK-VgKh zi;}r(Hcp^iMhQn4v3f0)`zVBwccD+-m?RimL96?PJa}|`>Q8%CM-LBJLNh|s z8NHOTky+X7R;@PFj`^4_S8Z6p%Yd_anSam*%ab686ZpiYghQ1v85Ke*PS5yUtjRIa z65$EnY|L9cS}?|yFhZ(7$kO}!J+DhRw=4~{;1o(i!fWSwfeZq3Ee*}c%+N*X<-R?C zJYERyf&+YJdux3_d-mhQ58jO*{pj!Qg@RFobqX-0;5=ilNd=be!FPDr&JN-Cj@5U` z%Ax%X@n_F@J!9DYCLT_T+W3xxUM|gboN$^6k zp1d->0DZ2McpF}w)mp`2^={t06Z4v%z>e|7i>Ohb^LR5hlsl)nTAIe#&nk{_KlA%| z!9aI0{1Eo->66F7`J3=jHqE^M!G|^uF|StFHsYP1zoUGQJRdL^z5o6PvDa(`X9`v- zbD1S)t?l^uqxv}wh znt}}>*)Z@uefm7sHwe`VtOQTBjpVR!$X>dDwO8BlTVa}Y9=hYAeNTUy59DP7K^kk4 zhNjU=Yh>k3`AF~cjxN4ip44}WTT zbA3JT-TN?hcDGfIW|wdfV-n>XPlS8ud+^GuRV$*ak}Fi^By&u-#GFr0BGE&=LmQxL z^ox2N=3BT04iU-{yz+)((HZDEyoY&bITHB`C<#dJugXFuLnmYK<$o$0BMkUmJk*n{tpjG1_`O)hAGdF(AYy z<+`8355fo*51zx3T5P`P~Yf*|30;EVBI*WknNl8`^qnK5pOUoY^H@0ly} z+v`?iL!uoZIrrG~*3q2Y*w_~RT-TiKX}p9>u7`5eR@%j@`ZSIYU;wSqKY!25#sALq zBEK#}|LdDR)z`sQq|bZy+3OEUpM95Edu{l-PS@${l0MJofKQE4laGDE0 zm>)usvuUx60GkFQF*b|@VoDYQ#4MoZB?*iezw)ryQ4#rMApDu}s3)j9Eiw_@s9BnOpMzv_+9h#hrR0%z5 zGt87CVf@}rBf%a;6AMuKgdj>qEL@9w#SR~TsuK`H%0`IFa8GA3Dn`cc8pn&)d+Y{d z=O;!LcH*#u#zq_}rwsa|#^sL3RI;T97YcxcS$bQs=u?Xf4=rKUZv-HAQPBs4KYyy7 zvkQD;f%(bXSst&Z9D;P*?xo>!UD2uZ&C{j3!SR>h~4@sgR)snsVcXDauMb*l+g}^ zOba$D-$EMw5}bh*VIOnHe4cYg8Q>uOMHxpP@`7^+Ve|<@7557qcc>f*X$WX2Mc7H0 z=fMcxXD0)}TT4m(PEP{~JIX_N92O2Jp9LL{1A=UMs;ue69AI1}RM9sz3?T^NjZiC` zD>gK$`r)ihBMFh{G_TWjx=vqu`pOJnfBLO&{VfYr=rZ(z3mVVP%_3w8i%Bk&Pd*Q; z-;YiY#Y5W)#Eur!>|V~ZvR;H6%$<$72!`&$uc5KY+spw>n@qGnn|%KZlAiHYvNLt7SHq!d?CLk9VKzce8c%vDvM)%h3hBp$z0G*H9nRW8}YyY-~IRTzxwb0I_Bo; z;titD=WN*E97gfsQIzOKSQO5uO2r1783@6X{0^@i_!*lQ@N7XLABHy@46I}r@H2QD zh8q+k7{B1#D39PtcudhelmYgzQr#FDFwo?A4;jMHJAjoh-^iilgYV+8L_VL3 zp=VYYn0K+G`atbEHZMXk;`YFwG>(LpBFrJ4B`9N1&W?@{g8D@G&{AJc1J55et+06p zgB?pV${_rg+k&3zd_S7IgmG$$&s|t1F+Unn8%{d0v%M;O>ZxrQkHmt8=@@ufr&_QJ|Ah1ZP+}E1R63B$*G!OMd<3xn9VD*|XY zJL54iHtF%2uHpqD97I8{><0&(*xGm+t-USd9ZGll&RK0Xq*>9fb_~;AHWyJo#tASG z`3wW8WDUXK>9a?Ib6>K_wB?qQ~ytiU~^?9s5e;yxxcu&`_V{KzYG)Hu&e-N!sPji8@UN~Q)BKau2Bv4x4x_Kwc zRXn;RM;Xq*6YQtGz)GFHR2e(ZJ=gGV!WhHc1sCv=N6E{EpAn1>gn{FI;m@St$Gov( z>YV5iY_h{>Bg{JP$M)8<*jRn6`PPyAd>)+^#bIoRgGta7=Gb5PMw+xMif{jq6qp5&pla%NH2B|TO)1!DDVN}Fu zlpc@{Yia`!^RX}b(6f;fc@yO!?i5Yt!0CeLhw{SaR@5X6OyS31bMoF&?dL#;rTA#_a5(&!fw8zedfEAU^e( z`IuY0sb|YERh|((iryVzn4!JGdG`m}&pP42v>v)jNLIpyayDSj4HEF_Y2L5KuC5co z0AtnIxccQWW9%q%+yOpUA*(AtW39;i(~>41`~J<^B!X} zXI~NO@ly1fu#b4{(GE4s>y>SLWPKbTe=K@(EV?dI^YG!*`2YUhKg0(gJ`|nVj88s! z9G~2O8r!?w*lQicJ>~uIqeqfS4h6G`*x1-n-jCv=k3WgWk44{F7##XG7Wr%}^&dm# zl`&ZDWc_60j&Pu$>(I#wt<#|q&>HA3-a5dd+v(b%#3vru_FS1L36@8(v)d9~*oo~; zj8lXu)cg@|!DDOr#i)sITBQ@(jjN`cjJp^?7b~ zR&#OQ?_i{S{N$k|ZH;13^4g917pcu;!barPIXQh8^0r>T4B0l;Uy zC|W|B3&V)M`qR%;aQ>f(u|zM#7ryfzxt*17F3WH8%OAAKe}i}Ubkc|AE#wEwQmo_Q zy_yXJnVO9SwOUnWik@l?5`Gqg^48XF?Chk0ac{5byujg1_?YK@PNJy#jRVnY=8u}xknka-$okM!EeUkMfgF{c+G`` zD>8Dz!0;Nplg7PM&jH4bi?Yc_*_46jBaQZbz75J@{Q*ugXL9Y31|(pIu7~F?b5LFy zm9ku9Q{6V-#-ox=FvXD&%ItdbKj4vVLe58rlbgcR@Q3aRz5uSc4vimuG9XoeVJQ3~ zQ77|!MstUaD!`vMF)t~f=fE)AjoguA!F*sYq5LAh8>XMiroLi$W$l&gFuoiAl{dSR zI?Ob-y)eiDd&;3(#%FzDo>Py<6x`7>j9VDJTB1|Tz3pw$tS+It1yjov9+APN|5Yq7 zq7MJ&^4I*G>E-XgXHp^l1x`!YLW5}dD&Nj#kztW#~zKD6EynwOpYoYUOZ8bi)|55C9 z_PiO-yM)9j5r}Dr_?(#-?SNq+OkiN487ykq2}=f)L%4Ud=r!}xJsW#eFS{%eKnOJg zv$l~?OcYp6P!|h!B^V?-@Tr5HB$Hg!A;ArXZDB)PnFR|Gpmb%7qeRf+ES!R6p<9>xjNE9+ay-q1dAgcBuPP<+^O71p!O1 zA;;LLM18cw3|sfv0q>o+`s3^{Vn64*#BN3aWoHtS2mJ&$B(z94%(0KD z%b-^2`azorqXO(KpsG)Yg13boJ-4AWTjE89z1sAdyT=KY1h$ffy!Zmw5b}*%%ERjj z$&8&3O;t{ZhY|iJ?5U5?E4dqwe%TPJwgXr2{6hU>S2{32c%v_l!>-@ttyL=OD?$^C z8bZFHoED5!psKKk*~HX%OqM31T%FQYis`x*{?$p}LqUKrhNAL9V~bwyI$fvh^iNJ- znc-_`e&KJ~Va%c%kF3Ib>&lBu&wQWVqWbjNTH+UY_Oi%kF^!^zg<7#V^~MGfu7X!y zC5VYG=oWPBv+1RrgZD|i!wtUYotN`{ww&S_?_WKAxedzUXGJ?+x=8kBQ6BUCyrVxY zCqxWU%+1eL;?IBht+;t(UJK?tOXBdTFIctp8XIjUm7hf^ijOopLG!&KN3(W2GH%|P<7}#JRc?fDIxeo*U5{b9@>s?`wH7NYqIe%*YgjW%;8yitW2ZkB3PmOhYgt)(|7X<|{Z%g)ScXy*v zuf-H$3dIk(P+0mv{?e4&NEjw}9`q1SB(8|>AMe|+(d%|RJ{T{+lzy-45On8)8?Y%? zs*+ddy)&Qjqzo&qt=z`YfNXZ;F+&l}J@A9Dh4cZOvAl79AQ|Tvfktfsm(sv>eu|== z@O3DR3AaZG!l5`h>{@|u!-CHin}`v@p9yEJz!IM0rNDK5abn}l#@ZvF&x0pRy^$f- z2w#@+7>Y-LAQ?#QB0L}Gk=P4|Gm%us$XHb{9*Tz#K8S96*Pa02OTX8Nwbj-562A`Uyq&b4cFZeY;NCqBNi4{gd=#TXbx%Ka8Nypte^b!C-JkN{mi@j*`?fU_hPr% zijB=p(Iw7}I`Yotdmnz}I&R*&6Y~p8DhJtA;1WIt2B)(_wH-y;Q5@|P?yRZt9t%8x z2;XJ}5na^yAeT**t9lpjAmQr7WRxdS3?|NFJjHm8;dp{J538So!_h%Awl<%;>~3o( ze)^Mti1*%o$Hp4Y3L788%TjnNS&Vr_s5M|v6OL3WGa3^VXBmDBg9mE~LJ!%%!G+A} zv0%M0VUInOi6|#a5{ z&sEANqJ-dymoTB$Cns2=VdO#4oAbkSVPNzw~kt+R7Z1EG_zO*sH8w zzbTw+xh+I*U`{y1tJ>neYknRdv|@X6)dnHFtWa_viN0ba751n*lHrFLQ}Gk6Yrr8k zuZ^fI)_@t3Rd{j&e{HMvq8Fm+c$;BNYj<`9QzAKl1FQo|hMNu09s}SuBD%B{yIZSZ zP>iS_7$AGSUBL>)x%xaXlCog};~VodX$4U`y7oR?(wxL-TJW*9#&n7`0JKbVfsky^ zpFOcbjF6DDYfJRw@#9C)Zne!f9z1*)@BH!?asR=?*xuREv&Zql`|o@Ha^B;i<~Z~L zW7rz&;t$@Bwe^kIRNhBVp2hp`eH4!$u1e;>W2F}#e)w^`|Ng_+*#$oE8Lg$p@XD)d z%tqtji1i)g3vP~iedqPR<`cXVua4=8=sS3(#53r3@&z_zh(=;;#)D2UVJ$1P6+Eiq zWi`t=&1T2t5Y`Y3c-KOeGuNd?(#!101%V1+kUMS#qlox{!9$v^4>E(^#Dd%U(WO-2@ z@`#$N?|9#!Q%GYa#(ZQK`UA(YVZO3=%GQ)gp7yFXTDGMS_38*&8v` zCw_xB7)2hZ3gm6D~74kTJV9crx|Jm>uq8CEeM30j2rk^xT z^d1hHcS1M0! zHGT{-()QGWQ9d+)%@%B)3HKN8YhamSPT}imAak9xRagE_qj9k&;x}!wjz|3<@eXxB z2YOxBR{NIM2`h@u%SO@aAx7&UQ6_&=}+oY zYt;@s?Gm<5`k<|e6IsvT_SN@)UQ!{yrJw?Lf7kV8r_Zb7^R9o*35>cnd|jvO^fgHk zoT+Lh7H`~$X$gXO$G|M{aAENTKZ6;jK~z}bru_5+L4yUVLwTtG2yp0i5D>|W zpo$QP0GPXklt%&$;ed)zg$ELb5F`**V1VR7$VSLu=RS*Ulw2r}$_OwLQV3sB2qQp( zcQRyS3N{$QylX|z5Tx1NN1I^k7-{e<1MZAj?&u_}o)$T(lX8j$2Fg7cEO0WD1;BbI zcbVpxA{-QkGvEY#atBQcC-jpx@^^M}ZUKZceMu;0?A>pbg`fzm?8zXZFXMJIbRI#E z8)1nC%`hGTR~y)r&vk1&EXYU@Wzk4GQ*cyU7*P5w++){zA@sOx{b!h}9|&D2C|J07 zVTDkm3NZe84D~KTCBoR*B}O-lWmy+WkSUG3af`O;9^M!jfXNS>5MqEm@TM%_#W;g6 zX5MNJiygjGA3`a@mpd+)?H?UjfMjPMc~Go^r^IA0YtdMnse1R`^2$=oFVDs7yo5k4 z3Mb1Fj>l9wyTbM1sY038={jAfKO}u+hA+|lzr~n^Vx%y9Vc7D*%ZslU#x3}W7p5$5 zp*<|fC`5Eogu>-Pcm2D#z99L@ryfHC`N;S9PKjA+rcY)6qBMBd$OXFiIr^d`5 zyvSDjfJm=L=*gD)ks*9755aTAD_pMH&LW%oP|mS%_@YMvl2)Ao<%!GA(Y0G z6Vt)jRw!_Qn2jmwD~kBJg&R?>&a0jg;gEQg{y19-g)L{}ATJ&46ZVl^^5QGCxu{fU zJ#;8J;k9GxX9>@j$+Gz7r0@?y9*^_#F= z>i0Mbw)E@~qY@vx8I|dV#!90v-p7U#&N;&SVsxyeo05GbYqIeK!_nwiRc$W?=L->1 z4a3m9%BVG#Vq&VMI#Z?r2MEVkn_G$T$+;MttfisxRPxr@f!>2hO2!dvQQW1s3?6QH zM~H`u=VDMA9ub@bkJF=`#uslBl;aq<$UmyOP}Gaht8GKW6}^k~MmTwPs4L-N!<6sq zQs+7I3*$_ywHf<8JV1`Ed`2b$u5*-%6LNZY;5;pclR)MwmbIbc>H)Z-h2P!_{A^Yi)YW*Vr6+L z?%sVx@DSc2YpMTgpx~74##0Mf3t4DF^AMSdkd}-EUWFhZI5jec0Va(I9)L?iaWi%p ze^9ty7@s&x438WPk&~0;mAtOG-Q3-aAN|9BjNJ zO$F$L;g6CW{4Wa@$jT_tiAI2N2hXpualG)-dvdbe@Z~d%HO~uK@8tAIWk_BWjsiOh zL~(9~r3j3A>rciS<0SZs@dLVpaiiJXH6Ossg&q3LCDtHY8*6&DqcK)}&@#z-!vjN2 zT#7!NYo44FRRYB~o>$YJTQjqSq%4WX^aYn4)je#3ICKal9_RPaZ#-<+jF@Lw0eh$+ z%0^w681`A;2o9n*oS8LVYG_`~_)I{;Os=i3c~e=VR`*&E`JJ@{o-u@3G%W-^8b?B$ z(n#jDqg#m9(hoc}d1g;tt)DPTG2eNYc}7S{WPf-9#?Ei0Jy4r!lY6Up;GC8iprutDgt9Y=dp429Ah$uJRe#E9cxZ&9PkDzmnIWO zHRm|H3PUS%Ud{B__IrB{`*928uCyn~~`sS8!rYo9Tva#gXzy2ux;YUA@hfkhst-BNN{PO+y z5C6-L;%7g9H{Sc;V}Jfg&)}~#7}?rt9bf+GuF3S zy1yM;TcS@QlXyZ3rGjvH(8{^_MH_mE{xUm9NW-eexD<^>P2*qF+?-Nhr{lG|cj6mw zy&lU;gbrm6XuYauYyj!^F%!BF)rzCcFrNtL3rsoV)FBO32J--(UU#U+xma47 z)41h1L*+8_@6z;-v4XF|kNHj+@cg@X@5Y^5x1(0Cdu@jC3p%^8xuLdjURc{>$2QmBhw;vhsMMKj=QNlM@(sT8jB<9m;O*beIv3Dcu5-^Wu{MDU{CT)!j9qzduhJK=0N5V{mFKwL6ql3JHcJ^3*izxi47BcCmUmpcO>)^ zTH5VtZX6cgZ-fa~{q_O_zXT>W(WzX+(WO%pWozC@mSKFEf4ZS@6Zh2nJ(an)+l+0| zE<)1dF;5ziyb4@--|f@A0am+xnF>sIk)NBs;Pw}!7q$GCn1J&?<@#f!&(;A|zBYVa zr|a~!NtX@@IJdYI)AeecNtnXug(42a2n@swntTXpBK!ydsSL?ojxbmYCSqcQb0f?E z2mX4eGQy3kVOcz2&XlQJNwoA^jDdS(6q(_H?hc60fWbK@@9956)Uk8YMhh)O*S9y~ z(bLDVxwBy-2i`HX2O%I|M#!Q}7!U@h6b4~TMIA6+j7_wUzTsMZuCfpYP{3i(Ldiyg z=_2?QVFT$u7YrV6F`mQRX|IJ3!IZXOOhKTx_Z9unZy0ysU01w6G9*DnfAo)WpiNfb zc@Y^lkXZ;+J7KB_6S(^$q@Y|wFtN9i>V{FHNI*G2n=wjR*~+^bM=yG{Dnx*y|FpwG zlb!(+1R2H|_#q@C5T)`?4bdlcaOf(Zgctzi?yK62!i$T=1qvWy2)9;zSGQ(GGy7ITVBT+m`w1KPON&ZwGXbZH9?^mCs!Tpz$c?h@p{?hdu>E&`h zleiCk9}sWf%kRILxSLlB{-2wxD61%gulenB5>IrwT0UK}_{wF}MC)$fT8QPPMl3Ag zK_K}-JPYM0vPLScFHDE=%4S0aN+Nb;qmZC_ly2i=>EQ+a$LN69GrS(Uj)IbW@O5}9 zN)z}S&u9)_8PI)TJTWl{7szTy^qC#0lv#u{r0wt<+JnNr)!DIvWMqU8e(dBH|Hg=+ zeD=l`FL4+v^<@YGYEVU0q0*YOBL&J}eAL#4h{-NMB6_q;YCkYOxf}db9HHBgBmU!4w za0U-&IiZ+F_81z+D970|7(XN{pwJh<9p23zRmG0%Gqs@{)jI8-)m4wFX?AVr<{^xH z!z1c%U>pF>C(&uHMys{%F-%3iWKW-=g%bNBjt|?a?>t5|W`r&CyBL{<7~3tGt7a{G=>9>al&1270^+L zVN^iY-Pu?TqTDSk&O3BA#$x6^o@<@S^if( zWJHY3tUoR;@H|CHH!6H-$J**M%j+1YP!uBAqDTZkwSv&a&Uj>8$;;C-g0JSR`hwvG ze$sC3MRRY<-Zt|KH%vdFO>hFn1@DoPU@_z~@)EB&GwtZ0rT%Hn#(dX2V@}!lYkXtf zg`)A;UN9JJI4il2>?=CRc{XeYq<@^Lg~u2$@_B8@!MAdfJfmqOf(8XOk+lf%HyL`y}K5>yX%4tv;br9SbTWz z!+7-Mf%=SrGdBxBW4jn?)NkMb&)C@7jhv%c$VZx0XY!`N%4F}v03+G}%Xw-bjaTB}{+p`bO(C5D!&XvK0YF0P2q z*3_O!d!sHaEXC~njEz?G&E70pe=ID_49>J1iMg4Xc=eUrq8()``8flQji7|agg0z$ z?g-9D_NwANHfgd}JrR#3lpf0bo3~bM_+q`Zv9=ix9uUg(G!_>yyvl%!y)Uu z^k}(s+t)R2oI{pI6Y)8XJG4Sm%rK=7B-X(g*6>cj@P#2O+lKdaZm_i6$a@3h8Nbsj zXt1^w91k((3ZH1VP|9^V8jRr0+)+V(54lRxsq=Zx>ppx9TFkCiWF}-NDx_}8p>N#c z8SStvH>d*|WqC`oP8xC~H#j3y5FSZcyvwir{jz-N@4BE}_B7L^@}^jQLbGWz^cGr5 z-+4~oeMXm!E@kJVZpOb_tC~h5-|ge+qkPnc;T2s~VR&*RAHy#VDI|=v(D6JD$~9Mu7RB443HpsmFi zn4c&Qc;~SKW-3@8E{E^bpJU0mq#O*MrF@!j=NT8TCG7o0?_=Z})*P?L+}x~Xai4jw zxdAW0gAZe(!}m^R2y#3%i!{j~R7 zU(kUuHo$_l1N}qy30`7YZX+LU?wZ!&<<%Empd56W@K5*vBgy!I`#IqSXJoQo``dy*``3z-z-cS8cN1WtrJ77+*lR_cqvz;Iy( z>`Y2QD;XE;5`lpQPBJom7bCF|K>uvSfhi$*iI~7Nl+AgQ3FOkA0^tjk4MP)a^D{Fx zGfI6b4C?*hO+;oqT z`>M7g^btA}&p^hNHgP3xsx_(?WgKur0Cis&8@-1x%a|f`0b?IDt%VeeZVQp%f!e~@ zGk)M7<+9`6{Zd(0oLUK*2Pgw4>U2G7GYhXH;IH2-V8A!e57kY7ik)`GW_=P~RM7Hx zG8PUCru_8HJ0-QiL6F3otfB?qbQR@fdLJB7rYF&Lx=z>Wccib(@Kvu?|CTuq&HYsR z>~E6pi7c20I(<$aZb92VPbmN5^inxVK3^ohe?d|3&#UKyJka3ZXqF0e-a&ft?Tb?8 z;D5iVFO7ORe(-~D#lQWxe-(4{DAL7~Q7niqqu?rb@D^cbp|z%ql11PTR;YkD6GhZ-%~y`7bP(l`3XA-pJ$zQiT`RfRX^ip( z7@r?=fc@iGUwz~aF&GdgONECEG6{wWLOSZ3HxCtUpgzg57qnfqA=?#a4+RFhuIgli z4zNzy<`NI3Q#@NZJ4f=H%S*U3t|y1>z~c);2;L7UcEJ}6jpb53@V*)m+`(s*xZp9$ zcf+PQ@5>iBfg+xS2YWA8pMDZg9zC=IwYk@djg3v?E4WH1u)D9^iMPM^cKqOne-XD| zc~kN_o-xSh$C49(8OB`d7_l*7`Sy+Y_MiMo+`RdUWYY84+1j$PK~1v4xK^)4wTfJ% zF_|2VS6;bc1#+c=M-ZV1Ulc{aP{y+cEc=y-8jOWju3b#gLabYPY zG~W)o&FHqbqP@Es&!0Yu2cLWtPoF%rjKyZ3$~0l~AT}Akj&g@bB%@7CN3}fW_a`;} ziz_S9m|c)eG;bp*Ml%$2%%SP&dQ1ri2=O;Io?eO5)q0E)!jJFMDeopsUWPphLm32D zxXGX9De^zEq~&DMCTJ3}nvLJ0L5GJKf|NQa2al1x-CcbjvVyc$uUJ{ieBa*Q_PIs< zUf;54t=@>n44yG;6uh+Z9{hKR_7Tp4!!wHSYMrfCP<8wx3r`r}7@t^>Y(z_OeaJAMj-2m=*H;#zL5e^=_ zJ2>dZ_Rgm64M(+7cZg0+H04d&KLoAPtx9<^UVH70m|1!)s*OeQj0y3GfmfdB*3Pcr z)7e<}f(7Zk{Uch&HdcW827^G#rJ1YA7_dohkJb3shR#tB6UPW-bjE%MJ zc>MUe+AG@8>BrV~Q)^nyjprMxr>ker;@PtewFl3%LRk*~Dyd&p&zBkTj9WKu#?4!| z94Zfm_0rOE%+D_v)||OltIild3CB3Cx+~Ka_n-L+K6@=>qbcj5^vuARFh4gFH*TzG zd?suJV2m2VXV#g71Kix&wxJ3mB(#}z5BRaTxS05Sc;NLEI)$Ud6MN#IOow-`Z)~Wa z>sBVS36l8_A8HAoInOG+EXHDMYg50Q!fDn}!fD;7t;|!_SSaNW36-k$AqULP&Z>?X z^?%N^k^#`wN+Gc$KMk}?)`VGr=Ij;H1hSGDv zhcz;CL*kReJ8NF0-hz3Sh6T#=8eFiZ9q=k>1@l@3QoP>5xRAyu+T=}_qGwR-g2vHL zaGfSwi!STk46&Quzym9dp9^g8~eEaX-07KL^(! zFZbBoiU&Q$Sm-9txevgAHJh5DHP&w#iZ8|_(~En+#JV6D04PT}O7xlWa!%)C?9yNd z481{2^?-L6q%i!_KJY9JUn$=JGumUEb1K@AE#v<}KLmYFc%WsW)abl<2>^o zSTe_~b5kJ&zAz?SStoNKWomSk)-S1UpYzS%b&-nC>-1$Nu=?8Yb)Bx$*C>rhz+I4FJHNCf;r>NzW0W>Ft|&o(5u7Yk zpv(|cgc-6hf{erD@p3^pJJMnZVNWuP1ZOcWEqG9Fkn9D-3u3M$*0(T4Ghl=*m1{|XEGnZr(2T2tdMDSTk&-5c|6}-kNqP;HDGqqL%jZi{btY{)1B?b$S0){DMfzK=qcn4S@Gy`82 z8-!s&@HK4CIPXjNqCD<{`UG5Zfl3^B4(=9SsZs2hCCrUsqW`=gV085^?ecWx23Pl@YSf*ujJ(9V}r!^mwyjZ zQu{#~~cG<;=!bQZ{JcGrs!{Ca?KzkjIM|2%8 z50n@vIVihO20@46ee@Gqg*xHGBDq?u9=Z(p4GVS@Qt$!j_3;Uzg;3OTCQkB0yqQq2 zor=!FC%njaJGsW9*Xu@4@<_RiGK^40$(xWnpzE|BKIwMDZ!DMOW)zGKC=@7bralwp z3QFO^;6wGuTkrt-jADm20Np?$zok5Ne%ckEI7+aJkEQ{MUxZx2D+M0HZ~ zdEq_Bx=kK<>qHEXrI*a{LEkW{&&)@qaVy5B<}7a@|DbR!O*dj>qM@7^moRX_U*TsO zH?=Vh2}T|-aaM-_N!3wamfkxG-Na|o5B%4px9h&Q{ zH@^|JS}7*R&Q;z>aPH14uiSFzQNWK!Po+8;Z@lq_Lv0S(ORs1z^B){aJc^5M{HMSB zpW}c2fBawL{>PtK0mYnQoLhUF@#w)v@!@+vkDvYINAdHY{wUs6zdpS8eypxO6P^%4 zPB7Da1J)N8l9M&g7*s&xlY@3_Z784cXL;pL+l zHl10KCR#NvnC|a$mSZy&qN*3eCUh5?1I(vNC`m7rryU!cTd}#Z6RlP!wzsyTTAhwt zckV`ov$7^Is_e(w^XH;LXAY6hnO|wB1!vh&exMF$KAj&&ud`<(5k?s33{e5VVM2Ef zU7~;xZm4V(@tX=uQS0r0vKT+JdJ*5*G3S= z3a_P0jU#;_>}6GBhq3%>U zp|e){7c4a1?D%Ibh_?@(hlJ21RNpUt`L5pG6x=2S zi{sc>-;H0t_i;RUxEdQJDz&N&UvK6=RXtv4SV-K0Kf>IC6hnu*SFrPIJ~YpOfk{ z;RI`{k2OiV*$zT9vw37s@WVg=eTMf=Oo}h6yt&!=c=fec)y|6XeQkYBWsSNVj9c`D zu(>Ub^V-@*?Cxb)!RboL^9JJ?yq0w&e2TRfVJms&_KTLV@$~>bL#Jm$R0q#wjS)r) zj9nON;o&Bq!ee9s#1!gbUCtR;JAyMCP>IZe!K~AT=N&sd zavH0c``%0`83$R*-h$93)z1Z8Wc}(nqB400IAOHpK6St=FberSW;wi=FKRt&TpQBB z6Wwup!#eCf|C zdi~=&V^2SdjZYY)s0%vbjV8uz^g6U(WvQ*a349A$51rLZnvdwH#G8c^ya(LIF=Xl! zIgqi#qma3Ve2M&t0Ubj#b>gktYPZbm9U@U_wGkM=7wKXCm-V3_qimp_;MHC785S-=ci^chi(XyA4err!w_UJe zb2moqy}hR9e9}S26B-UK2@71F>ql0nWc~I%J)<1P&-e)f=sP+YQXvcT8-79JJ@Zzz zpSgt0NuGQL9@921@R0Iew3T-bk4`imhxT^e+v|vzXzm>&e~Nv%QQ1b?#@d35kcjm2 zNcsA`^tL=YgkR#ps`)Fr(CHAeUi`1!i><9a@ebznson**Ui2vkHor33wAq!@PPY}v zXJ22WqD^0P@&E7p_s>r+@K@!13D?&lfq~bCuj_Q3zD8+CLeJvLa?H#T7A2KQuua0c zL9%U}&^-%7B8V_@twqh`VLdDk3L}99RSCoF&f;AJ=G>K%MBI#k_w}7iFPJzYoFlMY z5!`}F`~OUQN6{}aF?xsl@oarH?mu}L?S2c_&MJPXZDr)g9IAGLccexkD`t8Mp>Hm@ zDX4HLJ_|I5w-GE5)-2R%9N0OX?^*kEiih^d`| zE6HJ8bYEHBE_N%j7-3P&O&j|33_;N6w*g1;sx5}|89Rtla3xU=-f@P##v_G$wNaNE zYPfsXkowD67r5Zl9_6wEh22anuxQ87C~@Mo_?nq2a$_!sK z^~T?tuQADgMt(a0-?98StIw-Z&4l5kUptjKuWCD1M!=mXs`8fya_@HYZ!EWUtfMaPu3-jKtWSjI@!rOk7 z@O+Yx&QAJzRWMc?@%XtsJ5YOb;|sea5{ zVe!60Lf>)rR3|VdqPP|(7R-B+vAV*E^yc7fGl$hyyHS|;1P6>_^d4m~A)UC?NVNmS ze=m;J4$hMTsXWH#2XWYKIaFN#u%~j>Mmz z-asDl*U%{D1_nb$Y;})nHZa@7!G*4;T=LhtnAXez;KxJ$?&*Qofus( z(4C(j$L{vJVfyxWzZXCF%YPH!`{92R-}~-&qBJ=XySuwlDo@5+Z@n3JUwbQRjd|e@ z1`EPe6Bb$W#PMOu4k{72q=A&An$@*t)1`mZ=ts39_#+xxWKVx|Y z&yBmU+>Pa>JHlNIo+^zAbBR)LFHVozHpH$yeHcIe@!!Yl>Qm)I#+>k(SU>&A&*I1b z_@j9L{a?qudmqFvfBDOJ@7EtF-)ihO_tcMVje9pH)Mn&V&PZefl*5<_|M$Cl@#N8i z*xr0@9KcvKH@^~<`n={^RbbT^oO8Yn#udrvQ&U1Jyh6YM=8IMi!h=q8CmyLBppXfcH8KLccr~9M}_m`N!b+H9FHlKfEaU_yPUZ-GD_$>%|-Bpnwdx{ zADYFW)~Xm9Z^q){lHfZXE6a;9JHKc{4Q;@fwYjwsvnq?QjEs4%g^*F3vAywJIFn&C z%a!S<&CI(jys}DV3^0UcKNjwBh8W?|@IcM`;H<-%Pm~96Vf>IcGeqPF21am0nNd($CY(eyREgJU`hBw!g~6AM&UQ%s!opjqT8upM0tuQoMFwp zRN1T{n2RTx3(P~pUNZL3RAg(~2u;OE#(7s5jR_;#624%>6H=#va+q`edhz_(LmOIH zx72EQSq;bT-mc|)HVjU{V?=8SGrF_8VY-BeF6~{{dXlq}@V=`|S2gCtaddJNds@q` zudSO-VhCa`GnW{1)*MqM!Siz1a~@^-;o(W_wYu@)habg{fBaLeh1llVwi zs|lYF?d5zJeeds|h+hnhsu&stdpt=UN>=zXH@{%dEpW9~ulmd@j9&9|bFnP^S(u;K zGrWui5aA;{4_v6K|D-}G54hlS_FfUqh0o$q!CC@i3JE@imlilq)D7~}U!uCOrsph7 zV1@VI>`Wt;mX{r#aCv3XXDI=5F51VsWoLWWYiY)LTI)T$K3Vr+ghP@3{Q0UC%)n7B z-D@BC0UP}AT%(WlgLN;V2q^>aEY@ta1zyZ}QociQYEFT4kXse z{CP4C67}#dZD9`ZN&8a%KvrUG^^P*SF8%SDMlm)Txfr*}*r2kqImP$9cnsI#3vwKJ z_|AL$**NApGv%D;Gi9uNJKrb0TsC?9svj%Yz^K4|aFIO4`)7g=xS%)nEIrP=rUy3S z(-;_e#yhO%@yI8N0N(kGDeG#l{{>@Y7rv8^F$1SC(o!#mQRGkNAjdYeMaM9VQ7(1S zPTFFe6n)HlB2NQ8kZo3?KHBDf<)<(5^V=7jst0+P&%CcT(2hc<#JI9i%6bIgrA+iw zuTa^b&s3=Y{Cn_SiLr4R8gpm>xj`V0)sXP3lxUA|}RbsoxtwlUXoV^Vq(=G;qubZ`JIKtG6{jkza!N}F`K zxR<-8l%=~iU4snzpuaC)MUKzAKAZQqU8LgkpOU_eGQR5cRkRf;=-Tjgovzc@C_$?$ zGxexTkR6*$e%T|Nj#HW2Yl z`ROZdv;d<^(DpbY#8C&X+k8j3!6?V>t`rzDETTcIx+nu-8)1`jfQ^L<^(BR&6wYZE zJYDeMu zg|d$^ve%Q~&w}1N{M7~)alpc7rwI@EjgW+(!q~8*PY_p$?D!k^?o-+gOj!Wo0p?^J zL%2k-hf)(oWGb)d7vW9_yMiIoyO#t6>OepS&k>%1A`2drMBor1qte*r?5>xqsLo** zShNd9j3u~9=*#prU|pYHgbWV#p!lOO7LMg-2f)D>Hn} zHq!9LBsTr}EtmfL)TRHOuAcuFp0Wo?my!;P9*bT<6W@C4Zv5%D-Y`v^6x}m#I~V+-HLY@&KD= zP___W7ar$L6z0Qt5YtYS9eAA63h_CWt7`T8G`g*=Xg7Csm(3vJC#Oe}8AR((55?QW zqg2m+ud9Xrp8Bjd3&uVxYqX;GC!?eH35y2r8uiAF!b3v*k~#%jLLUx|V9Y?NhCD`} z>A!vs!V}_cvfn2()X7!Y$Q)d?|Ez284#HjGwL=I-3?lt*Q*Gb7fuAa9(gk9g4#=8-Cpq6im=2Ltj30>k*2+KCb3sAn$`&NcCwpn^aB zM}E=B3T&!F{qOJNfzq-f)&hs*1nR?xa&XuYo*Y@eVN5vVhrXaN1rP9W!TW{5v3Tkh z4SQ!jXJ{4PWt>5Vw22HNs2HDYKpkU8I%muXmdXQ;AEJ!)nMvtwh*tw=BBlJn#u~iu zP;L<_aSECe3(L1-ymTujO0zM$ycFkx--jQ(FSs7s`{VZA*KGLWd^OI2!w`cplyije zRz&HC{N(;$YOKx=)DJp^^1B=}3wTYH@V&VI(XZms$M@p>cYhfleRMB&n(gQx67udaHa45_?Dd2WHvUDA&;J)AH~l0Mm&7dL}$ZX2qCj1LB3AcVl08Ldft`u8&K8;!IdJpB)H?52D-Ii?(2u zp%Mu-3T@#6Ui%u?1Ig0+qBSVp*+_>>Hxbj7s&IkuZ>&L1Jf564!&!x_3y`P5E5aIL zAj3#>p}A+zLE##P#Z%4a!vhY;*P2AMLDRr=31jHU&{6E|tj6G`@@+Jl7hGc%$vutXcn8IMFb&cu*KY$NjZH@YjWbjB&CDD4J zsmeZy`wt$)-~HX+$A9|IKacm{|0F*7_(426q&uC=q)N$~aZbj6{;7zZ{z!t3y)*x74EtJyS;unwXu&IzhiI8$uiSFK7oMrf#D zq6_6acn*HC&a}ac^{3jK3h^P+YsMQ-yf$lI*xnZ3)Evdw z#kpfMGn^-xUYbKADB9WRa57l?vgRGt9IpF)#t7aI4d4u^Rze$0YSi)P>$A-yIm4)fRApxmEN} zFF3E;q~DC2KL>5hPvAPp@6UuKeM~xqe3QBv>mi&ESn-TMN#<1P#?8n|-S95>gV@4vc(`DkDlN*uqg1YivmaP#Q zz=O4eF13q|$ToN}CpEr!oM!(M?pI|Py2bT5NptNtQ;y4*kzT-fFxG$IRlNIUr2?-% zThEtyec9>r>bN$1U8n2xbxR`h;}R~X8WNTzq{0kOw19#supLQlYS5kl|~qh9w#g1gTO(}EbG(!!_u0+WM* za-W@r82Mn-ERfkbb|$7rs0Km@ARN(O!aa1nBN>4TC6R8hlz0l+$ff*dth7<}6h*>uXA7A;;;EmdAjTMYOc69x z7Q&MIc!H3ir@|3-!4o$cp@uel$FttFan#yKNBvZ}DUdl#1VW$kvJjz4 z44xMB{l|FbckdoLNl&s-1Y5ml#R@y}RUeC4jBez$Fe&(g-_(J8!uacv7ggSgkHSqI z_fB;6hxULoC>bb=b2Qkc4{iWk7IGxO0nC9B{YC(1j;WA@7YhO4qYs2_cC54T!jK1U z<{38WWd=Tz5yKpUHD!45rv)kf-bbNu!Wdqs>vWwylfF8`7am{w{9TumXywc4)4%@M z>8cff#3b4VALCQiLGB=33-dGa#_P9Ze!gx6Ly650$_@R;BZft=X&sq$7v9Ocx!BBI z&CqR!&(k|rlEXLk2d#z17d#Y+gEHWcsfZo3YyzDg9cN)p+w`XCF<}x3rId8siqLV+ z%)--Kb%_S!K>*L9EQg)ZGh~LNz?I5hj4C6eY%Vzz`w{OmKSjyUC;&6@M)lvGXM#(wvk@EX z&kPgJiOKU^QSyk79`?)w=?7=%91xmHFlCG;HLjeG1F!NX7xBz7D{uu@jf3S9@!UKg zjj<8mB=6~g6|)lh~FEk}Hr%XXh6L&Y0l;S2deWefJB zV|sr|_l7Y}GDf7~C{GMq@%_f@ug22SQYiw3 z`X^i!f>*_NtnPxy)z~p z*>?njsS?I)#s?f{7x}ooJ*JJ9cxU4Mh!GUU7Uu*Vr;)~9kjw>8Hbd<7dhH+#7RGGP z?=iv=PFcCnTxV_^9_)J_vzGE1DeAX3g{ck5et7dB|Mhx;+v7*Ewze+#9Er|J)>Qkz z!71UoJ)Arhk%3P|6WT$DM&N`2W^^3G9AiwKDEqWl(fl_(0dJHDCl0>SE;gXqYn9NG zBY47cfm>+|g|;#<7%kFMl5{F~^gVwrM89YdXXw@Hb+;9-Jn*{Fn2mO)9SF zmRyVn=doak{LbcsVbScqLy)0>#mI}Y8a%@w1Pz8(gACB2zTnR|;Dt9cGZ%O`(k}Q6 z`CuFEcF#tvCr=)Uc62pP=W*}e{rJ1T`;YPH(c{?O-c_F;$NTSnpwCs+k5?shbv&w- zG;+?*E!azIeqm8Kffrhax2KPIHM35Fe!*wp3shXl0IUTWGuGjRSZmDG)GyH%=%wfZ z;REr!f{t;{B3@s3J=JS9uU9?xUQeRjhZl&ysf9K+iGNiqWx;z&@Hw@o3Uw1Q6K`6d zL8yLUL}YD`u`RvMDmF@SP8T?j!XLiNS`sfmHh=&tJjAFML(j8kYhK${YdKH0wsu4t zwv8jD(uC*#qRPB=>y`~q)B_!4O=H~Em~h4ro}(DGc;09x{4G&ayEk3XZP{vaoyXg}510N>&r z>q`a+JfU0+Kzx$;q>jQMI4L&@cZcS+*M#$TR;Qv>jQmFh;>Mm;+Q!nWkT=8(ailz#pRw zV-0M9L$US-&)K|c`O&f&9+HHw%+RlRI5FOgJ9QJf(rwViyWjx%pl#OQ0OP?YiFLW# zsk+Ih&gpJGEBaIPiT3jq+$5K~4t#*&r!HWpG1GU(?dm>o&X@d`iO<0p`riP)`Oir$ z7<{?PFX#rVFQOpDBPkkQeHFn9AF zbBv86d{Q6dM;V2#iHm#4oX~%~!q|L4h*&}#;;EJGD(WrTsk%Pf7H$vP$@lyXT(j?Z zwIK&G?ilZFRAt8lup7We|9oYATrVZ-Z1~KdznSvk=fUWok_veLQ?D;GeO~#0jO)v+ z>+{NjQeGRruG4k;nkBrZrX(=WO8CU%3S$C0JlLUZMk7W5qw%K%sza1FA_y=nLdn^v zASMO-#Ha+5Mi_uez!(rD_+;T~G6K`nLWNyMUYwc0=ylykBr10Kn6(aQF}p5yTe}W# z_;B@!=SmT?0D+B-+^(;N*Z~!5f3GlT$BM*p;*ecFloHW9n-nvkoVPA)q&B6-I)kX^aDj5GkiZ*{EiWp;HNA^4X5mraSy=IYwgm%f3NqX$j0VpTkZDt)NM%7tf4p;z zwhMkNf`BUmZ($4set-z&3|?F*80HQ^aNLSo_mBF8kArrCGvr}j(4G^)0{9@@VNgvW zO)y~LHNcl#%uNd}9C}XdasYmvuG4jTDSf4euff;fnf|yl73%O?uHRXCk@ugFAbwm_ za#atD$@7?>t;E0mH-8a-`By)PsnSGno)hwb>xI5B7+^fcuSQAGFwf0u#szqaNA!@TL zTJYlupnU2lN_Ea_8ZTjZA^cW`5rZdH>Wvr~pHY(~vy4s0LtW>G1-ScWw)%xmG_Ys8CR6Y zcp@Q`BD08NyG~>q<^NvTwi@^oF#IfDx?nBySaTw`t}rl#ivqjSp>C^88pNPmaNCM0L19HyZW zilLa-v(j`-j!TY|oJ_lE!{K2+_I9>nduP-5F+E*XdlxlUcBg^r^-lcs$3KcEPo4-y$MNlNe#VcP0ZtCTeU z!V!%-MifGdo8pc~9#=*Fduuv=T}R?echL(W8A>vr0)y}cp4PJ<`(OHIo% zg+tIKA_{OuS+zPVe4dZ#+N|jgc#1)1cYD+FH5;QSU+AK7)Vx-iJ{OlcBib}M&a(_T zkKB)95JSCkyDn%5iaQL`7_EjzD!MljmuG#gdG>T)FtmZ6(FK2?ThK496EyE9%k>zY z(EQQd#rq7eDhvj!`!LFPIxW#YXv~G@Q5pcCOJHFdNTAcuO=Q+#jHseVcxsM|{_q?c z%ou^Ery7rf&SaQZeNpFG+l*6^ZEeP?)`##C49d`J3}45DIaPmH2hcVm zey~xjDmsey6-v{0-g!5E{Nta;KvhBG5&GRnGLr$Z^q2bjPNqg)nW}mdr%(ZWkhJbV!g$cM&Gj6anM`lFr8ui z;CHMu32VstRpd#zKaG2A$U{NvO@3+%(KOO1luywkC%BOY7bb4yB z{(w~QS+9$ZYfiG3q)oSO-4JbEu!kAEoAvJU@{;C2NoBL1X1qduVsk-yU1Qv4;|QK& zgmfg_Bc2lQcAi5Q@oeNb=ZRsUdiB*;9oCS!hcVdU0`-2U)3vdd?|ADn((q?Cyx2gg zzT3zxI*fsibI>r1EG;d>?c0PEoljV(gUltK^U3BCV8&((4D5K?I_$paVMlzQ4UWJL zIfD(Dy?$S13`fo0nnTf6yO<@j9M4q(*yPIgnpS^ug=a%> zNA#6{SLKmhz7qMl?J?lH?ztcC3+wBYb+Wz4ZuyKha}PMsKX5xM`Al-zdRKqhrz{^> zf;-G3M~2ZoM+(sRvHoRzfm!n6tP_KnH#VqF-i3~Uqt%LduV@x$tI}VLtk5IsfL<|= zkQta~7|HDEq;h$NE(ZDw?Ia(`a;Yw4PH1)-=QOv}Hs%~{$?<1C1HtSgDdCi``P8Ln z)Wx$jaOHjU1HhRaS<(QAdO=kv=|A5dJj-gFuF7V5cPLG&RC2uCm@3lisNR?H*pa1W!47m{KJR|Y49Nj)19lSIJ7$bv%0%n^nw z1_^^tLFz@aFyMtw#EI(JYwg9OXOH8PCl6w`)r`|i2_X`KVA}Q`I?gk^U`7ZtHpZy^ zW|FF(cG#Or%$!}+v=u>!MKN*5*?|lrFFdXgbPzmE2vr`ts4#BOf5MXxc7d>VEbemm zN(v}mU`W^^G(;Yfss(}a@Gc7x+J;dG!wSMWaCLYd!H~Lh7mJv>>ZJ_`N+QPzd-L3j z6a>_7?y&?gqU?6UEhB>MDOV!&RD1i}LxXrXBDBf%8mhknv`6n-3B&EnOHN7}7|?Nucq z(ZYk?p)WZG2*_%KaL1uQ)K!XGek!@r1CVkMpn(J789mm#uW@0)0`AiXlozxcT;W~1;)NAE%=JEF#=?bX zAUoh?PSCGPx$1Kpc*a=LM=tP}cUe3$Pk{w_+-$Ym3n*P)aH#ytA;K{n#>FW@>vg(L z*J+UcRT{qjXbFP8B3lcPnw(x-xR%9x^^R3t7fB1L*Ccg9CZ^iJ~ zNHp6lR^i2>g`&66w>&TMSS?7o0Xj?}&^z-x^DgeEVu7YwVPv`uPb>HXtdQW`9b)m%M9IPQ5>!=ImCSFRY1G1wR_RN64 z(=2E^3TOJ|uy*PTp@YeX5oLUQDk`-`Ox9LnbbKL3#t8{Fq3@h2f?~I#a?{gil+6^w zco}CuM#k{!Ldnb~4h(q*Dqp-<{mXNl7#H!;)1D1(DQD>(4U4nrw$`J$x1(`E;ddCE zV>3Y*G%+q`lbm#VhL_sD`XTvn{$`Y_i@J}p6y7O*uKXk880GLLDtTiI-fPr6qJDFa z_6-eTj1*6jT!b8fp@p`fU`=%d@){dR@J>K6I}=mWGwOfg`GNrm?+6rH8VAAW@*L$L z#(=qKG*)7)Jg+*_8)jsPb5!<~Clw?p(WfRWQLE3|aDhRy-QJaKDcN_b5!1Cr)x}v+ z?DWpfCiR(xm@Kd8p5zsb43gjIlMP728kZsZmu*u|B(GwuLa{FV(HL}FyU}j#2u|m* zx3?8*>raeN$ePvqyyW1z%3yp6O*b67JF7v+O2!t2FgO@PgqqVOxgsm0{2bTd+&17l zQjgKea`f6;v9r1AIxcLqkvu8c6VCzWAsdG>bmg!Oo2{LvE(hZUXRl%O>Z-k*gVpP_ zVqVQn#%PIigK|7c7w6sBSiK()K6*EvKYJR@W>0mLG!`?Sml(X} z=VxPPrWVVKb8+X+jd=By+i~~Ktyo%|kHv+VSXo+(n=32v#+z@%cfa>`eDC`|j61J> zL-1J?>?<)T*$IPWt+5>C>QYRU8>)jH|6`gT*AEXW#af4`&qzy{e)_^+{;EL8*pJYMH*;77TiUSzbtYELL=#gNMAv|A1< zNdGv03Oa^?052a5KNw>15(B@-g?D%W(LUtHlodzZ2fVeANAYU2T#3AofmO6)bL~+) zee$u&h29ZrinSU2#4yGgOq#DME4@NRTT~_nL3l`^@WsH3Y>ihEVe3#n;{C@tXlx|F z;DMJIXDzWdWRB2YXfboUwYTjv-=O>48q&Pl-q{fzuGvHDQgmu$L^OwX+h8{w>#L6i zo2JH_IxE8cPOPszHtlR^j?r%nk6XfJB1xc>#yjrgPwvOVM~?;f!)Ud8@!;XJc;^@I z$NL|Atmpe4V?q@kADsu807;zkeU1N^% z2SX1$1Vau+Arf_Q52IwgQHjN+SsT7E{Ik|k(V|P^ar5SlG!{*lYy=||BJZ$9Wo#(} zV;;P-t8qLKzO&YCHd~(a81(r(IyzC^guczXQ5d5uV54MVpn!J6$1&8c+_>R+*lBk) z9(eR(NIUk$JZ%U*GqW@H(1ULhE)k;`1}S(5?ZjJ*K7qgKp;lJ?X|OH6&>kyDzH0Bsg@D9XFY-eXr`7rLDxbGM=G3c^Zg!X`& zSL0SpNqL;L%#Ki$^htS1Za!7=q5D~Xet$W6ZWPaXG^jKC z?Vr4q&#ta~_9A`iAvZoJefrsF+i{)#n z=8KCzeZq8n{ufMK1e$w%!ra*Dgu)-j4}-Fj9)UzcJRt$t4TaEwpy3@c6KVYNZYRBO zCZnbdYBQtb#<3PioaOac3!I0~p2T*0SND@?yDbuI5u*IQ?pdJHUoNIZwDf7_F2M=G zPLIT3C)@|xkFjNnwkVJLsyvjzVgN&w+fw|g4tB1wTM%Ow$}iq2YjK6310zOohGDZi z?et_|@N!GiWg4$D!s4+I;6AW}iMl=(1QN#G7nOxTkMV;<*<`fvrQfuRgwcw&+0f^_ zu{t@EBLMDq^-NuMSe~?-ch_g?$5#ym266!ZX zDrZ!=ttTwR1fQ^sqD)I`4tcXt|`al}3sc2Gl;^L$9r zKhZUKGW32_^csFClIOC_Tg*2w9OQW{D0QLZsf;BQT6(5X7IYH&j8et4Uv!nwNhr|Z zBZb0(_QEIO74Yjk2NH!3#w!#moPokwCF1|$Qk*w*DV|9g6RMYURa%l+Fhn7fpgiEh z+ssM^m2G*+yky+UeGC^?D8qO!@j7X#-c!@`VTY~5NYsk$t>-Ggr?!aSOrl)IkU?Aa zY{bF{bIDmhqim27=RNPm?$(;mzd1c&Gs>}f9eHR!e1!h?`<*xuKc1e(lT70>GObJX z(gyLaa%ColN9)QvrlyGR*uaKI7{(Wj3E4(uh2cQK%h{djnVq52gaa2CV%RxM8w69y zAoh4s-%-FLcOc8)u`^z7sBaje2s1e*m?1~8Nl3hMs;2f-BzKJoj-2^|ETVVB`?4*_ zNNEV%+TL^?LakxQnyAhz3+JD)L8K#|JQ|hSyvl9pJ-q&qNi~jRY6;#bLl{idF2NZ^ zz2#EIXkb9WP&PcQ{s^8!Dk}|3$i~MSk9Fa}rs_J2&CPWi08pIH&o8?@C~%PrfX&%S zKX!LF)K-+m$a81HQOO*Hc)J``4wZ_*)CqY*xJRf-^*v#K5xd)u;?aZmV@G`^L^5Z8 z5gouXkLK7IGL+y)yHAhXadglR!XHkQXLN5U4tmY#wp&&hzwySKapUF#x5Nw_kZJ?!0nW-`|XHeDgc;{qO%p{Po}bckzQi`^&ib>RT~cUeuhzTaZwM zQ^GUC+~FC7(M9+&fr393Uc-0<4rx4vC(s8%<}nBGWV7d+@SE{u&gZx#j$&vbAHTtM zjHQzk8cX$Yc5cz0Rm?x$@L64BRehs=-be0(rk#s+v}12)+w&Q`tyJsAW7au{M z`}M}GWj$yaGA7>%w@95mm9e(^OfuVk(g@~+)+C&_C2D0lO8$j~l_*!|gf|oR;$rTy z-Wndqb4q_JBbrmgXK^BWf?;T5bJZd0 zkU{aHz@VS>B^AARf?k{+7`LHyD5EV0i;mGo&X+=YS?t0uR|GRP0OJf7v>wAAoAvP6 z>~t|0^i?!8<1BV}Hsks8XU1E`4I0h5qSe}qhYvo9ovlsJOTr(rhB!Iu$44LhGWL6| zsMlwr)|eBWKehMG@iFr7l*+n@k3W78@BaFO=DJL;5DM>td(q- znx2jtAw)GU@I@kx5K@pnUkWD;ziP#N27H6Bab^{v1o6Bj>>lG!*}xTAfnm!0OSIDA zM8!W@Zy#wLVB>&F!k`8}nGxT;b^C@5K6`tNLC5VNeBs?!@2GvkQ}~+7WDN{YrA`Wg z#$vS83myaN$Kwgbc*EYnC9ms%5k?=@K6pe6d(6YRI46m8!o7G{5wmH8?nfA(Qz@S-=>409P=+ zgM*AY_4%AS&Fez{LYb~t@6j6TIW+FP!*AL{^4aYEhOC$d7TO8@D>mpNyCPr08_+$u zU%L3Dht$Dm(cgTmdyFk`*FDCc_Fr9U--~-{fnlc0MKJnGE=N>baDpar(f+Kbz!N>! zJ!k`&U9X>$^xS16oG|*@LsGEIF{BD*AUqUxI&ap)*kt=vlfKi2EEb&|UwDsp4)TI~ z?#}@3Y7=7%d~I;f!mq}qz(2pEi~P_&K6kd8-n0N*Y$R4bm&c3#PakeerlQX;`u%bm z+*kXkC-qqQj(+<3?0cVI&hJVtHNOthKdqcEFH!%Ob^Vu^KHCSV+O^^9I$fu)VPdye zZEh~cBnYs8V&^VG93kdlL?i@l7ILrvGjcH%7^BF81P~U3gndZmJ%yMh$Q$UF<$porhYq@3x!q;Mrq`H{9(sRmWw9cThe&t`N*& zs5Uf6xTTFOE~f@cCPEmb@@QC#VRq&YW#~CGL-?-i@Qa(szs|EX2&5 z)HsYg2vZhxBrtFjg`dY??K+Xr$ZkUf0M2(SO|Uz4Lc-*+7JA({=pVMLD-@c%pUsLAwa&M|;mM&$XDB@TlMDdr%P39)8}^JCq|b(>v{EJ&^6xlY&VI(=n^ubDr<@C9A^+9vT1 z2%A}qKKZNHr{m9m_@_SK3)*Y`B_ef*F-NqVGf;{hsHh(BRPw?7&{y$G^G(riloTi& zy&x8iMBxUXB&=0>#$r@~hD)ANdDIV0S9NsD1r7*XHG%%LXPs4y`r}n5jvv(r(CTuU% zw*6jHwy#URlx$`)lJh>M=;lkKB_fQV9c?z!%%^|f>*e*F}aBgj-5tGyN z>axarXk7AfFZMNdcoyDz<<KeNEEW&PD?bf8&f6DJDb+n*E}x6 z!=?0k(=}eIOD@$KZGy9&MBA*iMB)^lB3lcex~(nIh&9dkt!TFP1fvnrI?kazPB>`Z zVYm=wb!f)pgMHBwHVUu?3cb_zbBrh$d@x!tZ|Uzjcq$rlxX%EkKw7`qUW8c1NIs?I z+NnL#TCH8tp`OYTZsGX@O%y#xhJ|*6`wI&wzauwd|_P!%3?&j&|mh6NEV!9RI-7q)76*{=UH#8W!U73 zR~-b8s4U%H$Ln;~`}Cg+10cq~`Gwh7SX|U^jv3&LrQ_I8-Gn8#-&{FN}tRfzEidJDEdUE@Uy)6;_@9nNm-`v=oY^Q z)i|$MA74Cop;g9FjhjOaYCc+~8Cp=G;TSMBC80fMb2}E(|6aE>E;eZFLXTA2#e_?4(Tk!Mw^bV%?qRo%4)- z8n%Nrx!)>JKWx-OZ-u@A{givG=2(ZK1PoZ~Gk58Od5G#^Oeu?ta(oTm;nVN?ciziK z{KsZ7WTiBa^4%NK`Ch=+S;YZVBtrly(0*jDm-Q70X<1EV9=Y?@Kc@Mv-@5Pn%B>to!Oqa?-pJH6#KP8u?=g7&-C9a}hY4n1|(k|qA zLS2seIrE!OM zf{|Z}S&mA`n<%k+7G(@xQmF)jAmD`pBSR2`>A(c}%`Q6_49WzN7&B$-55!b4=F*=P6!u-!c9V%`fY(iaA2n&Frl9q;EMJk#F)VgeuZ$t zvxN5vl8A*47A?6eSbY-<2j02E1;vkq1@*%M140q+SQy37_Ch$|p3i?!AFt~5*g@nG zIL|G-C&SNsgkPaw{2JB(SrlNvb+IFjy3fxpwP5c>r`hz*Nxt`5`*Cuhh4o9pC_Ln6t*eaptZT z>1rp2!|QaN{wq&knc=HZtN+W%$)XW2(#zj}&*b+9?+s{BCcc06`t;YUPo;cS3r2sy z%ZB3i?WOqUTX*BlH*UpjqhjR}n{41uoPPr!gZH9Xm=OJj*0Df_Ph;f5sLy5v_!}|? z$}D?$iN2$xCBJ1Bl~X7i;1hYS7m6&Djf9*+R>12^JYMfXV^Nr(RC6e&QkI46!29q= zXm-MdMQ~UNf^q=`9DJ7$h*r!(FhXgHf(1nj_23~*pUq2@4+Gl7RM~wwIFNjE zb`+U30MX%TNcvBaKDbB<~xr;#uFBigdqiE*5)}ayj=2(mlOE$IVoM1hM5>(4r z8)ThxFce(f@!Z4e-%e`U2h<4CN zl=!`FPp@4Jj0h-sB!?+K9xuJuD={EBl%?<(FQ3tI!V9wWMxX}vlnp#l z`U(FI_M_X{j)UG#JiPxw>`G?Ft88ImS>guXC}|)CFM(B?FyW`1L6@F$F~qrFz!-Vx zMB_!M&{2ClP1guFS@#$r4{~k~iag7ox~Hk3w*))o$4hGE#_gy#=50{pY%Y}9go3+y z`_-6RScwv6c1;TxRVE<|$4kPsag9CwavLy6ArH}C<{J0-&U1dBs2%Ot*;*BTV^m_3 z53&-{4+)v~NOCB~8_svd<8#7oM(K^02qCaWebyQEA`?>wWm5<88=ioKGTX8@7tb(| z5UL%VadzVmaw;2=M01eSgf>FV=@kBB$L^gOnMB*5pQIFFA56X)wKwX0V*GahS2gG9CV z#a;}D(S0&kwjOU4twewI%K|^qpcT!4cA}BV&%oTBy=3=JKWCihcZCxfE{?aO%*}@n z?ibxs7P@V*f^j%ao6Iw^GUrG|0NI8!bRFHC9qC`-G3YD|m*AOZlrfVd^PTUsy}g6Lc0A*L)IRv|c6;x=58LrE8h@p>zCyaEQ#YrGMUS?~oK5@T z2WO0kBEK1T4-WfWH7>QCZD5B!g9FEr=t0lv7Ub>4#rg0Icwp=@Z_wM(qE2*QHM{Fg+Y)f~)#(z)O| z1NvZ$cbtJ}F5N(F zUTG(X*W*Wz+vBaR!aH;ETT|+q_lc8yg#}ESoj0CJ8i;q@HKMLsP5z&93AF7ey^;ONm8Gy zmpxR`<&>9gOY&Y{?Ai0Dv{4&+J?iiB7I~r5B#!ZwWeW`!La&|_j|J1(>XxG_Wume0 zAVn7sfQ#lN{h9N$N9BQk*YWkW+LJcuo8NHCLS{5kS%;BWuy}VF;t2RT%YJ1?3 z`{XTkD5q>M11!9g@4cU+{K{~z=SY7-)8R($$uGTx+3-8>6@RbK-sW037MRtz6fEU4 zR<8ce@Lf6eTUj-ZeN6FEsdz(vi|8a%8Yit7>eO>xwkzu#=f<-NEVt=mBnIYl|m*M=y&8H*2>yUm?Z5`nAH(ftZLKQ9@ zUzh1J{RSosMHCUI*JOn2GNwlm$9T%H5ymD8r3*e+qGXAh2~*7P!J)*sgUA#k3gcl6 z*grfdMzkCuWhDyTS%mEp$WwklA7ZM?AnYGS5Osdny@wCmy+`-kC-?8RPaoWCyAiHA zG$JmRa8qqfyErNEB?<*5|AeuN5QAamk5h`#%)3t_yx3v`lTIV6&-zG^Vl<+#ab^&T z66x&T7yV3}zrI18eFCi`Y zz>u&=@Tqp`Q(#^zT2ilklqs+WE5e%8^QXUoF{MLA#>E*YCA=kn33TbQe!6ExEBF(v zYE_c*2&_rUk|;5C-bVV(Gx=QfmON27NgP)H+8*Q}%78uD&!VWE9;I*R5nu*K%OGoX zS*hMD!PgH$fl*Rc$^|R^EJxJ{j@nDHry!JfR33ebU`L>=h_tk^9AAuS=_feU`++fq zkq~D5I6{rJ#4tcXEaPd$8-Bv;?wsvTDNWUezRi_1j3b<2Xmh5VRbWxt^XENq*EOrt zD8SmTEDEGP40D6*Sf44il&}%b`sW_ORa@0JD4g1AY((nGTPwfvSNKu&=H>ALK3Ccl z2ln(Nb4cMa2+Fyi3tW z??q|h1?c(}(Pzbv#>&uMXJI|FrBRP;XGlg{y;p|M;>8$49&E&L{7+ljDOnHzQKGM_D|1@~qvt^J&}P-7Y>boo9=S&M{dE zf9t$U`#obM_Gx&)1m9nnPd$0ZwrR%d(AHvy`voJ$Z1CaK`sDTxn=R`Y4;b-n(Q7M1 zqj+}wsO{`LYzKMQR*4*#coQew>G?^?EXJ8Z-}p~VrY-Y}-LWw}7k-)XPyVq9#;C!O zmAf29cyeA6omKarAGNci#~Fje8ozPd8@}L(I&O#ikK5kv!*+DE7d#PZ#4$M878jPw z(R7q|oS(z7QH}=D8yTy;?R$03mPAgg2)6W3B$h4G^dp_9=$Y|}$c*LmaxM-zf_#+c zFV3rv6=gkw%SHMw+KJO;JaBXNPcSZZI`bC)Ud%Wzw^@d{^Ct!G`T2fMr!DQy)2F+4 zZ?_+O@7saXmA10FoN<}WnDnR;aH(w|ZRJ;yPm;Ms4TtN2XF&Gg(+}If`PcuVef+@> z%F%k`#+&VT{{BBsdDk*t8JoyfON%R!zpnAiujnD8*Q@Qb@|-SZd%%Z}9=F@KKW!g<{7L&X zpSHN?M0pr}@S_htY2W$o`|YET?q{w)jm~jYPKZxFNgWq<@30ua_NM4@Fer_)6=vsV zjOTR3$j14E`x1vY{palLqCI-N)$XRfN5OGXdSrGozAaQ27w6j5tE=tpw{NzMYqrDV z{IVV7bi4J&wQ?G94A61ke*3MqzP{R@hZcz(!&?|+IZnVDs@39%i~+~AMlPfdb=nCblB@4UK+S_rtbywo-~ zH{10a*E2rnb(Wf)I^Y3^7k!YU&lc(Mm{a*Q`D`6l5yHU(I#eyR4E`#c-oojo-E=N9 z2)`A1!C~jDVfqcdXnrpIH+YEmyz|bR?bfa9^`3P1?)~;xfAzg~|K7vGH&NGMTsvlD zZdv%@oNi^~cN|5my@)Mmf6>+P8}q~h7=56zkq^GO4In@$xdSds2_@)w21y<-=)z&-R;gRofNdQ+VVf0gShuq7NNmf>dMQZBpi^r8= z0lJ7xbEwlq_yOM9d34~sKWDa%>{}x_O88siK)5ez5@1YC^27;p$HrWQ7m`vkwf z@`f;r{97$Zsj)Rk7wWxlMPpxOv%C<+KIJ}*AU_;(iwRLM504LPE0{YEIJ@q(yN@2U z2V0NY!`-bi)SO3Q)CNLgF}}2m@Sp&KhSfln^I8d#_Dc8w2Nb1HUd|@%#1Khc7@~wZ z5^N|r<;Y4s+Q^AScq(U77^ZqKW91Q|3FFFe=&)6k3`P!8SJuFADOiLJ%wPSY-zYu= zf^Ni{snvGc)wf{k0!&{m+(lQsxnMmg?71P*jo{RIDxsqb!SyR2lo@r`_iBSkvMzW~ zPY5Ce79i{bYZux|m`+`FzDmiqDFB#r5jHN)FCrBBwEEn38Yk`Wz}6?WUg{A~S8NHB zIwEFNd#a7qkyqE)mEPtW3mtS%o3tVK$~cg5mfhIB;I#1xXOiD@;{bmYub*JnonKb? zU6ixa`@IUi4vxa#vA_o2MkwvuzGSTORNHM|7-&@6GzxC2i*P&@fwIOX1%Vesfib9Y z2g6+O+_)JhQ3G%l-WX#BFXLj|OL)wE&PF%^N3`1*XbYpM_7V0(K9rCboMNcbXHH+8 zD`7V8={JaX0Vp`0_FC=8&_nsRN*_F*a7qHoWx7m%_tF=`@l`bX7nOe2l1A_S$m=Mm z>$Nl{!-&q0Qqds!Dry+oBi+CYNOJsmN!_PPb7)U(BpYdb#8$IlcZ-%IJtGdzG(9_UKj*_DDq3evg z=&!up*%LaB?>rOr5}u%byrQ0QM4`Kkc}I<74lVYM2NZMf_7%~L@A;hUkz#wh+ZFwR zhoHr_|C)^~w6t=y%`a`XnYpW>@z2}g{-f&Sty^!mC0l$gueYV->(NRt+VaY3TU_c9 zI3jgsXQ#^9#7QNRVlsULdrmK_)BCn|foA$Afd%>K^yH+BK>G*%tQcoXfd~HKpnk?d za!|y-GO(YV?3crAcW0{%`W%vTvkP@D*Zll)Iq&A@r`tqu!PawAvrBD^k$lYdfhpuU zL;ZQ@sU;g=$WPk&$w7^Qb5NNKMMph7KWO`r`3{fvi(lfgW$aJeIVfIaY@A<-pK~BC zh$>oej!-`{h>X~sM=t`)wEg&?Z9TqUQ3+wVk;!0Q_#`Jw$}IUSFrJy4&$x~FZ$3Hi zCK>3{hNF~`MkKE&f9E`j6bgoqbEuLfIFA-{IVURPp0Tnm;n?^n8s^Geo1dM?7+uNp zD+O~#=Z`=BsD1R|2W@+2J1|@<*_gr2nMZhamnE!zPP>BFJ%NKcM>YsTzBq4x`KN!_ z{-6Kj|D)~fJZiuF_kXYb-aq&!?b`KQdEU<+TAZJ2o153${PJ4i?08_s5m64>$dsbS zhAoqo%b_+dO77yMGSwPMFvhgTPtNuGfZ6(6$t;QB7bz_A}8I{>{{SwRs3|p zyth~TIg5um7Y;kdGcw%#0w*44XQxdiPdjt$<@T4U zxtwkmhdrrnMJ@R2TL+qtC+$cC%Eej9h0gn$hjTN|uZq4E9OA^_%wSM;4xG8^oGY>^ z=h?)Rvbs*CAEJe{@yZl9_b8fv7GK&w!y%dbqS8hYZ4;ppwkj9(Mn6K^oOidne!Z>O zc_X-I;eaSJIO6QFwe_pzI42|9qH$(!F@1&Cp^@iDp}8CY{mf?DgrY-}d8R3%cR&5~ z)8P2+nx|`_T_TXa^WE=9&)W^e`dP`gzkl!j584mk|FC`d;qCU_@BX0u$3OXt_HX~~ ze`tUFAOE!d)i=N0e)z)=+b5sgZ4VxX{+xpAe9D}w-9qSmCnp>*;}zMqwr2Z2(PLz5 zG{ScGc7EvkoW6r;E%u`u(sLrin{y()=ndu_=ifEXp!9`fXKi&Q^LIKlc(J~t^I+)N zt(!NB-uDHKkB?65zm?Mqu$N+62-+18)I%qsa z-E0N_IU!2FOWry|J9BBJBGMM>H^-oUiNbpD;6eNLx4+x&-FuMdOM&xD;TC$%0lS)U z#W%sq_}YqbeJ%WR$s&+k3kywDvxO=a8_vyTZU&B=8ysjN=pNjEkbXR>@n2h8skz4) zu(7e(-gx7US}0-c$O>ed;_IOY9Dmz8I~hxhKX%hDk;t5P7MgVZx^%bP^XYfdmXzIp zqdo=FO6(SF3TRg8%I0hGRT+3muKGlG^NcP&Dy-?rNi{Ooi{T*Lr?sT|c=6U8-WF>Q|<`O;C(<*o5Xs93l^|Gpe z8P}>wJ)Y+W+9jgL-0f{1m63AcFd2nRKo;bXLaX3m&8^H|^_PP%3ErXg9HMwUha8-& zoqU4Vc!#omS8vsk-)cpJ^+}t{23GXqqIf}|O8GS)?jhoN>)>rV6$dCH1 zU;5&bdN1?Y2P~Ge8aZ^zGa{W8+$)$_Nx{-*SK@4)Cw$Jb@LOuwlqg#LLH z_qnBowh&<$8y<*%Z50=0gOMd;DV>-(LBv7GRwl}eDG>yUDJLgGKc&jbAp2t<9v;;5 z*(g<|{OoMCPw(ETEe$`p_i5WZ*l$l>JZq;B*{OrYAKP-ElIaR^bRo5N9FSrN9#Ij0GoBZKoJv2tF~6 z`K*X?fnWsEp>m9G!g#*yG?MW^vvm|G~}jS$*}>^`>2VuJ>|*9BcpS;`-yntR$q zfUI%3Oqc2JR{A>;@%4*K=-cax!e@UcmE)_vymoct19DtO1dgxGmG-~=-~O}q&bx1h zwuSd43&R0ggyy1=w%;oQLTF@&T+zi^9h}Uig69+eQSflq7n+9uQI5$K=r3nKqbI`$ z+Q^_O3WGsY@(#9Oamq#LsJ2v;SQ+U#v7+FI-gds)`=`DtH}v`R7_%`dK{99zvzwaM`9g?Vz)Y+G7dYZDwXlk>Sh z*T!F*r&Sllqn!UFLSB@~m9gjLBsw_UNt?Ad@}`iw(ad?59K;MoHgL|`(aAw%hKaVgywW3i#uw91(I6R< zGX7`0GG^Kr2n2j*?fCFGb%hWSvMs!JR8@Kd^ST7blsBq>art+UDlXHWAtA zD0spl#z{A`xDi}%e#}D2uc<7>lP4lmj;CLf;iHj7$+?pp3c1&vPH;H9xlqP$j*#Jg zHyBkEOw9$qkJE?Ka`gT1{g2w8ef=-m_T#jrFFb%`z`W{Kjn7^$~6bL#0q@a8c6i;Pld$m-kEiiWeWhfJx9eapZ8 zPDMY|)_jA5D+O1i99ivkczBWge%4;3Pv^(GnXf&HvJ8NuzNzm;-hc5tbF}ILx!r%?7EKU>2z=>OUT23tQ)jv*VE8)%i;3qkgOr18`u97TfF4<0xqu5rDoM}h@WV}TkZe#|NfuapML#YnFkl; z2>QW$AGAOEqrYh1_{R6!$DcgNygd$_!UHnK&P1D>oJ;?gG8Z_f7xKB3-wUZzq|Vhc zY}27oX?n+OXfmB{cWhr7Z*7A$1Cy-pK(ug(EWS&!;^aCl4FY_7S zTeoi3wuOxN98h*HQ765Fvu$N{G0$yXxz?^-+sGI^4gBvG{4Hw3C+QpX2TnZESR$VE zZ)SF?qDjB}<#(c=Ek*ycMeXA{$19!g{5BBT-7!yg%8`Uu?&Ud$S9dN(Ukp95C8R|v z7B|vIIN7#$_S?OC58Iey1J2 zD;xdRtD$!<^YyR&?&x0S^=K%gzJe7RCo;L)P6`gmJ6z<^N(F*ZS-seL--EhW&*YJO z=|9T3sSonGoB!Zaw>fltu1Ly^Wyk+sXE`}*T>3pVm28)?I$V0)lCr$-KKL4APA`#` zDy$t7a_J|yCu7n1I)CppJSunrk7^6lP5Yt=k@2WfA8t1ZRal{4R!taKL29VP|x4y`gzmmmHGPhdCAPVbbMW= z%k-O?GVfwuLKMZqr6)%ODbV4ef0TKY7$2cfqpiCnz$&$L?A%PrGNLK-# zcXJs(V{Hp0&Q;DO29!HKB_ZS@|+wJg> zA-D4@yn&$se|9#MXeg`wZ2?H8Sz20+{C16D?dhC(GufP#B}$D9!nr51g7N*yh3K!tGV0jY&PwXu_B83@xSgGJ=M%V% zjagLFY8%D9y+@G=_Iuyb=BX>s+w<^IQCiQRp0(}mMKbe3dmQDHvo$=n`%YV3z1sfSKl^9x_kQmmw#{pARR1#^kvW1Rkz*M8 z3&#Ts&V>8-Kgl>V?o^?XMFYE(`{4)g6+W!3ueHsaw<5Q%1%_AJ;lX}6C`6dS&7))6 zr|p+BtS<_i4jwMmHhbg2Q}bbP;=s9!Cnq(=M2hFnBjaWa?|%Am+R$aDzI8O24NUS` zjxA-7N&^4m$L)Auq@#HiSdQ|^^Ze;iOI^_wEGQec;B;o4bGYj4wJX{|UpQ?~qhs_)728JlGeY+EQ(v;!QmKs(PD^#_ zzjyoiKMQ`Ew+|oQZ`)gsN`6a+OHb%gbIArk^=@cL`ZyW6PgF}$z_gnT2Y<=XXw%&6 zO2%|5uRm>{-u^gk*{l4VyC)f|o$bdNyY0w%&cB+exhb--N7xys$oms70^i{AbF@?2 z$1>OU+Ae2r>LQ0a1CHbCVE19^N9N4b>_%wLO61e@*%qRrEkkEGc~6h`+oOl~A{Sen zN5>JJ$T7XsKK=A|=J8hAF`Hg;jEcnU(LeBqGr>H$cjwdggZJNSfBBbx)&Ale-)bLx z_(^;Gc(2`m@HqFr-Tv$^zSVYi4y(;**_}`C2ezU+L-%Jm_*UE1jqB}N=EM3`(P-=S zyXX_yJ+e1P45yB0EA)Yrn{(s&bBhmp)Dh>Cg_-Df>5Qc#p!pW1MXpc%E)HQ1GedJ~y5G;Dc!spgq_MOVH1?%QoS{Wwg$A~WU#^K#OKesCnJmo7BF(D@r@vj#_TI>ekqbXpp7xg%kbg8re7SzURBYkft4k__f1Z`&G;M|- zec@(*E_K@Xqp98>vMA4A-XTx;Q)X`qS!T$n4N3Xg7ZqgY=F^-h2gJ*^qVF9>l5)V^ z+k*z}QJ+IT2=kf21Gk z>3XdBQ}(5z`#sW&%u_NQeLXnms<{(9G=EZia0RXIG93IWIxvzQdt203%`I7^;F0!q z9a`D?W?RL`1DP-IOzyHb6^`^aR#{|L9&d=a94w{+4479>4bPFfJWO`u*OH*T<~eyYdnEvZIU~ zdx2pulYL8{J8d4KtlaPC=uTIDHaUF*TlS7_U+l03Ph-gTrXu5tZ`xIeqs!uYw6nvx zk5NS%W(>-M&SEeifRI7+YJ@T2MV`$PYKnk%_K=lap~*YgeO zv%g=Z{?6Y%z23H;=K4ja&#UA0>x+`i{!7Q#Wx7nip=oMyy50QJ+wJC?Z$`jg3Udhq z4YLRvE{0W3FN`cgCI*F}F-Vm_m-j{3U`!lBoCKI6VG}d%!pC^tqregxoh)8lr-QiJ_6o7?`>5R=t(b9syO`OFMQF;?$Q%CexzcW5!Jsp4u(rZxvV@9q{EP%i z`3a-)lu)MM<&f-*hHyZsARP2FJ_3&m#=UyA#;8Ktqf9)B;$y`rqsz&$Rp5QADZ+X= z250)JWQt5}JrJRkVk18<=Cdc@tnMF^^d)UpCZ&_HOCR0WlZb1*PZ^uOmw0Z;5GAg| zmT@!qmOgPP!bw8-#b~_1B&Akawelx*z}<2P=J|QX2o5QWU<)^`Sn}Np!l14{fNKfgnIjbySc-X{8$C*)<04~>aS?e~ zI1qUFq__~O4L4j(FGYzd3QV53fVN(QR^pcNzV)xi37i?NL{~uE<*CW( z@Wpl#b>WO0JjME0(H74mcT`lxSYTH4KmAC* zML#U9Y?Nb4RPU{(5gy#PaJERpS!1&$*Kr^{f9kBPoyK{=`L=%~k}R@c-ZLi8pZAr~{yyPOFZy?ZrtxBfm5_ zw%;Dzzug`^_#}LN6nz+J0_;Sxou;482&=6cBeRP1dj9ON9qw<}*>0lS(ya9VtUb7U zx11;N7Cx;mueNvJeYbrnmv;BaAQ6Qkp};6|)xt`fTUf61vdA5e9zLr6+h)=kxpzPL zuzmRccY+IJ?aN>KO1p6@GJDE3W+%so?f$(x?eXKhliwV`!-6JbD9WR@(pdx-(RZu_p~`HieX+?;y~^sRJO?V$GdH7EBKUgnGOwk@!}%5dM9OkP`Z$_ z!lq{zlb0+TxTg+n9eWv($8ipScdDBl3VS<`+WYT)r+sp}J2z*hCo<z4!f+ zWpCZQRd7VlY#sH?R_Kir>skB3_rKTv;P-#O{qZ0DNxuIuW4{+%I!HVBE8#A3$E*Z3)7;EX1chijo&(omkyPQyi@_MI*m+tD|DGU{-f^Qek3oJJAB58!T+_K`GRMy=>S}j~bGmPP zPo~#SGC~?kNK!D$aKbmC=G{$iel&fnNNzB){qpc4fJgTjim8n04 z3z;{z`LtcIc|;z7PxSZ^d8iM+jT2qmUtTPD`mZ|_N~_OzvWMGvaDJz4e#>9FTfO4O zkEXiU|5Z7|J^1Hm*#+uye|VNly~B4I^VuCBT@S6fP;;w0dGrsx^L^;wkcRddH&@R; z(#w^evOk*&7P;7g)YtR$d;ZJ;PTS3m&B6g^!ifZZ+2&E1@WJ@OD`lB)XmUmHWQ=5! z7i}=_M1!ucuazumeAPFT_e-x155^nN81fHYyy{7_JlD-?_Xws#LZg*cHlG1rx#v5& zq7nUGU^i+v9-%1h?=a|}eerb0CJiPxa@4%+E7>TQ=gM){IKOI1Pd)eNq+~R2Y7Ad{ ztKgIReCn6?)lv22mpaWo&5&ofw6|{RM?Tr(I4kjiftI@JS>~ud`CT=n9&(d8?iv;b z)S_W|^4#1Z*K3C{L3>nII}Bxf&|L6EH;q4(Cwt1@$Ez>MSGM{7JoDBr67WeIjluD8 zWa{(2SUafuQzh+t{qq-4MUv#_wE+;eN((!efF4J#d8jAwGdgEIA%5VR6 zyLRhVF}Oi#s8v0=N^mO%MKHD+*fs=Rk*e+ba(M?s!k929jLIrPf@(3UeUntn|zM zYE$TcSB9(->5hXcGi_kxv3iU^pdT2oXI2!6%2Bo#)Tr2Gq$Qr@X#hPui5r$^Ct+r{1Q1P7`6E3zP(D@UF7K5tLJ2SJtLWAtX3d zq*~fp&qqRsHgE(=oRMX;83f%tcdr`^1F^t`Vyujd2>tedCma&sx)U$$%O9oED$9i^ za1040$k>J=7lUO9%}>&fz{((>okTz^r`u1H()tphBNU}Q5@Du*u86>)lmzf`qwZP3 z3;$*V@3c4d>q`l%xxm6ZUBTJI;Hls627I;I7H{&O&YY-OUNf~EqY|Yz?5~yp=!rkh7U^_+`&b*}%M(Kc)+R|ZvnJ&|B zboydAzR<50SaRJ^dS630(Og?pcIrEj-Gj$sVt2x+B2%gg8|DG!h6&NGp_ zwuI|O#%C7{i?%21=Miweke3)Vo@Q)0TdZE6one?434a>i!BN)f@^t93_wfp}odalT zWwR}>T??c}53tIyovyM3%DZC^%i3Lm`^EO>U( zjt(9r569g}IetF5{eHXi$qyq7oz?j1!?VCrq}|ccZaELj@Scu{CKE+-lsZoH91a>w z{90s^NV(@5hSAOev+Vz`n)tKS=oN=5$;CB7`8*Od%YB^Ah2}3T&E63NB zX>jDU0l>&N=ZEe1c()zwY?Y&j;eIObk)uQvD#O;8-oGMBEPbmvQO+rH)owdKVGRGc zZ9Tr%=7ZDT1c)p}-Zdz)Mms=_GV9fPim zi_?trX~{+A4P1M2c9eb}1*Q|3vnl6_Gq6HCY+Fd~&N$Hv9^StnxQ?~j5-DS9-iprZ zWm~A0&&)|@S4{;*91APUOVyu%u$@N-DEbljn)|P!27BAISIaqo&2ff)j@H?tMbCpf z&YT;o@mgJ3%h&OCe7Kh?PxE`ZUCWqlZr z%q+HzjT`06woT#O{9>IOTzLO#|9;{|`o*P;lF zFDDV&^CI(>@zt=+%}v*tQ5ecl;>pVq7l{_mei!Yru97M{~mp9+MmASiI z+NYW>uX9sL|T@VDJ&U%=RTvpMzj>5I0r8@vqeot<`r zKix^>-}KBxoqJ__!&-8N>b8Qe_+N)pzA|IjesA8$B=Eih)X@=-DurhWx`dJR@Tb z@W+GLL!PCd@YSV9_1T+NpWTMyNpCZ_^f|>=(Ct2zvC8mba=Mq#p`HDE^!wDmurOOr zD)g0uc`LXrk-@5t>XZKT?UwNieJq_meXl+u0!cn?*~_VX<9gr1lA~0FAlgw*u;}t^ zLHMpY>>W5#3s5tz`ciOGdM~zqYlHp_{nJ<5k-86#@L4|Z*E_j7tkV9#Yk)ggcUcCl zt6B%yy;b;Fg`mUXIJSRisyb{X^(KQxx)5lyOy+1x`*@sD&fN!=ry2(N=9bw*+4wmJN&C#vtieq8E( z|It3Z0Ovp$zkdBJ>Gk)9`un|~T;A*TzFx-XrN8O<7dd?v4zFLotaR!4x=fepH#AK} zaNl_AjrPXdZ?`4;o97R6$J0b&VbCu|^qJ5n;)gNF{eelAFcf7^>VhzX{CSvIH{KJF z2vZV65yg{ptKaL)8YA@`10-OaM~U~F0|7_G5DCB>37i++sq?lXd{3l41h53(q5hGQ zAezg{T22mSRy$Lk{Mtr9wiiCdh7-Zc9*!=GQ#sC(Cz;c)QQ2u#InoF=X}7Z__Ch0OZ|L53pdVNon7Kvvo;LfDF4nv!@H0psZ4IKl>}VS(Z&CwWGFDxoa!gA+qL)6q1$3os>2Mi~Ji zc_?-I&ah$}>Pj2x9E7wVbc{2+4b)4xtttW&ur~(f@Ql#JATlT@0}j_2X2AoitUZ7O z1T>CMMh$|jh%>Nem@7dh*V7Cpn2SU+e#ToHVYZco9J}4g8vINh%CSWaye8b&c9Fp! zt3(Gpl(!479q)`4ys({?dBq6~Cm5o@iUCZU%@?2GX}t8g1j%K_&H379lv4Vl%j}ow zGX18eFNEXE{QjjS^yzO*Lmt%1HKfn}PO6`;%Ir@myjH1CwEyy-{-gGP`@jER+CTgU zzY|$uqWJ5ML(Jj=qn|j{Gg3iBbSpc?X-2BsGN7c^tHy(v$(J_TIgdjg%zB$IPXk(E|L!sk;?`1G^%?}cdk)Lq-hg-@OA*SR(foV5ia2Vi8J`J^V8#!$?!q)5M!9pt-RP2AfrImnmX`ZDVl{@5sYLlKUA+;R;(8mKaMsFcMN5s3 zPc>T>UYXzo3IDtjT$v3_#zcCA6JFtHU?dHneR7bt1b3c2$#cfaleYc%UVHrbLFCry z8aGh_TaWLyy`9G;CrwYzh3C%}Zas&KfivE^z4fr|?LAI=yV2?-ZQ0w|s%SjUSKCy= zc4JRQ-~b~pFzmZ*A$KM63;B&f8V+ltNU_Plh$BgK0=d~XV-apDVn~0UzqnEn8MfP+ zn4GQg;V8zK!5JPeu85vmj;uRY(P+0n`e8S=uU&0(3l=0Xx-XSefXueMv|7&?0n0Fy zKU-GX4zT3M2uQX;(}{8-S~Z<^FV4@mjrH}ma`k$fp0^s`c6PIEKI1<VEUBcT)aTjkhQbauAqsPDVor&REdX%8)izV`|$$b4a1e zB!~G9RxUz{&&)#(spZY|Pvk~uK(dKIbcRu#8xuV3PAN_~eM}pkoV3IJy>|ERr@04j zr`vIGqi^d-HZop=(=GLsGmN7ybYe2{=d;LzDc?40h4ZP0jM@!<6729188!W$onK2E zor|nB2D^dhr=Q-b?Od;IZk9vn z=FMB>&?_Tv#-Tg#r`v4ky~r$MQ(MH7Yl--wWtrWD8{ok?4&OP&>RiP9hC67oy!6K3 z`s$Y}y2@OFKUc3_4NhOFh%DuD{+p+CKd|FK@>%*o{wj)UW-9Z|7V{US18~xdKryHA zsmau5?7sA+ciLCJ^5xnVRzEn|zWk*x7u+5^be3S>%|YthFwT{s7M~d8drmUCfH{s% zI(rwM(Z4L%uyvt`U%YBzaj`pU@;<#n(fArCWQII=5eoC-S?G~1=2xqq4<0-$=Z(l( zky&UM=M?x*fbd$zeg@}Wt_VO21A=#fAD)N5m2o+=yXarqW$_0dOF!umWSwTvyR_%| z(~L*jp*`opPdk9n50$eTc+n4)WBYr~HIZ0_lbHkBjX$8F`U@}ce9lPDfTfkiDo=fM zbov=uhSz`{=eFOrZsdG5w&>ncXrKhAmERo`@xg85DcFqXyJ0w;Mp9T>gqv;G1s<>XsAPBJER)JkrTz7DDC z9DVlhx%#b2RmbRA{f)kN-5Fg}V0RRi?mQ&LxM#8@RU})UgCl%4Rw<}(ai~sP$v35w z*YB>QR}J~kg-Q9uQ@b;&|Mo~ZrDInY{2INVhw4TXIEWX6JL=#ZC5PDZ+Fa5fa+mk~ zHs{S(b_(T?tIXjZ$qOIs`ZC$pLlf4ou2o;Rx129}Qno5(kjvCxi$8-Cb%cSk@(djD zF8wSRm}t4Dp23ziz+W;4YjJ5VQL5G6yx$i|>-1=h@;?5cUjO;7K4UbDo9{!pbuU+k z)vK#FN-z5*zssZke3T){eRYtR@%h1SAe%4snJ?-#Zgo4~*Rs9733Y2$?(Wef| zhg8B#eM_zqas~mm3sc%mkO~xf-h#)AI$sK7FJn_+p}xE{66E@dz`nH-X+haNDyZNx z(FGIba=>sDa_*$q5)y2+Qe&6j?$>IsRCg~?358iO-!5wY3f)&ndwzI`J?u@^7 zJbV7{Jk8GDCNCaR9K-m!h3#3=CGaBX%>PU+y#Tq45la<@`#1 zG6>$ukcXFvLhC%8W5RY*R?9O=Jqyk4kpc|IU8!eq>`~mdj$>@Dtd6=9C zApDfM1f9*z^yi}Z$?*xryDubJTv}_JH{Nc`Yj5ZKt?*G>eT5D)xXv=vg~ybNWt%S% zK;Z}BEt6ML=M_c*v^_G(;Z8d{-VMtTLC(3xIY<^s+taqQK-&4_ z?4XSH3kxf4XD;vT zx5tm}v^#e`@+QC-@kU_o{ErtEAw4m>+{Pvr+tc%dikg9&LsUYfislR)XJ?5_ z;xOYZqeG~XBxMbC9Pmf>p(UXJ(3q49}@Tp165ue06YYC4j+ zBZ`pxF@D8%nybO_>lK+caV7IB_sJJ8Ql@(9{15O;y-&{eN{;T)cSGb=cT_#k*gk#A z32H%7Zq*ijo=M&xaD!tivSa#lu=}VSo{<_0Px~S@c`Q&n3ohHj`?$ttHo6Cq>FD^N zodidmS36bP1Dc0x+ZsO3SlSjb@GdxySAIrCa-fEwJshOY zWwJHwl`G~^o;^Qp-~Ov_v_Jo||Jcq$!<-AY8~X4U-}pwm{mH%Hlx?=3whur0xc&KG ze7pVmH@=-d9<XUlHeidqboaSRS~E;t98)9Lz+8||xK{YrcH zozS=3Bg5h~96TatMOTr7=`EZ>bFL01cp;ikvfAWZJ8^5#yNkJ zO@!O#watpQyP3XRyS`DhVmj_U{m>e^6+MRoi9Vzs7Kq>{_%-J$U3YDL zHQ;zwZBVZAYx~Z;k4GBQ$!U&=iQ3+9GIgP4>sPOqe#GgeUmTU%4F)2`@C8v5%h83r9LnU&z3yPjAY5dAIBx!9n<=55^C_==wVu1ctj8I-hy0zTp`? zuhX);mP>v47Z~~u)aM?5cGhZu$HsAF}Tg#r7&njP=%Zl@|IUN^kJUg!hive$CDn1Yy zLUfjPyKmmA3vZMk4w1PPf~UL=6K%scMTcpVd`|*j3m_hE?S$s;*5Z*m*W8%b930g@ zN<({w>$ByXMS_Fz4f)PwlC#c zi;z7LW{-iFFc1bVRfHDh#P)JHPy4z=4CMkK}t4k1Y$710x>%gLafqH-`{1__2W40v#u ziS!~_GT`V7p{7>&=H4q}PvD4Z?EMG^T_|zC3$$Q17dUZ1Vbonq3p4an^$_afPeW|Pd4{bqSIBslB_r|RoWq`xC&}Vtj zzmUPuRarpCb9)mXH7sDbWESkxn&d`FUp{e*Y z`v3)=5t)Hj!>j}ywuSAqH1CJrs#Cl4qKqRcmy?Te=Hhwy!x6{Vun4F}g$*lY)7a`i zUZLGmci53ZY!M|&VW};wUQITR9{I!bN6wmFME)ORD96{2%Q&q~Wk`vf5-yee&M_l< z*oNyg@>GvB;K-U^+^ElqiGKEtRs0O3GaM_6tKC5}*H_HW%`LW>dCs1tHa-#B-^dn` zi@*wh)VERO%lH)wjJiz3X-KAEpy6cfiz^tN$U9>h=k>O-cC$^-aS+Ydn3K^gWEr1Y zOnD-Gz$mcJ*pbz`3_;!_ds#Gel)8E(I!B2ycQ)6(J0G^4?X9$Etck)KOWu;lf*Txh z2m5=?nM#<~%IbRCy#7WLg~bWBv;DX^U+7C;`chlHdZUd`uBWf_k@Jzg=4#Hs)%DFAO~m)v*->y|JMS~vN3M8w+D?x4YMkDF z=bd)##+w;SPF%9|XmLww-g@+~-M;-%$s3~g;fpiB$i&LGU8Z)q>I|sV%lRexN%{KE zA=S^YGCnEwMVF^L(n}c|9-o(nI5-0qeeQ_BvdyOLP2nsV4!k0nq@Mk@z4a*b_&E0` zf)C0TshJ|iICJ+4zMQ1y>Dbud7?wdod(;~_@WMHB`)zl3t8MQ%OK7aN1(oH+GiSQ! z+jROISts|wRa6hdImb&>l#=VvqV9N8u8ZtBy3%*}2A<}L2%3_si)L^#k)`1`czL%p zm6zX7k9ON9AAj8L-@jY3IL84T;cTGafGIihH1Zd@&{m?x>Lhc^J0E@g!|r@X|8l|W zPd@#mqFDT9oMnJy;D7LFtL`6(YPol>{n^*Q-oE{Js`ZL{DSJvD5`qgHe%e6e?Am>muCu}u(^Tzdpsq=Y6 zG#zrv(KP}qx&^tC-T{9_P;qXdujT@$m$6{PCTD99+O7=!hiV)Y$^|EmFm!EsWvSr! z@X_OnmZF#Kg$6tf-rKIuGc<|Q%iLdIU#~jQBX!Kq&D0i&t1BzvCnB5(y)UY5_*K^v zZTIP1u5L)b8(2E4%1#TmCj2<#Sw`Q`D18ypN4G`07L5mMK$U#|skXs!q|QKI0Cr@8PZ_c)T&p|8XCe)JK}e)^&4D(4;H zb;rkeg-Gb<(YphGeNKJ&mGiC!$M{y@$Y5NNWzj1{*x)1Au3axY-%DFPw>7W`DR|nq zd34U!ayhox21;iOJm~Ar0YhKFW?^wY{meYcJTCeWe6MI=xKuR2IclBP!ySuYJHL${ z6kMctcju#X7+++ZM30SCq@sv3<7*)eo!O#3Q%~QIkI(C@vYp)y>vA$=+_YaC@Gx_) zq?z;^&jrV#lSOkq>5)|M@udSRzwxJX66AqvaC%j~UZO9WSgdj*(er_vj#4=* zhDQqW+=uT&8a=OP`HmL(0=LRBGUUzY-~{uh58B~zIWIC+1+f8Eyr?$#3`~K2UN2Jve2mLwjr`Iy)Ph zk?D)~IT8RKqaWs$MI7b}Co%n;KJL<ib%HOR>4*0eHoy_?s9X6Z%jAo^=#%>;-;TaK|5G0MVR|2~M<~1~VrrABeOzB{mu?5KoM zWjVVjFO*_vr5FxnI|>n5DYytGCRh`(xdOVM(%IO!*NbN+B8ueEnbb z5_Sj$-I)Ux%CO?ebLRk9jVIcRprmZu7wIRVL2(3D0*2oN$DSfoN zl&1aD_UwsVKSQe5y1=AcB^;$!97gbnB1aJ^IOdO#qtC=p(NOxzSy@h=;Doku;&vSC z&ZoMc_NVBKSC1wH3r^X-m4|I0MPzlHHqMNrwe4Z@JJSsOY$3^bWDa;o9;=ROoT@%6 zJu{c`&3h5ws&BQzi2#!&Md#XhmvR756gZBt zDkl|FI&9rVD6KOfN{~<4SNe8Gg}bS5Far3TUzlxki;Ou@K9A2b4}ZonyiAwr*E4-F zBEHb0*ZzKy37tdxUS6a7pPz=OpOXty{E^$Q%FKVo-x#r+lfuD&>(;fl82Zxra9^nL zG<4?qi}COt(Z!RsScEe{L=s+24ngxmy6PVKOR;4{@yQT|9@YxfG_qmu(**nES2L1@4hnSEThGAVLJEH#?;p%;L^7#{j>ETqtVlp zXX~!+B;9%ZIDGzjZ40@uxYjuQIABgsjrUYrTf5$77DShcY;b1h zvvOLku3gPNky+Y-_i@6ggHiZA?;p0EoyP@xtH(J#$yy(O^l`~a*EcuH;2b~(A5Yuy z(O&w5Pa5x(7I?wA$6F6l&UP8=IA(1zd3d(AQWE`!ni%pp-ebO46nLR&32EvJeiE+c+}V zAxV(*7tRm!zs?e@{z)WDvM|GC^ox`+JHHfI&7~gO#?438b>{Cu&A0JMZ3GVq95{r* zEP6x6n{K0@&PYNN4l}2W?L_A0;?iU;0K zm%Q6;dE@}F1>wK?{eRp3r~l9Y(!Tl4@3h;WeA>SI{rB4Y?|+oKBAbp)w4=fY#Xx ztvmfih@6)LX^?f%{6QWEN3wRO@pwRQN9h!4^YY?iMQ)*846HlbJE7O7qj`4L?%ugm zbf~u2O8=F`@lWS)K=u9mkK5jUX!I0XIbMc%XPAj*m#NdMu4^WZr6ILgoh+piYS4j+)v{2cH zV7RqYc+_=&7ryptuH!G@K;IgiQm)|~E8pQwr->Hja6oh3c3g86X&PO zHfmh1lp7e8L-1w!y^g$+G^($D4Of4)bliO5prTury(Z(&&H{EEdp9CK?co?G%L8ym9Mh+uYbJzNUTVt~pS)o08u;{Tg-| zf@8J#H)X;Hb-5?Ox5WkLgWAIRS@_|r#Zt9cCzoeh31`Tlpk4h7ynP1)?}97n4D`-> z`dw{Go$mLcFeX)f)#a;t+DdAzV~WeTy_7|d;UZ3;AbDw{=TG5-Z2hvxE8AG zS3Y}v>6?D!d-XkiGv})sW0(6?U&@k4$^9CfUTAC}lV|0)%H>^M@T}V-IH|f5&=@L{ z(+m8}MGFr+(H~X z|H1FIul~;8Ya7?El|p#&;%RNMK>*-Hq6`p$WVywwqD^Jh+>S)Z;s<4V6Iy;NNk`#E_mm>n6vWmJ%&5Nk*yUm{}LWXf`n@jrqx?Qg+a)BWo&w4+ajx|`wH}-o)SVT z=g|HL3He1x>8liN=b`OA%4bk0l?m=8Se4Nu0!iK{IFz6l-e1Z`+UK3F*meP}*Bzxb z?Id6_*7Y;qx`efYo-JGN_UYQ3LTIF4JZD4M<;{tqzg=;rfN9*9-nB3$JXWyrCC${k4Q&c4fG}=Z}K#ypfQV z_RhO+H0L>Veu#fQZ~Ob*xXGBwK;hh>GQ@{|p_zCyrJUiUXlLXA#p91dWUe|b>aaC! zZL34BnC{LMTNj?59*5rBu7VFO+lqgNoB54%E*Gn%6_CJ5R63 zg^)x%vv>{VJ^djEFuv-uIy#TX^Sk^*1}Q#{roV`6@Zw3^dUU7V{`md&@WGw7x3`=2 z97l#}B~Rhy3nJ?y=hU)}z=pgtG0kwFdsjlEC!Ht7*b-H~BBoqmV%r$2b4NxKbzV`% zlXiHpTZUz00LD*J=lR)T`g@fAb(rI^c$kGm7F?90V1jeC1 zi>}ySZ#-=w^Mt>QGunb<;C7L+kM}bUN7bH+yb1n1e{xi93HJ#Obi=hR*ch6_otm?C zoXu)=zXdz^|I*4vTU@?TQCthN85?qE#`Vg~V%p#gD@G`h?|7c`wic@$&z>H&yLWC^ zdyE?%YWIR_Yw|xik1VS#&(1T}J!;>$tt>CJ<)x*9)z;&!wsCc}-MV=_a0m`ngcr8j zBds}+9L!#k9qG&InQi)>ltX~A-x*==eg8Y{hwpvAjBq`=DB~C0gHL5ZHBs7GfM(H2 z#udBgGzsq2d7LZPYlZy&?!(LxTQ9EX_gdZ&K{yq-Pqp(C(HOgh`#U>Z?fumE!TaBD zhldBv`DAar@pjv|`A+a?J@q{+N8EmJ58h2gXwdef6I;riMy42T3!1XvnKR{TtHX-C zGRE4Q7hhi5D-wf&kl`!&Q)Wb~JczuOj&kJMMv+sCENlBJ?E()@A9Ci4^w)W9Cuzsi zi?ecE!a2rl&P~p)i?hA9&zY9zlQl;AaS~laag4-(NBiCwZF?ry<5&TXUY{~6g=n} z8B0#>;L!NwLM<*@n(vVda2kw^y|ccIvH5l$c<=4+a=eui~flE0jF++u?>dK>%$%}0TF~u^SUNmz`-l65r?!U`l>?3z9)dH&HXgva!WeBnie3}} zN5|m^z3;fo)8kcj$b{F6+}PA6LZKcIlxj83Xt4-MLp$mK)bL zE4mC_^u8@m1CnxJ-M!BjqsZ(>L_{9GVlNvgk&i+`bc>eN?yr&*)O3 z$SfS7@0-iuVljk!#v5<85alQ`1bFF}t$|Nd7iY0E73t`^ft|=k@X}AIw&qX$_yA|Q zg#Xct;Jp5UHJuMX07G~s;p6x_yzcT0`T)a6JRYR;KK&|e^i@I^>R;DIOW&*8xnuC_ z$MC#=4hCsg-N{FPEp?^dx?R8g*V`@MsOWl6yDCF{_q0l?ck!5N|EQeG`0{&)33;I3 z?)~qDyOJue`i46D%hk7x7nt?PpuU|SJyn$caAvylIW3NlonO~&M1GUY?5?72(OdY& z%IZ>E4-c*=u9Qp1u0>CFUrA>~m0!&q*xcAiD@0_6e`S8U%=wp1*6&=U1HZi2+daTp zXX?m>)TNzpKwpe^IksfZyS9Dhc!z(U*OmLdwA8^_lzTPa`90*3+$&iFtOnSUt7F^v4x|1)R_t6oGK}4Xyk0VOewXcGwCGx!%u~;_ z5uPhUncXHfsw;omQ}(CuZi@#_&z^?%9JEJUp+B`qpdgs`c3B0Ub{Hu`OMjl^{m+)s z+x9B?{n>keJyo0jhBS=tPr8Qm+25Dx=SybLrQ_=|U8XN^8jnD@_U4Ut<4bS1TVMHd z`|59htzC_Pe`RW-99~Z%5Qst{d@!P8KnyWGGU-LFnzA>!?QS?<7!w9(4MsFlReA`C|m9uy*6vKV!q zVV2rlt4Go4 z%a=U96C%6whBL7rQri`TK8D&fr11!k1PkSN;fE2+isQg3@94j}l;53RGr1yQrEd~h z!FNIt2Mgm!Dagk6@U$K7ALsKd0&DN@&zwdu(?;@O34vE~l@JE*42cXX+7+0lkCYe+ zwZ8RLL0}KQx)#_bC*^$*%-|Ox%#UQL{1x4oKTc5N%P`TEJjS$s-ki4yZSa(`!ZBEQ zl{%|E%1eO+dP2VOgO_mMb4sSMbOu8?@bX=oZ6#o3UEy*7U1O~^DNHDTcOv(92boPj z=jRqG&q>CDP{^ocz6=6lhe;H`D5eBg@0f#x{&Kvf9uUw+zqQ5uvNBtr3cm33VkGch zrpxrjOtuPh7 zG%qqH8PP8M41HDz1>ZKiWq3u0Lf_CTvO}l!WDfkeJ1gX~4WUnMU?{T<6#8k^IRhFV z&xp)nMvmd2sMXt{lYPbMco|<4ga$JNuvcF7rMr+e*B{`g<^`F4b#1*}zwu_fapR4^(H4M_ zuMf7`?T_ATpMLUj6M1B7IWh>NF((K-)OPr_zrSB|z_|1+2TP*LB^s*l4&YO?VlZ=r z0Gy)QxRiOnRBbA`I&Bi!$xyx$e4Cn@%N03hVlib0x1V1GXAaud;|G1aNW(m)KjxGL zKu_B7-d6kQqxS=gv$ndvmgX2sxXM}Um1pVSZfJ~1vuABK<0Il~%$ZjZxEb@56WR6Y zg#}=?r(;O#x(B^L#M4+s2Ey?U-=56f<0{{IT@N1KYkLQKsWULiIJ;_^rXgb)o3Zhk zYM1v#2flcARt_7Ek=wUFDT6#`2_roDk~8S;-TQf-@rW!fBIoueciOkU_5Jq#`yaQD zZ{KU*``!=p{dW80lLu{UYrj3tb$AfElD3Nc+uXd_u5Mf_+9R@tW43S<%|w^ACUmSD zq(xJ5pm&*>Q;N<;J|;(2m6sFo@b24>-?>^-+HSYJ?1Q((Uym{ zFy(X_&TKN*=`N>tL_ zyLW5*$o>7jwtui6_*`U;bmxrz58EhuZY#;{%=KDW5jv^g`g;%^i7_Al((hW#7?iPy zken|+XA1{VZBKYc|L$^mIUw<(;&~k}@u6R-tIlDY7bP5Cczn`6x&3L|=d8*Y(RupWk@IbBb)|`T!((f^ z+vF%`(Mb1!FC1YPPr7cb{avTAjhXsw_i51u2h&;F+VKX=H?LhS+%m4((RK6}fwyfZ zrwabIUF487X123@8u)>!tv-S4TMcvv6(%TSL?S=F|*F<%33`lH{yPra?9{Qiui3(fOFrBMZy&u#C* z?a3*BavG&BIIrEJ zFfGg`W0sy9dW61kq-A=fEtxmIXl2?(o+DG1eJNM9Tc7h#JN3?-GymxDA2(GFqT7kQuR~HZ#;oqg#M9f%62hoKbf({B!5cfuq>yfax#WhUdkQH z^0V6nm4$EEMm%yHdK*}gePw5-(k}PSL-XA`QY{o4mF?2*a#ANhzEb^6Yx>-TA7ptB z{^xCf@2H|bYXM8>fXd8IW%Nr8dA~k8EPk5w>iyTR(Zeci`0@I8>9fB-KPm4Qk%qQ? zk<%;q{^Y)VHs3Ge`f-W$cj@@LOqb~kn#LknUVY_EapD%?d%!-hK$zeoggbLwc$oCGWOdzpxl~8;U;iCkz zF#Dwl%)-c?|?wt9dBA7_~YWER>5xG1Mzh8P(R*g*m2|oneNr zX(tBEpyCLw=&axm>95vE#O}BCIl+Dgq8$q4umzMPViQ+Gf$142~k-;j8hj73U-P!>_Q< zDhGTWxLU^Fj5!>bOYXP88YUKBwAI-|{&yn3@$qBRZK8`#AN^R>aiw>}G9|D1yhfax;-(R#vaI*`=Gg zzn1sr+Em7FJkKpSc@@Dmp85{k_Txvz|2Z;5s01qQ(fuE`z3uyHU*MKDJ$rVXcAq6b zzF~39VdN&~)1)Nhk}l{ohu&6|XB)HW^nW?>=+)F6d2^ft%feBKUKDx}W+Vwg>m`=6in!kG5^!C%4~ghle}GNAcI`z(M~fr)^8e023LG(Kv8$ z4pf>K{{JM;7|y}}S@>t*JmUs+|VwT~V> zEPPmBTWd=TD{W(0KHnIY_8~^$VqUIu-EO>bt6jhOM(Ua`ncdEeCx?4&e}5}5I<4{N zcwp3$-&S|VVQFbKZA-h(j_VninOo%yt>{8?2As_AZaA!ns&evZ57`UeSUi>c88`D# zd1SbmnZ8vZCu`3WJgfOkcB2n4xMhSgzbwX?GA}sRo~N7>u->n8XO|b3gQuyl>W!>) zaS~bdabSNha_N4_b0t3oZckD-nsjA?6Nuw-u4uySbZ|a>wVl?Bl+ovO+RSNH?b8z5 zubuU;$ra3~cKR-QuObniaXfRRXKW@p&72tq7P1|-rqX9{ZGHqe(-~j+V0+dyZ`V(zJJ(0{P1pcB3tNLR7Iv7 z%ec*@UT0%1w(Hm5Xz#xJrFM1WdYc#VIALqQt}|(Lr=5}AqrWgf);V^8F&szt$c}^I znImp#aj_yEMbdCYITMTivA~O=pI^_0}70bK`2W_|X=h&hGijm%m(fYG*lWGRM4o?b>F^wfFAb zZ)Yc`nU8d(v^DdTQB_3ovTggEWgEIo&$7FLtsOb6=2NeEcx~fa=^3H`uWoEq*+ zA>(bwQ}9FQ>3w*qv2mHBaJ062H>N?D(tpkMl%&tbPL$Qji3m9cUxx4T>i?CAv7$N7 zXye$X&y;SSdg#a^>1-Wm8@O^F1V&q1+vQ}it)(q)orlNKx468})-vW-H`XiPQR);; zSB7!A_;WO{=ZAB6we2{sUR_TeoUj~!ZB+J2#$Yb|F!j%}H7o?C*D5bu(0*{`z_8Wt za%d>s-O&Q2W92#AG_EyH(Ra_zFVgnC+6HoO_bBfNuhGe(FR-wu(yekCQ&-_>p6gTL z>L{Ok#1D^7J-nH~QDxTW!jimVHB?MmCcw;k7n- zzu=<8D$@6SsrC+zm=2Sd@>njk0FKWFAB!KSE{g@&LsnKqV_peg+^ab$npMOgo&+~s zXdDOXNiAsV&g>~Xt91F1?I`tfyp{b3%+M!IOrtvu9MP`)Mn8Qw_kGtd_${CAsFTyn zyk(ym96icL0|(sld~lZaaqZ)wY|r7az7059`BK*)^8sSPH}FC?1{zk5ygVk0)_YQZ zd*3CGXJGEBN6M=!ZSx%6b6=Z>HlPU>25@HMhh<+$CbEzI_tvG1{NMYA7y8wmT7zsZ z$z}es6IqO1yFHOZv@P|aXW%A3`oY#Tw6prH{qUwf;bJ|lv18Lnvy*Ks^x(Wb4!yD< zpu-xvy@Jb2_*C2d-`o3olIQcTAD8}m-aZ#zCEx$%_y4Y@ABElL!{YPuxPBSw^XhTI zx=Y8`Wx7mX(6ksq{VTus+wE(=`}f=C^=s`)gp0E%YG+X(YK6++gi7A-yb5CsQyL8E zGsE{VEQ|*uqFfMGI1)sNNdyk*lp!ePDicp2)NZV=M+jal!w2Sj7DiGQ+Q5B}j@b#QR62+tomAL{J#8BgE#dl!ha}d}h+w>4N92#6_WhAe563jRj zC|!jAo(7@M_JZ9B!Qn?CAXpg#5kdqi{V^W$5H0|<93p|SzEyprd&;HYl%SmYDK5VE zD&29f3s3|IzkTnHw^ssOMLLyGlXr|)`o@^3k1mSV(ZOjuKZ!s{2m1vk)xH$|k_f|` zQFT9Uu_9bwI3V4m1QI?NuJmbGA!MbX1ZIRxzm#b#{O}%Om{3RPt7n06XMFbi?#?df z(io5PlyA(8qjt!o9;;`~iDv->g?$Fj65#XPs(u1strpK1_Nao38gtPKCH&@H!l62~ zbx;zjjg+(0B|k$Cf!lKr3D3s11kmKMg_1rR?aGrcrL07e08eGZ_1sKbx%BScje0O{d4@+ga z+36|X%IJF~&(V94WKYUb!U!ranyOso*R!)8silshyJH-7-555|PR2HM3=3b->p?EU zE6`BA7tm_sRe; z9iD>Zi^_35eZrW>aMztFwk2dTonY8qSgG@!@PqU4mkG2S8vL3U_xUWXWKb_rmu)kenIyb-8);DgpmDSDgNY19o!rg_X z_4GGa;KuRfOe{t-PNVg!*Mf(0&GuxrmAiTKjdDz^uB4BV%#o&c(u+XHO$H1b@#&%AM{9E(O9oO5jlo zwIauJFpz=O$yv*AH!q@cdMSP43<$n~|3u_QPTLDk@ZeF#qZ`2)-r$Jx$c5cuGd7lY zCYRgH{8F8*w3>@U`+3GGttokZJpCJB@gnnSf9GCB*Zs+#e!cy{zxl)V^{;;;WAQL@ zpq(QaW5>&3^2zOc?RKuS)4)3ThSu4#X>y`(J?9*!TQ_gC`RGz~FOEA-N?YyGuOzZ6 zl332F;2H;nK>{0R?x8O;>7zNw;j|XLuseUIDyo9xX)T}Sq=65!Q-SwvEnE=Y#K{7O z(eu^3tG=ym(NlXxgS&CK>l0*3`h*1!7HWBJ(Vp@|blF|NHn((1>a}%$a zZI2#33f>&GH{X0S`LC9aN=ENHf-rI#r}5zSacyg-E#!616x-w}b1{9?FLlCYaM8yb zxxmaBUHY`LwvslFl`gxnxe=OU&NyGO%ldQ=`lLl1&h)ZKVqWW}5!(7XA? znpgNK$0!(ZMw$zGWp;g78x_}^>_4=jx2xKnyH1n_= zR@MIWBhLoh=soMulH4n~CV6y}Edj2hb9Czt6ZO4vP)P-r>Tk*jZ7^SYUT{u3v{Iv!_>iewO6j&%Xb8 z_gyy1ZHi}ZVK<%h=CIVif#FxKi_M0l`C}+BpDAV3+iD+ldo0` zrO(<+>FXi;SZox*yjKxuxev~%q~NT7B?P2@>Sd$=Gx_Trk-V?J1W3w|`cho-Mkq@e zgn%@sU{z5;$?MQ&d297i1f5d0I5tK?g90#~;bPdMBx;9tffYCqPzg{BBeh?9#>aLd zPfnlY^GQ28IBREz5deSQEe?M|QgR7g`7F5R8icn3Zv6w~5&R>tmAI6#AvAf^`rKDdBr2Sy{5Y(?%;-ODK%e7|g2v=7Fra-<3}DC$p!wKP~rez3(q=FZ|C{ z3R=c)5R}ci!l^6WAPnDaT4`a+QJ*C8Tdd5alFO|LHR;>(XCfzf70uiX26F^`JTWFBd3gagNDTf_|#Ai!#c-;cA?F+poK9zG!G3_ zHe-G%++((s>P|0?j2f zrXLI8JLDEdwjMQH1~cTlSukX4!l!MXQ8}^+C&%f@eyIPmHZeWhre~L{4GilHj2Y=R zJ-3+m7xUgs_z5S8Efqu8EsQ8*{UDQJc_G+gUfR{qIqCz&;Z_kuwMATaW-!tp?QdsH z4%)M)qTX%$6PfJEQ9C<1Oy6yRMyBg$zml`2GR9;La?g{er_J_PqSMJWRa4+XZkwB5 zD#NWvJBH%EmG+Csqqo||=FQ40@`)qE)_RM!!kb;GcJFN6Y5Ti(tDf1V&D61)zRslm z{R|Ih(b&#!ZR1wzVh}qicwF1OQO>gm5AKJ5owuu-w%lAy9%I*W?dgTHZjLfO_~dvy zKHO=Chud}b((?K{ZD#(hHoI`GBBHv1$N8EZUK|b7V*E4^uRdn1=0q#xT1&xNsi+*CHJTwBXtN!g8Bmxt{uNRTQ46yS?p4?ezGd*-G>1XfLw*QMJJ~ ziP~T;ot-&D?7JmvT)ld&aGTM2X?d;9%r0dPavYx2nP30z-~C~;72`YaezmQv-^g=Y z8cx-Cy#L-0+TQL~nzq2XO4@Xg4x(Wc_Xv;RcB2d7pz1%jZZALshPk&eP=vnuqVS9`*b8Q=lB}7Ff;*!+ZRXe;BdD+ ze*7Rf*`uL$ceY9npP6MOB`3ibeMaE)Pv6PLqNy@xMA7YSr7s7CueRp1ONKoAyLZ}O z{P}-u-~8q`+qb{{{gi#!Z1ec{e*5pYuYK)zYpkC=x1F2Cabs;h^L>5&TCVk68^Pb; zUBC%H=jX}w{cKsXIEOM?g7z?0(xEhu!FXe1E$?@ShVd}>IFH_W`_1;&TQ|$uu(p=E z)>gXnX=%Blr#LChYqB7kK!>3($+wU(bboPSuB~5PD?>B~iRd)vevyaGQDra$bLMmC zlnxnsS=-U4Ey{Z1&0DE|CGA+P{AjL79`l)eZ&!)?_cL$PCy`!gJo>qiIb|!z{k?<0 zgmJe=P8okX!C7!rn;BX4o%4><3r|9GM3!w_6 z39zlL3R7n^tJ3B0ot+)KlpMAFgX3H$%@%?5B=e>(gy?Okg>b=D@53ENdItR=5BSd2 zIdFC->07sLY-|LEq0vFtu3n&0!9d3LJYQW|&b3s|Em6brU%S4MKD2f$0v7x;UiyK5 zY*i#wXn*SEd>ahdB4rr!T^yOVOGFz)gMsnk(P?N=Xmi>MUht5!91Y`y#Fz0&It@Jx zPC7U3>ebb1yNGCQC}(u)I}d#9ezBN#gJUiHnCUtbTwpLShqZ;4Pv8w&{j?S_+`s>z z&IQ9;M3EWi&BEQ4_Avc(Hk$L($V6p7$hhjGF*mk!pAJ*w-RD;6@uTZ?S;}|$-0IFQ zyfpWG;^Q8Sz*ye>NoFd*0rj`dxLqdi(tq-j8r!Ql7dw z{FUF!2n|X(ulG$EFH?Q*P6qE7o1q`RbjOLS*I##&x3{C0;j>TBy1hW97;Mzhny2IQt8KSJ=hiD-Saye%l zje&;Xu^i-ZNQ2NFeI)0ROU?VziPJvi;;WKzHGW;z>j3e;zKwuZ@G6IO^11`YC7X1`Q}Wl|saj>BX_xT_rX%V&=Da(k-$`Ruqkx<DrBr z_NBl7JME1xzf(@ICt)@i-+7b@Ober7T$&EU;z)8v0KuA)!Ki{qP%=eQ$+O6K5GHkD zyNr;AT1^xthMet380ki+lpo=PA)Nu=>N+c$F*=Smt6c~Wb)a?1eHNxG(#!c-gAiVh zwFuwZhDmY=6Xl2U5xKdYs4wMfn|Cnpaws_n`HAgPa-E#F?sCGg5$ z!8UC%4rQdvI2(5>jzoiju~lDE{T>N;gsEb*DM$Wt`UFP4a~PG9kuflSFCw&cSOw1l z8}~|(g$u5Hhd11ueZ?{ZZBNDp%;2G@FWara1$f19Y0S>xbjF&4k{}9y36#bU(omL_ zVVqM;^1y-Ao4*>Pl;hKCIc+yi+F3BjI~2OYm%=aD)A6hua&1AvAe=S^ZyYwx!KrRS zC3xsVR|bN&!F6ylf54M5!8r`2g#Hp8otNn{{Swk;#MfsN^6)n%nMN6ZLjHOb`h}nL zt1I;QUEdZtH1F)REiEs$YuB!YHi|Co$}2it0{4q=r2LsV zk#0Teis4$l92|=)>*?cK`ZLu|j*i;a)>e4pY`gi!n{9dHt#)N{Ep2$(PLFL*Cpv5{ za_VZ@%E2@fd1E_uoK)o1m8q5Vtven#Ca!Q=hF48H2kgpnU}L2?15#fAWNf##`<9B@ zJQduqaI0_I7ryuGELj=e`nE{VpPgoi&)eGSdYhP89@V8hTbZSt)5GHJaIbGO*vAFW zv@=29@-GlQk9-t4xL`CrpT3L8A4}gKx4r#?a=+WN0Y<$0e2Zo7T-!TW`~ zqT$AZo7%r@o6PmiHov$T*e^$hm}(pAYwhN(w*%)}ZDILpTU@fk!B{zm#si0g{oVE- z{^&on-~au8-By-Y+duv%|9N0%`#_Ej(OswQ5B}iy+jqYGSAkc@`7#ow%_7J2=fQ&q zg)2)7^KCY5Z*|_6{*Q3561l+qWT3K0#@3`0ZEfRvTUomqU1BjgyCILfDawjddf1Uc zAA6ZEf+yQ;e;1yZ!+~AK$4dWNRUbHmJqL{~2F-KxZan!4ekp@L?%C7hc66{CT;5CG zF6&LCo+}e+XXb&nGN#c}&<=ffChEb#exCJR6Uftb)?Kwr`}EJ89&5)3588LX^Ue1C z?|r|0|NB2^-}~Ns!8J~hRE+yKUxE#1{B) za+H3Q@hzMz64xUYM8;UnZfiIFg%2Di^ft0#8ALM&Yj=py)y2iRc5QR5y>aVCyDE|< z_rQAN>U#UqyYIAj-+jBb{Ua}1I9O3gsRs;=fvAa{o!wd#$stPK6@>xkjn#Jg!Qcv( zqJ3;jZ`C~~c5O+QaX@3~G(o*8lbp+mBtLpNM2asEI%@_v!NKy$?Ke1zMC)bx30kc==iif-U>b4IVk6!vwUmpqGwJ9#`Fj9 zH>b4A*qZmYKa?LYK|>k$&D;6;?)<3~xLAA$?yfrLGH}#RxCu735HL85wwOmt%S);K zd8aeGI~BFY;l_-mu4tuaF}*n8a>PX(q;2Emil^;${rP-=P&zJ_g?16<$nL{_eP(&*_++lP!3@? z-1q6LTX_cm&`5Yb$V>&I6b0YAb1>hNH~%W1OCQPx6xo5jhC`a1#o@)73(oXwpXvfL zWr_OZVCrQW)9y%t%WNAW!=<1Ki?zw1joxk6FM)y^1!rmBwzKdu0B>080(X^ z4h}|T$>>?-@n>Ap9&JG%D@VRhgl3ifry3lb%13`T8oRVbZqL2zY1N$H_5Mrvh9=}e zZ&&50_v^jkUGLPBe9cwx&waVsie7j4qI-@p-~iWNbQw(0Bkw6dyX8L)zcKf<*?5<2 zAux~^e=--rUhU|Zv-!+T_l9F1jIVn|H{o|a;kmJ@_Kxrw4Jf-{^)vmdHsI+NC#Q{N zpXmJFIfk}1-QM2Kv%I6-U?j8e1%&}-ZoRr!U98`~i1e!5N>%nSKmT@h4DbAHuOWTj zv!CX=OrM`fx0jBu%XFE(U}-!8-&=q0EA7j_{rB4P`g(g7h0mE@m>foqv2bExxy6t$ zx7@Rx17!e{KRk-i8^K#XtGzIiTJeJUh0SmnS#e{(dWTDPMtI(iP9uQkkFcqpF3ez< zJ+jGu>JB5x1O zRAd2)14fOszlcIEzp_i|&;M3<+D^lnBld`AbZSxJyg`^4+Td)Cnb`tc0tVJ4 z45eM*s9eH_{#9G&tdO5fKYMghZCRK6n44AE-ghPngAggqDtv8HuNAN4km;18PC{a> zEVYX2;(1r>q7+gv_qO-j*)fA!D*k0B!VJ72u%^#l7&d}k5VeI6ht_!nxe^v@%qcU# zXq>u0(2b^6TykIq2AKm@eBe*;^DbqNP_F;rP(ohb1w%rhay-k>bQlKmelynAIHj&Y zs}wtJ18=y*pkmG$JF8eJF6IRo6Euy1?K|C9Kb+y5@~%F>dxnwPekR{3?v!B$-ZHvn z%;jTka-|Ff|C67 za_hs(^u4UM93d%e!=$vyO5X=TU^ZDrsp zgLUpQmg3d>`+LcY-!U$`PkFYGWE9?>DvaOL_VheF`eeVIo*uP2U+H;x(D`v- zA$n&&aI{$FD7-IxQ-@x3zM#)X$C1m@Pke38n1mOC)!yDg$pp@UWHc9rba;G_d^2rr z?Txm$ypj5+y3BZXUPh|Lm5sPu(F;mh>F91#@fW#ll+dnQ_(vj zfO_AZ?Zl8gH@^~;F|OSZ0tcR)i%yG7gjYK&D({SsKZ{&>kiMU!u7h@d;ao6Letx$mK1mx!=VJtCL?St_ zjG=yG^G4ge{#ILFy`Hu+<})5y0nPEm!N37HpZDR9dmJ^HPbYhk&-U8k!EXEE`#)^| z^Z)$+ZGZmf-)y(ue7pV5@BF>YO~$U^ec)@A{P(~2o%Zc-f2-~6?v(NToiBZ*z4_Kx z+j7Q8yErBo+8HLNr{_|?c{DQ6*UX44=q#*qdbyvm7}uY`u-ad#{@wfSlaFtgq5k>v zv6R2wW}*-1C+Eo1XK8)pPKNoph1tl0p?Q(nZSBTsU`tW*7hR|v2KjD#Soz6sbTtkO z&VzCc=ZDpywar1iMW^t5-RO7+5rE*GG$jEudiTUWk!|IPnFSPD(|FG@uiO$Ql zvmZU~xGn}f(R0pvx_|#+`rjk3w23hkZ3ORw!^orQ*ZC=D#ZlYYw*AyWIlwuy>5IzX zK;q1BCYVSnvLvUY1z;A5ozpME3nV*^hz_&$A{-Uv^U0_8(!RZtqu+Vw&EV**jN4M$ z^sJmb^iWQVR}|= zK<90%*d1>@8WB9qS9R~gOoS$bf` zM$(p&bw6w(W=y`B2 zQ?s|D3Ld@d_ozOf+Ee=Ts4cyeQCU*5%2QuG4@#Dkt>3Aum#2LlM%|H>jJa=t=inIf zUVoDw;DCSN3|=uez7< ze3|mw_?0}H`|z-IZ25A3sBVC3moY~Rzx<8L)$ZKt?-jnhs$;lUSAO?)beuLOU}Aw2 z+SchnZ@)R9bLH?#orPyf<}uq3+#^@(HhSS)z0+K1tM}RA(5+fHoP>^}x$4DB>)B}B zlwA(W&_c8eZYZO+I@gXMvpmihMW?md?l|mCbb|Cg^y;KNe7Kc%gf`chsx|-V|4T@| zO5l?J`;T8}`b@d`+Ux(@)z#bg^QB)z8JFo*G6OChUzh1JeZkVy;#~XcfA+iWov(bk zP0h_#G{_L?Q4AuVWk?FY5Ix0Ej^UJG5e8U-Mi^AYn9hg@IQfnd5#%Sr)CjEvaE7NR z5l#vAgkxJ4rpOXTI1wmon73z~UACoQGRN3XGr_Tx_pR!q zXc05^@X7!H|MW>jK~(Y>$~baLC`+3$aOFxA3HPipsXfxeXeSAcDYp!25u$7{<2!}k z_H`U!#d0}(Mq{M@Vrv+OIk9bs@^Cd)tqk)#}eDQ7)dI+3HZV*Ks@CwM}G6 z8o#ns!hLWqz$hW91iIiN<0G+9-?Y6}Ucrk9Y9-vJUjRqI1sU)uVKuM;AD3}w+_U-< zyd{FCI=w_l&5LOS_~cgpD}m7;ya+Cqkp0wl3m3tkE49_9adLKvXB?*LP$rxijES6A z`cP4hnRCkSD@VI?jUwJ7%z7CVjxzFEVH-S46Y9M*qaA0g;29wkEEoiJ!5rqef?vi{ z9onuPRvg#Ls(gnJ=3rNj%olV5EK+8aWGgzSX41E`^*s2X?#pzUe$CTwkmKtoO}OFN zPdh15!=H5h=+_^YirtKo@91N_6M|H-L}(G3gBD-gT(3w33Oz%bWDx>GhkRvhP62o( zgC1r_F)l|{-a#|#9dbix+Mvv%Tb_3#XJ1&*jRvD_Qc@1y<$Em%i9*eZ08$n{P`LB3 z%EK4YWAw2br+YN*OP-Uyp{HfI%nxls!$l>mtzQqFy;{*b&o9m^ib=j|s5LIm3 zEXIwQ0L*<(E-8gOL+j!sJSnY9dpJUl44(DSCIBSOodu?ZDs~sHf z7aX6f4=2Yf@T`14d(v0s;x`O|ON$orICsYuG0#fgsx4)7E|+>l)`+rkA4|k{7MEAs zwd*(AQa;HQw!;J4%}vopH&WknU@@Qa$VOMv$H-1Iiz%%;vN-G}Cvp``r(QZ0o?Z3t|8CpZyjDh7cseyb7rAR8W1D^ibfU$cU2v?7*S1V^3s(cT;8|pWFxEDgKCG_a zY_s$0RqpoIz4qwQ{fueaC;})l9OtC%K^K>n+uFvBHaVR#t}GY+a2)oi^IR_?FFy^Q zfQNC*sB6UYi^KNA_rBNu;~)RK_Km;z^Y%x7^hfP4|MHt9L;u5n{7>3fzWk-s*Q5U# zt;nkDtE**D{^;Y6GUoHO72opGYL_`8(`;`&Zu|SYHLb}u(5j;5s^0YNg~e*-E7^N+ z6uGo1?W^zdro7GR}8i$K+#Pk%<{Nok4Z5f6(^!_sbE%aLJ*-@aXy05Gov*@LFIn7Q^Y|naDdJj1je(Fc9-p_Y+m292?(Qops^QLUeSI(}`Wl>;PGe$7w zII?Xz8Tj3(?HB1t9Ecx$@KMI^tQHrD_Ohj)Gp;zhKK@F}krt9MD>yY zG9G6>;5QlUf+w0tZ{bYSX8cPZ$?V2h1eEi#Iv=u2NY`D;8Jx>};($i$;n&jgLR(qJ z52k{fqT~9a0g-9iN1rd|rGn6~69dX};6P7l{G7FccP|MKD2`BL|XBM*i$ibtkr{ZqS)Z!ZU&`bAdg zpZUN4L4Znr)kmdQW%lo{r+OAR_PX)@d{2Me8?p{^Nu5zXdS~d1c8zMwcbDHirG)&4 zJ}2ej%Qn=g(UE)3YC}G|bEv;l_&n+l-IHy{BYGkHE&bbHFS4G&2RKgO^c#KhS@xmu zAkWYS^avfQh@{AQy;mK6XeL^THo_+T179)XIZzXwXH0J3?;eXnr z0cBU|nUV%r_8UI+zx01_sA~i>c}J!9@#y#KUf=`%Qiq@CV3l^KU0ue+Q@Z2LLon>+ zgH=BZt?W6F9~1^0%cafQHsCP&irx*gmR{`Rgfoo^}il zDzDP>y@Sr6oBBnTCO@zdd0!i=-d;rR=~w7~>R|IS=4hAx%kMq3!|5Gevr|Vd%^7T?rn&{_N*XLs>(4#;uRtD_9Pn zKV5nWzn>xXx_|cf|5GPzA87Bd({<_ix=fep3zo(sOkaKX&GznZeKiX7dV3M(gau%f z!}(eilV@QfNG3)}SjT`dy;lN4m{9JOaXtAEgi>n4Y{(9!#Dy`rhlvki(-^cBJ~Lrn za}h={I6|bArWmLCDL&4Uc;#QwYr-kv9P$Ien4gv9t&*30Fv zaIO|(!bmVF;4}L5v(uF2-CBh+5+M2*jg%|GNA7n)tiR{GcL*TL90W0aR9?VT-<=C0 z{}~1O$VzchJ`R>XZ3jD1qE5SG=2x8vO(nplZ|ps#Tm`P$>{*(f?-a^zFu0)T6#ToQ zCY2zmqrT_zjia*^tSDdRhHVewAtOMovak8TLDmIfmxurnXp8{xuY^*CrVYls<^x=e z0tS}G#Cdt%EoCqlfvpRA5#r4!IC2qXFoLG<3M20k8VP?^Suy$^93ItJio`PC3Le#_ zXN9}Q7%npKc0tps_=(zn$x8lmmZo2#DdCS5mIa3Zq#`YJU){L}KR9v0pd!CUQE_nN z()o3nz5wa(M8sF7Khjf|RKH)l>fY%3sgn2l$LRX}zg~F0`I>M3E3-##beVv&K6EXg zvvX5zeRSY{ceE=(H1SFC%yJ?XtsX1I*y?fgvFLgDvPciKhtcHOvu-4Qf#@f{s2O=g zl04z?u$n!z3Xfp$LO*RM%Rs?kW<`8=q>P0oGBh5CZrW;!alIRJil>Bbqn-NKWgd$w zCQ?V*cWO&!hR4~WyR&o7rCLg>l#zBm7Y)yOg4WtHjqx6AtZEHUy}(a$ry`m3CjC0w zZWm{V;RmO62GP@8<;-JDyb{@9Y9`ODggz?TJ2SV`=9kvX@y1YTK@tN+ojEnT8d+tw z=z1A0((k^78@^!68$4&SR!HNMPr^&4CTH5>^3}GqBFbo^>XU3QH^02rCg(P4%fZR% zxxoIS*%o_wb)$`4Sxhd@sxB)=QY(Hbf~%h|mXv;vr{5Wpq{x=#4|yJ$>`~jgChwZpQi4Ec6zwe9^Aj3w%=}3nM3)P#0XB7 zK56&ve%ikEt-q=*&qM|N)Bp0nX#dUs?tkC@*?;w4x8M5O-)qj>GXCH?8+lV?n)7^? zmX_O>zx0)M?b=4$dUU_tz57u`&+Vs8{d`l#v$M>j)5tIB*>wJ^?HxHyIjD@k#*nOr z6d9o+!FnQ}!HdaBa=pmG#o(*6&@wK;rzhtbArg3`9XdDDLZn?v&f{!2kr1+ zKXTVa-e1TZn9DmE_mjiGH_)1#Zxd5%ZEkVB&1dYU=nlcjqoe(z2OJ$`XbcVNcyN}n z_@sUO(Z}uUfA;6?kN@aTEAnZ+wrAw@Ic|^c-)VpL^{==0-+wPO;YC}^cr9j(CNd{2 zDk4+SQ#gm5r}f4gx7y0uY8h`Cbo;h#Cz&&mDTCmgzznzO92~2&+tSYEm8EhJa2nIW zIG1WygTPi^TOanbQ(lz(#c^=UB)fX`YUyt1bB_cWE18u;mjj9Z22R(mT}>OKdxghv zc0RcGpgu*JJPCa@W^ltcj%dtA_|}b^*Mnc<)h5wc^e1h!1*mN%mzNd_7f>UW7`r|n z+#$~c1wE?-?7~6)a53`Y8Fgk+^oiPiB=9OZ9dFEY^1SxrffezbPYxvdfe17>3mPXpv}o1LxDOa$;pX!`*_zb8U0;YB`gf{l;m8ciOTH+zelb+m-6$=C$?E z2~nT$IBf`T$5X+%cnJK;I}G=DqisCV70yVGRFR6>K_}v5WQ14AbnrzIJ^0}MR{FA& zcH&vlZ(qQ_u2-)H2X5ZHS+LmI-ESY?{a&L3pO6ukNTJI=l^e0u8(f3|YzPOpI9BTP22T`8YZNJl} zvJWNm;AAxLwKz4os&w^?ii0B+@fCejQjR`Y*iZ|LLl@0sdT{kIc;9(NUr=0cqt6n<|7mBR^WBD|ZJg}dTew&Frj7E7Vh4kikv5hsCzo;X zJO6sB@4YQj$r-(onmPPe?HU%+jaqm z9Js0d{mB|-Tyw0OUIKbOG z#0ZxapjRjZGf}1@==3uQlJZ}z;)`<9x7%QR?`B7&!?om5F6dhMZ z{U=FXz@kv35rMh>lpss4DS;os-8XZ2olo z?<=v*JGiFZ1YOE)KO2DI;yjA?aXqub`1Jg=Z~#s!tF{&m0JK+ql=j-*GVQgc3?aR? zEd-zH%Co*AGs^7zdv@z{PyBF{Sv8g(snD)apb7^ zw!U$_%`Y+5E~PB}j%=XL*|oroK{0Yt=rov?VSk!~g)vp%ZEO1?@L){0xIx6&mB?1h zbuQF&%2cO?6?1b-ZD!$WV7{8Z%;tRtm=TYgO#AE1BSxEy-lm^dP^UwYBxlwz7UbZJW<~3}1aEJoyd}?pyd- z++x90YsUxM?bA;_3VbhWJGeTJ)m)35X`U~yh|Ig*-g^7Zax(m*fBcWyfA*jKqxRN2 zUutuU#(OTZUU2)VxpEv?@2up}H{N`!z4g{RZEj|&?eA|z*4xjVwMu_F;}AF}Pt{X$ zi#g3mHFD@?9`?Qs!hr7tMO%ql-S0QJGputIWb9Jr1Q=dPzsH}YzMYEjd;G}Oowk#N zuidbiDOa#CuWP4+^m%@6A+QdPq@DJ~`GNeEL!QAO6Sxq5aE$^{?CazW4o#F0w5g`f~T~-S*)JKWxsGB7ZT^aYFR% zOuM6xTrWz2yuHGS82UE9IF~w{FL=;t#YuN?iL_i@S&DvP>uFI7!GjkJojt0jB9cPK zIJx>ZcbONZzdeuM($AWD_Ou(+(Ji0Gf}C59sm+bxlf?zgWgvX;a4YklL9x?Nawl45 zo}oXsih6QRw|L$b(&m*_TRtwe>({T91MWCw*xJtaedZk6_$X!Gz4suvj#e>zPvp5R z@}f5_F9r^Md@AxnU1)XaB&XWj@4QiGjnTUv-hWv14gP_z$TjD0ZEtTEJy^3X;%ew1*))i7|G|T{9r~$m3l?h2uFz}K(A-*C zSxmdHwB67K4lid}*?QN)uhQc%mCRGJJA?hr8=DoWMpkBYwe=yG+Erv>alW=>^quZy zyvf(&v+_Z zTPwn@@>$dwx}Un#(YI*qW8%B5APZ)}740|2j0t|$qq;bdGM6$277&O`Tf4g2-g@I! z@^fB|6`iXyj020JPx+rsLA04DzM^>fZ9Z&nUTX{KX8=<;Y&%Tnc3Gssi3jH9km$q5 zxkP482agsOGTv#gxz9n*=>@z$%pCpTqmMHdeSU!xT2;=tV;8q&~?ey=~Td-Z<5 z*ZVNkE%p3q(dcKV19*nH;(OIrbykL<=$D@_?|UE9kdih$uluny3c)JUpb3D-t zwWT{&$VuATolVuQ(6Dmy2Cu3>Woc_*-plrm_k-ub+d6_H)tlSS{aRmNFDE=45RtnV z+>uY2WQ20MNB%Jn&}nl)&r@X8uPY@J2DjmL^(FNdJWD<)%TtZFe1!w`-0zN0FQ4_o z^3+=elxnNb`kj9n?n=Fs{-fhk$1^;e9Eo0_jUDg$Sb{^zpXvyF&EdkIQ90_VXD`32 zM@o+BSbyHH{;cpIk4nZ(*(tWeK%O*STYBFtp14xH-90z(H+ZaF3LD;oYvo`bwHxiw z7j=1VTxP@XYX0O;>(N1DTzN+ADtlmfWi4(?z1o3pTBKnd@rT-O79G#$?w-hHTe`Bp zC^aQ1OdWpKkGk<%`t0wYCk^HQboIO%iywdeqSDV&_D{<9dO5$$>(?=nXfGXKm+3Nn zQBt(p>uOl1ooA{k0LlVI}=J6At3LG45Bsyt5OaDF z8mv~KT!v`}PT*)oHuw{uy0Ad72>|mSMVdgS@0@bAEt4@z|2Qnp^etm1AK{6x#6iYL zM~KoF=Y_d1ad;50BuW4whr-24!&yUC9=1pXqsinIjg%3ubG)p=t3BVNtTPZ0yli)P zVvqRKUlT9KNWjrHU}PBU3XD&}C1Xh!G^_u?G0Iv09f6qenLbkn?Ol3iI=^XJs&D+qz7b>DMs*${b&7%ParA zx%{(Szu5FQl$giA>^l8IPS7Yci+r&#&o~ku9U5ZgE*c|J>n!rZ$!(io4aN zebJ8dBvN4IFGIwbE3}mCljrCrBfCD46_j6*2I1X|`D70LVc_TFc>eStbn_szHN^1+ zeyt6*F5FJP4vH6(mBws+}g@vy*caivX6lZBSjPrSwI_mR;kazt0r z(Efa+p4whFFnjv+IJBGW1kScCoG(6C&bIKEsaa=ot>t;=9b_ahnFy@A(?$vaUWD&I zIqNVfIJ(Z-qldTK!TwHQVv$kqjXh0YPutn?eq@+_E`+h;K)Ek6v0`x!TsRz1hYloH-U4 zUlGAKUR!dB>bWw-VB4KovKfGJ;xDuF`Oj1s(K>hh) zV6YeX1TMTz!2@SaIa_FHWur~crtY!DjO}8ZU6{@=S`c=aaXhPh@VvI=)BdsW_Tb;f z^;>Ou{YJYovy%Iql9>a+o9X#$?dr96+qKQrjL%jXkk>ahGOlyU!+53dPb#YG2jBlr zdz{a?x#_mKd83JFGymW5|y|`$*TX)*MjM>@wQNeY3%0e?+XHJ*gPo61bU~qMOd@*=p zyUuRJRLfCx3XXM77hUYm!pJQrTkTK&_>bCu{F6U#|MFk{LHq7^zn{4q9p>VB+uzF^ z44&HJ@!$WuKdNXd4!-&Me&(0$IFIQmnfvq@(MqBMMZR-nJ$&%EZSQmgJ_8+^M)yF+ z%oUO;M;RH5BWN|c1l-_A`iGhg+IT=_IK%;#j_!%1jS8)s1M29UYy%%!UvtK|$?US6yV zjojT8fwxjS`>c5}Y2In4oQd|bz(raBzDT#gChrxVrS0^esiNgCqI=M%)Bf-$?W4zDyS~|O-nw29ePnpitMF=jYd7Qi zsOqA>iX1ylosif2=$pu}n>TMk$Ep)=#jhpgV8HW@;GiuhC3t7cHsb;|{p_@peB$dD zp;4RFf6hl2XDa%Sta46r5W`u{Gtqp;$QXR*J3q+h<92dtSCsB3z=OKZhbDnzr{ zIaw14vG7e}leAkN59+;KLvr75IMmNB?dA3S{r%UIGG9G^J^l5($<^ER`Xk?8dw-~> zdNBH~*>HqCVCajaJbxAf>AUPzv=_oFhScGZ^m;w7|Nr{^eDte3yZXJfCUwK-p$%xT z@dYb$u+M!m3MWg4Vb{mIO!d;{ME@phC9gJG?6AM@{J695-G!QS#@?8Vq~(ZL2B(*~ zqF!{ub9g7YUy-e$L6W(v&E`S>&G{eX()3Z^B<(2(8vp$3sl%dv`m8J1miN)BdH^o< zN`F42(x+2q;ZO4RM_|~?03Y<#`~b5qpUTqP(U0s%+mgA4Fm!ZCFKel~N56)f-p{?^ zlGrtBy!>!4ziVfvTym5HGFQ!=(R*a#qD{G9cx?=e*Yv)FW7!CDSwyCv)tBV$;{eV; zF~2fbJSsn{e|a(AlP6)2rO(M&ny_hbHwa5Tv{Uft)+GJb<_2_DXN>+fgIMse=KFh^cLU(8v2M%U^+ z`M|8&7kuV?v+`Ab_X+K_g~3#mb}Q`Dj%QDPeQ@J4U8Yg`)j7UaR{#4VL_foo|9^$) z7g1-YWL4J7l7{cf&S&+lE8ZLii;)EeUf*Q{+mtO7ud|Y!vnCX$ewXtL9ZhM&7I>wAby3_!de|b(Gqm>nJaSLuAzQZfd%FF!J-^s*hX-4s`JvlsJNo_N1)0g&I2Hme zlv6=pIDhI)1Lt9lyJo`276Y3ewa)ovtHJI-kia-REpQ~;v~jHtjPbbe5apkq9;96- z#Y-lp7>t~4rQDQ>2L_Ii|u zchjHlNN}cBjcX!wc}&X&h6mAQE>9C9q#W$26!46kqs6{ zQA*vpMgnX+9SM!Ba>bF$A%5b0Osg{LC^j@z^I!?v?6f@r6V z-8XN&-PYD_w1vgB(o5hpV_8MK*{ZVoXQDl6yE|L$2jBle`&YmJFWc_+R%EZth>U4_ z9$ET)zrFW^Z@1t7{eRuQ^{wx&5OMMppz80yif>FMFD)<~H2s8f1V zr$@GoGjGY-oH16k+s#7XZ9TZMx)^zXvK%t%cShC5=GBt>$ggw^+bcSgizDvSPw%vY z!^6Oni5rEx^#G&UbT+Y6?-n^AQy{LQIWO0Hv(~USwuC8Y+7Z%&<%1YZv{?da}9yoGx z*|xCPA3B!%M;!0wcIKk-AiHynama8uEvFn&TBTzoDF<$70|R?40!{nruBKbpzkq;a zwnz4%Z8c%mJ(RQ$HmM!4qfBvY&ZAJ z+fP2dn>i(#k8U%P7XlA+CI2)j7nuMt?6B`+fU@=9uRfD^^k02)$orZ9v{^Yrd9I$X za*VFm%JH+(%P)mL(ojbK{_43j{2q9>&*5IZpRZl-N)Lh)=79dVe3!Ep5af&ZIvo1@ zm0quJ^i>~vKl(dEmRev@_eZd*2cG-v_Jh*7)$e(dx&}G}PvLfrU*;6r;?=SprO0wt zt=@o``Am_u%3Z=&o$)j@abbJYOTh{{Q#k8 zOWxJyqGxHV{8GK2va0-ghx|D}I%)Vad{)DHQl?A0hPKIAea)p_bF`f1>~5hM-j^58 zs>SiC*Mgmb(@c=G%t;&4Y*M-bkyfAOpn0W>=)mKQ6HnE+! zr`!5z5eQk8vwbJ@-ogga$Y}1_>65yTrr8b?AIfmnyLG(=11U{T8UQq;&t&=)B(VEc zr_a_o;Kb|SU%!U?!{_H+e^(QVcIo)KOqb~kk~ZJE)xPw#ueGJMmG(43>$7kN3<;MY zI8r#QG{(qmRX{<*gp1+f7a?{S6ybqlA~Izn_b|fR13m95%YM%GJI6>lW2`W=Lc8h< zGn|{9FXN4E5zfvj7!gSFzSU{YVjytW%H%LijEcjGv&(8r+s#qmytIvxabkQrWA&`i^rmac{ z$`lN9!FGvO_%j&ROv!tcVG01V9UPFrgFzRr)_j8tc@OO1l)l@tix5hA)kfQmsC!tE zMd)?E>JQxDkFz;ys}>Hh+^58(iYhu?u!hfLX$nn1^6D?HYn@p6y@G(en#HfnvQX@j4$E0-YF%1vS@475xR*NqKRd& zAV*XmMk{3VUh$7fTR(NVi37=&XY=z*#h;%<&Jo>&M%KAKxzD+g?w2gZp*KD6jI51Z zYbEbYPvXntDQhx7W7Jn`>U}D@{V3l=_=etwZ+Cbz)Px3y524Zh%qfdFIPB(=Ph>a) zeB_yO6e-gskqeC7z{{2QBJznt<#)mhEr<%gd|_cmc-VO4hx9)!EV+stb#ii$=g->8 zO2%*XW@M(t;z!_J#t@M@lPhV@LY|3mv1li}ZFV8mk)M)hvdc>N&hpB7@{6j{ZwsPM zs(*F9X7HdpqolO?`ANpY8JLVV-PrczY`^Uv?4{4fY$AO)4V*~CQ8;Cb}oQZLH$v8 zt^|K}+Bg2}kJ`WdSO34-f_rU!rA;T#{?5a;b^mrdc2-q>E1M&;JC~%$G0)BdV>4qc zGR#q(gR*(;W?Q{_Gce7)lI?<q8xGpJwWtEEnXu#WPH0*w#&)pu>NjuKWsZY zTPX`}MW!Lc=l&ENcAi^}6^Dw>7|($|NMs~6-|+~dcO+s^JzTV7gf>+72Z zJCf@``v2hm{j@hFqZ66qHAjL6pMLoL_J@D?hwTsk;NQ0Y<$w7X?ct-xrF%H@=i#GA z?a{;g?cZlB)0Q_dvLtasmix129zV&x+2tTyar9MCp%WS~p6U0rYk4wTU^ z_q3gpiA>KBY5PGAt~cMfQBDiaQuOlr_04wc){Sy}aYEYCk7I*Vp}PCimUAaibg*=Dtg$oO~P+jLG0b9$Z>nDreWdQKXaX=&SQy&|I>#tInXw zv(jTC6EjAm<8~JClDyr(+~ID)A$gcVT3&`y5gl*8^=6d^UI+U}?a^cB=Is_tIj-#P zL5H<)%ZPCHz5Vt(Y5z>|6^2$0H2ST!f(NI`wQJYvd@_r=Y@LP1SxC6M%Yk-L{lr@> zvNV}-FmuJYa|SZxlY#M`+A1^sHBKT_)Mdt@Bjw1+=m znvr9-;F9sBf51bN1YLE%XfWQEGVnM!qbv#U9X4U=;6bnU+_!B-@rT30x+bDdr$w3 zd2IooF|J6v+}9ud(>~(~N6<1+bmpM^wKZctEj)#jbbW1u7aXA$SC}&elhkS64ax7~ z$O(pTU6*c!u(_b4J2Eh`7=Xx!0E^V0mXjp|wEGxBepXMdLBDxdYv_VovJ!e+|KUc=E z%iH9ZZfEPqrdZ@V+Z~q4?;hG(3*YiLlr=aYC&s%Ijhtc8@mb`i$6LFR14R9?6Oz+M zi_=rq`FYBV{s0FDJglBqe?LD}eZ%GVXYajs{i4$^qs+f4{kS?`@8@T)zYFPS={N3r z>G--#m+1?T#wNzw8()66z4euM+e8FMhJ1{L{%N1^a-3jD3^^m_hk;>geH*hV(Zx;r z%AInsgi#S3Fft5(GRzJmwRIpT7Qx2K$%7*+ds~E&e%L!F5vNZXwNlzV3gK($5#}*`Nic>o{17r%25?YS=$5VJAs8zTU+0xy}oxr$3f5z&7K>T ztBt8I0=^a79AGIR(g()*wE9U1(KlV@1PVY326GEbWt5{xgiNNteT59>PRV?7A;O9w zY_i%U;!U5xm2$PRv|Md_c40*y1+Q;qL?C#Q_nploN=tc^imsSg5z49YEX^1%q0arj zVu=92C>W(mN;{RQj|8N_spC?wc2VvKkhNcS#?ZUQ(0JI|5WFd$rzZ}`&Q;?_*rZei zeor$lQHG8Vj@#khaS0*6c1e>6L4idLZQ9Qn3TMEAz}baL0%aFuyFoC|3P(oDQOfXM z7vSMV;GFx$3@();GdOL&h*FdXY|R7XL>Si;t42#`8~vt;b4-~_-otM3Tmqx$0eQ?x zLT5e8rHvJ3P=a~dk&c;1Rz)eNgvPYV7DnYPOB>zSFG}<2xou4Q)-Z&ArIx`<>A6?< zuAlmyyUMa^)4YW{B19P_%}G%XL#iz_N9C!{6H#Ce#%ILl{IWHpewHQRGF_(s^y!P? z_>u+!@Z+vZ`GSD_qEgEG*-Aq>(1K16KAYS@kL6N_h;iqaSh-nSm4rSqwBEdVy=Y(Y zq|hLab_Th@nBlXO{SaKnkCHzoJFmnym5tUGjjzf&ZAC*x1TYFSu;Zf^a%ive`hp&d z7Az=<0v{SkNhe#78ORgpVbQzr26VM(ae7wK@u9`DGtS<+(XL***=k$1^x<&d_FLy| zY58iKS-jPwttOWu*DR#|h%{;cI7ieNhee0ovkT{GoZiZGRkgX zb(k@Jnm&RRLm?+-=g(x`=aJQn0q3X)p>C8?hB}_Kv!lE1@%<0l&i4JbyZbnOVz7-& z_#`sf>3(~7|I_y1-X~Qid^WVM0&)%?N5+4tB)vMP_ zez8j58ER9>M`mtgBG;>O0)hlzz6zi)l(o9#dR`~Q$SGWXLj z&b1HTe?PGPH|-C8{|_>^pSJnn_>0Kb&of^h-n-rY=#T%f{rkN0=+R!ysj=Y6d32ne zz5RCo{)3wPb(Uc6uS7l(xwWyeUR$=Ul*8R2{|Lh5<-L7!LG zR#WDSJQrPTzvt;~8(X zf?UiP+0Sk1vZQmm78h-CFCw=0hfW6Pk?3+L1gFTTqFsHLcc~&orc+kUzL!S&JbrG5=OokL04z4rF;=^PZ*TLKT2k%OVG80 zOCt1!D3|UScoulk8@iK7-~D;!k_x7wjrb*JDT6*3VsPeY@i({-95F^5L}0hDv{3lF zy|Wh@@wA*;rGqLg9UFnYHq@e+w67c9UHC$GG}OJc4{Xi7 zx@UacuRJ|(UB!O;doRl(8rFeeLP?F)m8oL-|GLKJ@5G(rCvs!CQHv( zzxw_B92}=F)2L2(M!u=?($9ivo)n%I-jVTS&3~hJ>Zh--rB`j!0Ju2R#YSW|nSSQq zu+YGL^ly~Ca8_H;P_Rc=wBhwsFi|$!Ltu|SXh<*HVr=qhcX+z=rC`i1llO{ly}Y_T zr0iiCJN0+ky%YLGzC-ia`9d#qDMwVS1qJZDY!_+M(BIEXeGFfH=3D;dtk8z?CpMz%Y! z63saPBECdIJ^TN&_upTZCCQ!O=cz(#kr64Xs;d>S;Ovr1{=h^2#B=t)B@fSV&+Z(K z28JV`1{&RHSt?~@XsuH4`!RnvGOJP5U1&6b>PC3v&G+8DeqETGo11Vm4`co&mOilbw~7XyMiy9W>B0NAO%`j`IJ^W5`^ks~}3h`}AaQ%%97n6_Nr#oYCB!yM)r zW~TBazukB4ccTd7PxnGnA7OupUq2W_F-5+EE5U^E>-FX9cDQ%c_IB)Q?1sXxa{>z} zC9EYDvG4%yXRL4C?gn1)!9?qeaED+eFI?ow^`?GR|4jeCXcRqj}X`{`=e1SG3^?WpZS zb{YpFg>PWdnb*EEjNwf6i-|lnXoqmn}C&cHI5KEDT2cb;+;2RIK)=`Refm?`R>#6)btl@3cS&@y0wKcuM zHs?O?UW$42wZbGK{;2~^tIa-n&Du-3i&jz8d&in!{k8k`R_Z}-(PbW0*2#mz{ZiJT zr!H%zUBO*pDFm1^7^m8Jc&CXOXFx5bJu_W7dw!Vb;lpO;1Ddy?1U2Tyo6|Z|2=9TX z=q^6tDb5bdfOU3yRGWcr+_*?~Mi`-9j@s$*K@+CAy?Rr-gm2tr+yb-7GI&jnr!2~g ztQ`zZy-rFK3a9gwXZ^}8R|~Io*>_kw)9m>4u<8UeXKhW*ECn8S!qe^6Ix(I8-MlrE z_ZU~QevI92j$;hqARQxRZ9=x*;S|-_W5P_`$=d&U^|S#>VqId924g zM0R$!vwnrQN*U!rk-k%Czj<}mj`lWF$8O^ZvVQM=@N6RQ^s{H+iO`r2-g~b-c=(Mr zJIl+YD~@=6Pfb$5pQb;L+VbLJ`_{L<89uQ`2DlY?+zf6^&rP;jMvyT)gmDhfaDJ3F zya~=Pwp-&2iPLR->}G}AJ4kzli4=NJxITFH{s-S`|EK@?|I*gi)@rQqf;?V$Aqi*3 zU}7D%K?YAAa3nE82nV&7cg~8>xOpddSYu=?D3Ffp9lRr6#$3Z2Tf?36W$eJfSzina zjCTwKhZ(cevy&z~*~0u%8O5BJ)N!sGLU^^`EDtpIBuX~2gi8a>Jy&q4JRAGmz=417 zum8OL-tYdW_Q|J@+Wy{Qg%SLtKl-!wU;gtSv`=%7!j2Kdxjw@9J$WqL;z=12*Vi9r z93PZHZeeM$3?1YFN_m^tD9_f`*4y1&yvFcyo=>OG;JSZs*fvHUO~vo!55I`t#|xG0 z6WT->%ag`+e2m_-z`;3i(;-X!tSNH`FD-N%ZzUnTyi2hw^7Ww>&&LEV@`_q&*bL6>dAh*-3{TGK5k}IyX5cKDF}Q7`6kb(((CXqZGmm&4?(+yqTlB9R!%nL|3?Ips zYd9}5;~2W}>8GEjjb{}}!A1s=J60-h`j)abHZ}{7&?P*-aH@+7%T@o@=4RXD!Ikzf zgfR-~htP{W&h~})+up9W^VXwm$0NhvE_-yvtozm&GG)X--bznTsBk0zL34nLd~240%G=!Ewe@XY4WhgPX~~OS(KBldt3zuq)X6 zZXA-w{n4}1VPsr9ALJYP^xJ*yc-PqF(>Ps?gL_w(GDn|&*ZZA*c*hXtmHIB#XaD-S zRQ!#9fZTtLzDvEV;l(Py+NDly>c$QD)IFE1_5GPP^|I>KDp|SxcRf-1+xCs>s5E>{ zw&9)rIV!ADhlBRiyZ)stu=JT3QMe{`{O0w^kkLb4l8w>KrO<4~uYrEz9nb{EkS@dO zb2rGF>l&qhlfl>8cx+C*wn0S*KROik_59|odC_r+u{rRnzA&EjzVx{_?4u-d1mo>KnDg z@6WY$blbh6IqA1~M@ME3y^9;lE&TS%aBoyz&5ev%6_?+VPw++`+%f0q9gGqBksN__ zH%5A~?y08U&S%P3H#jQ?PG}FA0Nvf(+${ro8N7lv_`-n(lo2hztF`sdfBqjz|J!M3 z_g76{CBHmh4yF8933?7EVt9%uDV`Y<_R2VjH-OnvId{4;2&+xzD)3B6&+vS^pEld^dnVIpov=+QnQAMJ*9 zo*LLAq?8O`YoWr7DZ3bql#D?kMB1fYMz6rZSl9`U$LUHS0t2Jv>+&KJR!Azt7^Wia zQ8%N-`OAyCR|b{j0W0ko6nSt1J}A5d=d>-&Nd6IH6S$llioL!cA^M!0`1Mc5v~WFG zmG1?PQ5(;bwHf!^c$S64PRd+Wj>qZLqaRR{6aek$f(dr zK>wLMRmMC2cj3$$p3f{urO=3cyuQ9zo(I;PQYxfeMl5S(t^J`VwSzm4csE~AYNk9i zw92Z|J?nHGJw}tz(NL@U{W3IInG6~gaxc$`(7XW{+R(tssjT;TPT^bzp`*iUBifEH zDY_Zj>b%9v@IGY}t23z5j$1>RK5O}D8k2Q3ZR=~!ZLMpsF812a=HryRTeMX@w{B<6 zxjZXRpu_zaZS%#Gc2LjHs-$XfU~qAMT3#G@l^z0`@<+KHrf*(R_&C!seGeV)&o1-c ze%gAP+QH^5eMl>{i#OQVZ0K~}eQn(mDvJScInUE4=TqgKJ2%mC1~zL{=QX4^ua4S9 z_>xfnl*J&H0eyYcj(484-JPd_>ruPOAagtYzj@I<{pg47$3OXg>Sss@T(eeKUxiAX znw)JrJDcs(Pk)^C>a?xhebCk)e4{Nb-%Fe3YYf_rS8Z%^rrjQ2%-R^9l94h<=FF-a zx4NO_^~==njIHz+Z)T0AkTn+PXGdAzDb^`kY%CgYa|^4v*4pIU-N1Aq?PN$DZwrg7 zZFX+CO)uR~eQWK`#6lSbYHiDV6ydy^wzpoix!LLV@ZtS7Gdq{@q)ZLJeRepd3bD|Zg7H^AD%S>{pO;)-?VE8pJ`s+x`8j|1;~T) zH05mNzHomGAFs*?WaA7NdG>nevck~+CKg4N%)@g%z=xxvANd{4$cZ*_wK#d=H?gEhLiT>>5IUX zVZxb3X-jw;9&bDage43OZgY`o7Ut*M^2%zS-EIem{aj!4h5Uktrp#YhoDYxkvOW6j zX?eo9H#03PT;~^y=Hx2=F>quY-FzYRUSM?bvW&L8VPB*Y@3_g6><(O zLW3ykg)9`JkWv<{Dqb&g3x0}h6!7IYuZXcWKR=!JFP8BFT)`e5$YXpNq|gM0NX8wq z#_^F2buX*^>Qw&1;zIR%W8-P&}m*AJmf??n471>o(cbYoHiX5PrSUm(3XVV3mz+PGw@bk_oR*d79MnQ zajx>hE%K$!5h95&fN6K})q!0Z%QK$(8WAV&bWbdyF1L4fsx9U|nTavfn39Qj6S%aQ z_m&W*cxCdGaE{wMyJ_!fyUcHqP8gFIPrZMX^?Z-i4pHd5&Syr*_&*=6*$~FrPaDNCyPvy;Oq~{6^CbNNi{2kvkl+iMxa8t~jb5&#{q>o9^f7s>eoNl1U;gthVYYuA zwPExwcz^>KT*0=U6z^mc20Foj&!|QBAfzGuHD0x5rw?g#%>z6iTs6Dx7f+zKS&;j+0x8`@xch#DDXY{pycvj#4cDX*yHE?zY zd^b89i##({^)9@vNnZI~Ls>UQZF0S(2i>C!Z57J7A}P@;1@F*s_~u!ydHL<$fNLEW za}}PX-@z02jfW71&TX@iVZjU+1>tRId$R*XcTa&C^(zi1&Z%JMH27ACzD?FfB7>YW(f*_ZR$5}5mVtM*Y5XLxrRX=!q-68l}#aR6o^STObkDU6++o|vs}^w6d*AUZ_33+x1@FgvN=r?Ty)#-wBPl&xK0 zR034$AUrURVB!Y`BpCuDaKK1(;|(};CcN+Z!RV=@6n@DoG>LGH+D8djG2M$X>TMJn z@q+OFe7o&$35`>aevJ~i2gd``>8a_!e7eT>G=e`sGOSWI5H##AGd_eju$I8C8_Ni& z-4g+v!K!d2V`ITKFXSO~f-88J2UeJPZNR)@4m;!66{i%Y7&drEdCk z47l=Yt6kKEH@PP?*nH-dIpZBWo*5{OF~jV9gwPT&(^vR`sf0_ESlZVa(#)T{XIHeg z!WDwBK2bElf1VZCVG1sI0pE+s%**f-+-j#6+={U6YyhEE%6ObVN;EK+98NCJb-GUf zMCsb_^_7yGvvY(D?YR_Ta(& zqM`EIF;20CM)ft3;;S3~87_E1*|>w3u%4lB3_@ru#Ul@bqQ%y~TqWpd5w^ov85C*W zLEk;&A;Xi%d0eF^qx?%7c+EIpNFCmxBt(b7g#tx)@1W(WgL1NqNm*kKx7z;xcCD%C zKpl!Z*TH&K}GwlWEG>^Ae)*<{IUWsy$B9upcYoX0q0~vb8Cc1}H_tasK zFqYxjc3-sPqwsctZLNdpyZYLjvvzW%k2}R{P+r}VWiU`eZXW>&GwNF0&sNn7_C&r`cxurICn+G#v+v~t}Hr<{{UuRRcGst?M zosBj=-a~NNSmN9^XOZ==k)6NfDRq%CgLmraXXuQ#<>l4za+JTV9R+7T`S?fe$3Oa; z8;wUVGacH8zfp7Ol25$JWDu|>H}QN|lx(of;~wzf74FBvO^)_eT;Q5hsM?dqbm zF7G4nX3TF^SW!3wR|mYpRn&kbMXq=SXD=d0ylCJ5{ts)1|JwTfwy?O;rY7dv{Ra=* zH^2RzwzhUJ<9(-i8$8MH{Lb&x*-n(?JivGkorEsn_tA**(pg;zuHI~q9zAVan>%US zLGW29Kw;LM0SE6V%Fsd4j#j{NUI&Xy3&l60N4!qWMe~ox3*!jhiebk*Tw0oMb8|Ck zS6~`IGl&T_C!`*}vU~G{j-exIn|wl?GgOrvl|GfhD!dbqJ4Uqmg}Kaywcz4Jd2liQ zl)Mu@j0}hOGER&Uckiy%xIBIOJmnl^KBkPwPohiU<4|Qrn~jZ)&f|wR^1kA2i^e&l z3f;qB+E_3j*#s=Wmhp+V7h|8$boz(qn@jr^=ADTZZZEi8=jPo+bICenqrSP%1_AOS zZ;pHS)&s}c@R_gLM#|HN8yO$;&p0@X?C#o1!3)lTH~v}ZN4&ea#z=%d^Kb%N#=4N0 z)Q7Gd2TwPP7Y09uqow8Lw!E}d@+iI(zP^miqiw=SqR$lO{oL!LVCK!hlHvbm^#PB~ zP^x_Gfx5iFR#sOtCZ}cWxpSw}xRM2GEy(&2y5z6q?yN@?(B+(hno({$z zwB05Q^9Q}GXIXR5Yi##DwS_>;Fukh<& z&xmTH9r>r`Tt2Pi=0UCNc?Oqi<7z&^SLj3Q#&qWRy?gho9ynL$c`{sN-k1;YLqGJB zt%Mh!cEJ&K(rcjQ~{`Hz)qdH3#t$f4xeo5Ln3ATz^*dvgSeREZva4Kc773>=+Pr)(muIA-_;hVnJJtgISl{@-9YM(jiUEW=2&u-`okJQWXX}!IZj7uVMPFQDj9!L8q&Q+&DW#5uEX+nJw6ky#uDpl2u(o6ki_m_N%OV%S zD}tSH3F7)6M}RCNLCU~LPem9M-Vn3Vl{0y{lshAL>o75Op24e>pK`h&*4nwxlw((? zOV}7hu{>SEv=DgILr5AJbPRD1Tf$Y^E}1taxZ3?HgdN3M5BYM@#&6#Vcy82AZiYCE zcro{>JFJ2xjF_RoDhoFQ-gty7VRA5P6c)T&Ucc@JL2wA!u0M-6!&w(6gEFev)1t@=yw#SrvRigxB(-*&bR+Qq3|xxa=9(^R;Z z_NTvPGz=Vzu?|eY-uU=DBNSft5I@H6ErV)Asf7I3jfAd(AtJqr zKLSU6?@AAsxi9ROdfUx6rCho;eqE=3qV&(y@MT8+9k0-!{>}G%`O-AXf0fY7fo4id zct;2iF}zY5cxwI4x1uvyD|rG?DDpPw29{2fyYYzOUP#!tA)CC%6PheNK0Z}>l&b}O zm$2|S1olqvC?C^-f=pg}=gU2t9}nqIneHJZ>3@C@=M; z)|WSoOX%XO_WI&D!uw9~Ij>)aPdPhor^n8mxCqS*KXb=f2B&S~+0(TDs5T$;9kLV) zU8$@eT~UrUcW)(LV8_RY)jrA`9Lud+ymnq@eLif*2R+1;(0br<`SP@A{hhJ7v{hKB z?m^B#hjw>^gilJb(DpYJo`K#CaLF2Xw$q+I`8a*q1Ma$RrLI@6oCE5N7a`mZ3vRsW z-h`*JDGJ{t4u4Z;SsjPh|R6473=fYhE57K8ws2dEQ!Q?ZEdS`1A2kf7%{D zc~WCGpRr;n6W;px@U*;r@Gp1ou7}5;ZXbX2QTxlk_>1IeZLJJ1bLnH}b$Ag{P}W>^ zmR*e_6#_o;y!y}RwZHYWee%(d+w-T7%aHfv$+N0^VSb^EL%e?&w?vK*A`;(@5BbJ7 z-f#cozxbWnSR>K|8RX#LxD@8E^H*M1!EwrdMyeMtc8a%gM(?Ze?~E+>?muWN!IQAO zWi(TEDQa^$%W3`odRtgrta)e?7~a|WBNY4$6SL*%GF=;dDyjv;M9MumVPHN;ox#P- zd3+G1Ekno4mv7qM?m-!`7!eK+Ptx|Y3W?}qw7-8p^4t3l+v>_{dDhtp-$O9=Xbcs( z1HW~4Sw=<%2^*ulyScfU`p+tI0NRAd12+m>JRHNR&4f1HF)H9{MWqlS!@V;2M&6p6 zo3Cl8yvb5 z7%;Z&6}?p^#pcY+Y;66G&oSmrCI3{$hWF8{b};f1VkkTd?ZD6Co2?fNT)cao|K{9DhNIoR{W7XBW-YHQ z6ysSGmSJAPIhf?M%jEJahCYIGTALy3g=uoEW_Z_`x4|0UxX_=BYv$ zC0lv$h&Ha=E_OIoj6hwAXxtuRA-3-N>9Wtfksl zx{S=*zDB1Z)%~uxHxPNfV8S@U@JUIZt`|(*clCEW-0DI9QvZC_*ScLlJhM*ulsxVK z`zs?#{;u-mAN@n|LHYC?F|8c(`aYDUj;glTJ>0K$rrmy5`R?a=^*iNO*(2J857XA( z-qGjiyZ7qKU$v=j)}u=94>t;rMrnAja*Xo()c)Gw9K6Ew;I-hZgwHVt20G@9Hb-HU zQP(`oAi!@4-$jRG^A1D)T=3HS>ZrMqdf|E*-SbC(fll@|_IAR9^56|!>HW~Ycl+24 zntfyH+pEUFHOkiEGyJFKpRsZy3MIH;j*L^)z2bu*{|3=v?7J@n($ikkMF< z+EPXJ_v-c0*LptO&X;%dp>5?gn|X~W zSL;}97Ed1vAcKl-}TpEShuW_0T1N`2%zug|Z|3N98`!0_# zy`fpPsAXlS9c&R!Fb)=1$|1rCp_W3Z?}#}shN^a{n0 z@AvR`6*6&pHf_0KuzI5(;D>2*Q7T}>Dd_yRf~lY+0RIwHz%;GGqzH?HDH=TNxFJ&STKQ#Jd)$x}T;PTMDn? z{%s1vj3J{JgI8WlHc+(K28Ll;UZ>565u!FXcH7xO-$C{3ns^m5^p?>uV*-ZoY}f&2 zOpG@}r8Cir84T=o+Fa;@z=-k7RlA!o@!rkfFozf}&!I`u3(-Oj!+2_TZ!kzQb1~4Q{m8W9<)LBZ5%n=N8?QTsU z;WXugP!p5`yx@9Rn_pvux=z22>DSZnWrF`w$*k=H^e=TGG_IeMiq?%3Nj-a~PyOmo zE8pl|{vZ87HIve}+ISIqL*Yn?`oRYe+v3t(*7}jsDzwDfM=@O?|3X7~UNJynJkH8^ zaGv$e8KR+wDIT30=&CkQx>7oz(b|CiqGdy>`)NyU{&{N zP#4{Jj?WCwaJr2LJA6iVo-NOJ;ETFf}O1;ee8?XC@18cw#x=NTt%Fa7?Y}|3a z6D4E#B0S8ktO$iyxylPC{X0Kw7vYP#Qt7gt9BsF)t!G(V7|$5mdgvN3di^GAWMD$! z%4oQ~vyt`fusI8LVrsU{&M&v=`FpL-u~Jv^j*SZkDGXo6ffrifI6g6*=UFdmTw3bf z3GZ`|`$EPEMQQwvbNc%#JmbM;csb{91x6Wb_XDNCKI_q)jC6|Oai)!T*B`W7xpp#;4Ms@$jzNaUueOb@FvPJlIQ_`&C!Ro8Um;X}&nm z?1z8zr)_)dY2g6gd1h`tu)1B|Rok1-+w??_qHz26cw1e)+t%0bwUxW~+tTW9x7D?8 zAApRCT$JBnYG^evFJmczc&iA_~y-V z@QlIZG`!{G_LqPDXYI33KPlr0BZ-jU@|6)KZDtt2PaW*-m%+LWQR4?k$LX|wQb zJkcoDoeR=&p5bPu<|kaBuxD_>a!gN;ryuj>4S09$UdHEEd;H{i+uYi!`4(2M6!VM* z&OHVXES-g4la1fDRS={>Q5cP=bSt2g!VM@bNJ;0Y5mFo5Kw3$WmJ;bkIz~&kq=Nw? zMvl=jHhB4c-e-Tqwe5SIah!`Pn*%d5z7N7FM9Ik^I}7IK{3K){&u|lNv%)#$NZAnBr%4TrBF|xkY=$nuDrZFDSl{y-I3dtwlOJZ`?0sk$f_0w zQC2f~R1vMIax=&M{=m(Hl<2$oU@^@sI9rHEy_a}?UWNqmBxzYkX++s4j>jD;K(B<> zIT$TVX{6pJ@tSSQ=Q5{Jupb+@7-iHYdA>0nVF#ip;NiffMWnF%ZQGHeF5|%vnGrq+ z8O>iKumjt{^xA)srbpT>(ZA&|KRoTfp$~ey2U3k1JC9>_LuU@2SI1K=$+I%+Xw9EP zWFe2cf7lkM084*sP29Z!JeiD1%AIjZZ}Vm$&nam5O;$U4k+uqRMT7T1gmSo}LRws> ztB+5yo!vQvkr3RCc-P4xGWYgZcK1gtG?OY#NI{Gez-VjVnk9JwXD$n*f=2ppi!fg z$iS%Z*PPKU!YzrZ!7%T)Hx=T2c`>zp9B0JLUB3y}s&cWNUikrx4tDR8DQ5WIjMe+p z6ev6S8|!0P5<{;kKb`G%hM(K@*K69J0*~FE+6PvYaob*_c7Ptt;6f4ifLI_4+#;W_ ziv_@G)S=_$;nN7ReYbci$;B_R1Fk4oP5BlvmR)I8+G_PAv%?5b4}XLKFA zx0*e!`>FQi>w<}#8HT#~u(?&Ba$?`bQ^qKiI#hPE#$vM#TJ&B_Hti{Sv+w{P&c>~q<5|O8yE=l&TN%_8G zZc`XWiw-5yTpFT$PeIHxt2R0;^LFW>T3}K*)bbOtWU^(w&2+3~c7GSB*uH%dm(*6Y z=T{k6@zwhi=)75bcFQHhkaNLh37@%COwXD4I#JzM%%)73CDpO3@_Zd`piy9!_?+=s z4?%68tBQu|$QYebO zI+QTZP)(gf&N)T2Si4%-Xa}_Fck+n|CchwtGLn7}3-Wuo^7P`KoA32M@u>Lc3P!_x z{|VRyld~@_8>UtuI@){{F(}y}Zj$%w#RTh_J_^{VR(wN*3INgaN$?E+?>>n|^GiN= zfJj}AhvFG5<*tZeO9U+dMP*Tx!Y~32RYku(h?VP{G9trH@xZ=7d>F0MJ%{DJl`X@h z?aO+GOB$@c`3vk8ACjHt37s&+VlC{w$!s}(+UIFm@=x;#KLhd}X)m?nx211YR!mlE z;p?8mh=-DSlf{Akp&~h%?vuJ3o0K#I?RW#HM5Y)eMS=C4aqV;Rjdp_0_2hLb*)Kl z_lWB6XUBr_qCIFQ|NeDOPx~R9pHt({%mUUJ85Ig$YMjjY>d%6dQwRbYQ(KBn_Avy7fzLg`uYQQ@hq!d7h$I-J{RMHE+D4yk+D~Z&_6rLN8s>T zxp|#TC!U_aBSzS@eU;1e!obNJU!(AaD&vu~MRr3sapd&;pbvXd)0dxtF%L4b_O7ud ztavwo+(A>wZq^H5aIV`hRl9_PaIj7#a)QI2Xklt*tO@_&bKk6?{~fbS>NiE z5*tO1tnQBNl*NeZ2)Zs!^6K0H5qvYe`M@RYP3|_(~~4sL->h;o-5X0(kW`1$ek~q7*nyix4LZNvf?!sr4XI3TWlaEYa7`~_u>T1l`=jHK3$6jW6K&jCxctLw^cisW z(6v=-q~b~8eg^OD`E(XujyIT`8$9$Mn4*Kw9I~9oY?LM>0DQaZYJjfY$igOFR0}P%1Pl4fL2~tDO{~Kbv&oMO@R|h?toj?4mw7ukV!%-HeCVJNt>=APx? z&iLHnlV3v9+V*8aqRA63zHSBVPeqXeY$;-2WIOW@{|-W#nC!T+^yMY)v50;gP~UeD zI-Ff1Ec0TWFkBgA*>4?$gtGS&!mclR?D)O0zyj1!K~lG z2lm>Eys+F_bf5#Gc0J(TTQOum)9FSkwOEvK15;D``etWu+u3|ZUiIgph=wUMt#Hl5 zXEHL%WIwA!*arRVcbFFLl6x4&H8}la=eDIfi@lruV)X=QYsA-*S)%H26^-rjlT+HyIeR-{X%5N*X z)u-}ot6ayMlZB#s$uC+3m(~-?uAio_O}-dsJnQHU^r@`yf0}(uoWKmvGxI2+AYsY% z^A9F+Jtt`UZ|oQhmiFG(8rL>Lg9lGqtEY(gkHv>;B`X1#wshsp{8GS)$u{VycBsH; z?9+UyGStPDA{>|JZ;@h_tGJ{_#38=7;MPh_mD^xr*%x~F48p|Gw}%78sPmZFZSHHP z$4nC8&TJnYx`STYOA6R}op9?+WFW0FDaU^=h@Ah^-2Of+oYfk;EEZQLyxq+dJn&O= zLKXZ)K_H`rTwgq~grA4<5`A$u)~i~Q0eBfGLE}{& zmmVO#nUl-Cu|IQZ5m*Sr83Cq815Pv{g@e>I_vFkX4IE<7-;~Y}`r+QF!E%3M31X3> z_D`V?Eo_26oyYaV*}UY13!*d@VQT-Ha@{9mHasXfC_G}zcd%-a-JaH+k)63U(GTA; z-Miq^j@-O+xq$PFcwT!sR5^HZ_bl+A%UjFi;S>9@tDH%u>5Hg}K-#S+JTXdyZTbJi z4yWdq;xmiaqkhPSz{`e6r{&f+jpg4QA#M}Db;WNP*MifG87ZEp(#ZCTkxAH+9x5>t z5`1A`UFznr9kMqPRF=YJkOmxHru=RRbCMW~Zz-dG{3i+rBG=ZWUcpj5v!2{K`<*`{ ziOPVa@0T{IIA2qv#x61C=(}Iy>WdOOOG!%--oH%{zY~uFAuRD;)YPg1kCm~D@>Ni= zF59pcjhA)08@T$rFHac2gEHUR(2&l}r_W@Gsf@9Yhuf56#ovX_9O-i#+#|MN`INE= z)E3FHMm>yXjFU@rpnBO?@BnzORnKbp8;yGpyWC^ckkd4lsCm_wk4`&{!{f8>O%}#w z#_L@Eb+8tC8XfQ1%@LG;DChu7ee+XaRkbux!B;XE7&e_C?IA+OkF)*Q>mHY~F+VzE zF%PSsx0qZdlI7d1+@Z6z2=9j7xli`PL!bJi$4_RF3?seqd@C@I%x%l%&%fh0M!|H# zo2@n$Ue@#)kOyQLM%H1yg9}{e!3XKf!54RpC|XHh&XI@?IcC^J@8W60XKL^%r@Ceg zR)D(W&eZuFib{SNepwXnbNyPIZETr-iUj!H;4Hu@Qf>oBVd61$Y2~)2pJvV%*%9Ad z8}wOYyl~vpP`xhx7ti`u!y$jL`os?)Z9}gsT{N^=kMi>Yf0lg;gYIzL!dUx`cji^l zq+*S3L|U{Du{&QoB_M!3+eKv^>s_&TQRyh??^6ojXjyW*-ni*6%o!Rbf3IV08-H{> z{eyQn8`UlqHU%(u^mJtWC`j$c)+ltpG{E>I$^YW0c~zk8iF8ax2HRUdXVt;X3eEVv)X_EdL)#hb%qPH2YbKn zb0waLrf1@oJteU=)b~HpF9lWB?BI{rxCn9dU(xJJQSPW8e5+GCMt#`hq6l$>yh!Lc z>_;@PN;PvDpm5VyMWbi*W^C|la=B&f#Wnsu3Dt-&#Ra-rX7*T8HX*{0|LU&&|TPvq8$b)7|>Vd&79mr5)ErX6FWtoNgK(UQ;fCu>Yt$-8wv zdeu*A(@J;ib4YEJnBe&AEXfOaokCtoXDO=7iVV)%=>9Pt>u?X;nY?Mom|B>)pK-uS zDdJ_M>VEvr8kn|DN~%Gu-~lg8+TDF}P2EGhk+f&h$ODG4oJn6;)l!CX_YSr*#J%=x z@mf3VS;l}nSD%K|ZqQnu zelV}WNaZq(#W&5)pJU+FHl0tT%|;XVhvAfa(GQ#A#sA7^7sN>I0=h>=u&28hs`JQg zG6oQK;#Nk`qaWAd)OIxw@vL|S3Ecx39`~=Wf|FNu0P11ZjC=3f59ar6?0tSKJ#?1l zNvZm3YHDiF_43`4bFM9tB1?`MLMi?nsd>vC%(z#$aASt?)#B~ZR8Pe&9xm|1{Th5r z#vZbW6J!@2ABksCNjrl0ZB493ptqr}3xMV0oHZ>fv%LiQ$OsN%Jj0zvXWR9G*1g}# z|K^phB~Cjj(gkBO_d7f|gp=R2>->Erp}@w+ql_Hja)@ETFhpwBWo$%juDRm>3^Pd-j^Mc;2TFMkB#}9dh%Y|>g9zXyDS3e%TR^g}1 zD$VV>p7dPjP@rM|2^CL1e(ymG=a;8=DI-cA-HPG?2SZ1?CkjiEH=riJ{@%O5i^;gL zPMf#WV>e^39v;V+s1NHUrU3a))M#nJXS1xEp)O15nUf|;HP|T=bUwm&N(TP}>apbB z=zgSDM-(W`Gs>)gdxcv+mD@C5Ke2ehpUpoh^K$^TQ@g~eSE$npZ#B=w8Kg+9WpW1| zJ~UT{@R~GO*umF-n*s+4G6q-N9X%9Uk@Gi%%J1pKMFadoTzh5(@|3EA8$Ka9`>kzr zv1MyR{suK>IhDLKWqs_YWtia7J$sWXwCuKnC zPW-hqFa>42{+A;>4=Shf`im9Mf1~MyJ?m?Hg`JTw!6`el%6D#Y7;4_Zv)kaCTu;v; zcFCxg${a3;6><;{O#OwF|8X^!1cN+6?~L!Mv`}`-*u@K}O2b9ldIKSJ$|@!W!}smN z65jq>Wta)g`p=qx(=&n;6t8B|N7wRK~Z$>^0JU13fp&bjL3%(Vm$I1HX z)`El%LF$xL!pW*l!-}eg-;9KgB)ZMqHJ@vcvnQxoc)NGJLi=dhp%=xbz#KZp#Y(9B zl#uAMXImBZo5uCHMbIo5ho`7KM9AGfDt^;rwso}GqJuphJzn!p!bz=*+)miv{t1({ zO1hmgkvG5UG)7a)b%d3spRSmk6)@?d6Vhch>QqETxNa*9nlmxfRDfJN{tuiv{%2gxf>t^dT~qvXGgs2?5awJl zXf?d;(?(mVd?9a+xNBedEoyo&J?9$Ihp%mDK*h$!z2cPI+ZEy_?{k5JPa+R^2aK7$~XNl=bx&Qw26kH8fEUOd5z5nPA za&s_eap#1cV^5dSPQ=nm z{T&^u|2f(;-4Vg?Y@a?$bl<&F2f4l#uno=%kSQJd$ix9euF*$KY9 za?|B<)h(H4Gk*_1rkhx}H}odg?7f602k)r%+KPk39<_?PTV&VIZm0#h>=V`+A5)3N zE{B9g?vjam@qzrkk_l2?nHbsbZ{qaT9wJ`rzMYBU-VRc$>}-CE8RK8cFJ-sr@-Iv4 zo9fJMSI)5M@DMXPIK&X>CjLnG_{d?+$L~|)^woMhA?1HzktLTgX{j6HB)*n7ZF#K~ zwzqowVhb2I&v|u_U3-mRx~hU79~1`RM^;RHPh+v}>cXs{c(tMn?NRX(^VC|ubG)nat_0yvT6e8v) zrP3p!U$_f~^Y<35L>Ta2apW?@u5QM z7k{)VwcO~^3O@$$G6Xo|2}Zn9q__BGpu!mp1OVlpnc-O3MvhojA`A@;1wXJa&NwKk zK346e^!bvtZiCP-&`5VVGTaP5*tY<9+zGrPxs$IxB;iccC{kD77(LT-l?{oGxap}b znwNO>FwZN?M%AO+CovuOsQIf;!WQxZy#SYckmvedoBwKJ>f8N{YwnnplOVohg3s`z z3enRDdVv3g%W<2O#-r=3e~AHhe9kmnihz{NOyclK$g%<*Pp@FsQxkGZU-`T&EsMVR zyAZ+dHzzWFG@O>b>fQnu{YE|tQvcEx(o+ulZyxe^!eKKxUE;QbZF03{td$uH(XH}DLP?%UoJ`G^>{amOu<9<2M>sb`zav`cxlw~S+uETq7MG@D;m&of$jZ#(8jK7w^|vU% zgf)bBQw;V=yTDOlyN^VGSy9cxP6o&N<5g>@q?A=Mp)8}hf5KZ({!`?I7N>oz$@Ow1 zM1j}U6;lTr6eQ@pB+)!UQ|{sO%5&S$)Bf2vXm{~VbE&}Zs>DF1tMAg=iw_Za_`6Zs zmaAAg@KO!f`Z*?7uBST|)3rgxGMxrBvd6418hK#DEwZgliPP;*E_OgCjdWr@qJBG_ zUo7}!+qXytH^z`><$U3M(dSOv7irnOJ3XPH+}$0Y&;ESyTP3%I%e3Ud#tYptxIz=pSkBevxQ=}=ZE^fL zL_TUo2hKOVbJ`2B9^&liU!=8dw-~#>Tu^H&;k(WDueP|!YN>MHzEk7sEV^&Z0Y5Cl zf=+AZ19J60e-Q8Bf!X{~e>*lORvkd$64JTq7!e@nt6?^14S%$gw6NKUvZL<%Z{oM9C zZI2ogYn-I-hSHno7r|*Z!ie1ce#(tH-2TyU=N+%1nq>q2l<(wh&JmzJXg0$bj6|{= zv1alEhhnuUYfCTOZ-{QVsHnIvr{9Je^GWrq7$`pY&UsI^QY2uKVeb|3LBY)}St*l4 zr6SfQ6tmggVxs%Nn+D5#PP6##Y{qc@W)790h?H)>h|&9DT*yZmCY=XUb}xq~I&t&x zeAF5MnMeK1xO4d|qry>XO#NTtU~61k;_tFOKb5_M3G0J<>*7h(&lzL3K|7S4df;%2 z0}*D{Y)aAbq#edA-ac}tYZb>;ZwSSRaM_1eIqGp2)rhpFBwv>m3)XZqC;ggIkeizT zVO*u0==UsiDECW2QGI+*#mUgUk2Azu!uyaDz0J~qin&HH2!Dzi9mimkUQHAoa&GF= zOiaz`?pDI~*g}`hphE`(rGS`C28GUhc)PIc^N`djX|5^%MD2OPWX!u;^a`85x;J`9 z+OixsN{2#DcPDg^z-+kLs@m=LMnv*eA$!g>6H}iG4hY;x{}wap6_s;_n2e=jpPgB9 zi4vrnUn6|vkL8!%JvhoM zeVTJs&~`LZf3iF2`{TFofg8VqWa9^dJMtKx|IMOHjH6+oWAeg~SB<=!Kq~ z{Dy1puWJF@kMXQ%2q{de*sWV_-N0InnE;8e12=lpL?3jvX3geRql=+04@JC^=a_95 z*HBY6KNLpupQ$E=V5on`#Pne&$2jWL;uJJ4&-C3(56*Ym@fMd?me(rVGDGL#qOG8W zsh#?x6_ZQU5-|=7UAnaJ0GDL4?KKc*C*}uoW%1QsfI>mvH$|@jhsxL^W7*4?1{i{$opa`H7M(G3GC8(M#1>ixKYjd^U#648zSZ>P87(Z@!fw~vpL zV&0tF<5Km{YcFp+6Tdd%NI&T+pk^Q4r}PTgwiKLgPG%*u8M&AqV-&9e7?r)><>ACH z2gk_r{63hxO6jz2@Tr-o_ zU4PF%EYanxulGY1W``Rst(y4p+D^wzBMv)n1*9v2164yPe`j5=tZBD>_4V^9AA}yP zs6Yvu@4~z^6DBR5r!i<8-(#g_u6V4GH+&QOzfL)0elhN5FJ>d@a4bpM4GbsSkMuG$ z0WeBpMvv}4dM`6jJaBNxbu%_LlCj6ZLS2v2?QDGO7Vlo&r6(dxrMQJ?`qxD>@eVw8 zaGEpcbDB{zJl-Q~@}Sm9H#DT&x6xIBN2k0@$Vlb`nMb&~>T~Ne=Bs7ZOj#|mdu9D& zfBa%gytMyi<^7#%S;#{wdXr??N-M{yo&88Y6a|b zJG(KOE-w%dgu9?fw^;kfYnCa(c29EWJ%FoWo}c0}v}2z~j66JILO9<{VGjKarxkOP z^iNA4lde}PbbX>V9|Om%6-EA_+Sc-X!K6X7I{8r_ATAZvyVbgi6cr)%n&7ZG6)|KHB?sr+kXB3^?_-XGt=@ zHo9mXZvOiWM-38CPK92ehS*W8#AoSE-pzQ0T5;S=Q|iE^du#cIxow1RKaY7*_E_o8 z(ADv6LW%8`i^%chO|Vwp>_})X5kJAh8Vts)sB~qgspY=1B#StJ)j9Pd1_%-b`;@3B zArjTW%599TR$QwW(xI3_-ii0e8GGTLoFjU4Y!ePJbDVyqQOPx&vr}t(3GX$)>Ql)g z*HJO{uaxvuAxTldwB#3jE6mV;!zIZ)4OS3+J9{KYn@N@((lG3|l(O&fBhL5V%^STc zsF79n5+KSeT`}0wT=G1ds3UxF9-}dRy>py@vzN7E zl=*)*hSsDpX)*39>c)Imgw0t1509!gTU?rXDI9*uL91Ua>vZYQDuwHGMKd_={;f-% zmH1A6VGzX@M;*zh&JOttl!GgiP&ZL`3@e(~EfA;b}v{dRFEv=)N9KuD&sDe3q`&NeM zK0AGCM378ahTY~X;JyHGZ^I*_2n>e;q$*+ezgBhA(_8mzn*!hMkN^1cdHI`H&hvXv zL~CfwZ^?IH<>1f06eeA_g5QgB^X!wqSN+UQD?g`;r^oZ3`G1L>xRVk{N~4sh6Z{18 z{$Gz(o*Y?!D;Dc(*Oz^zySCo7dGcyfQEZS|;J)0pT%}l6W?g^(GZNJ*=3i4hY!tby zJu5RuSl@t!7(n|31$CF1rRv-XN(9!Z@%4?#ZC~?S4>?LC{a(mYhtHB2HLjAG$tilO znn}Ak6j2uJN6~{a$j}{6qa(~w%qrn;gB36w6|=BmoF1Y;d$q5_Axn3;dAYMH!MKPO zY^n*oPw*N|j<1)UmJ8QFyhzfxCl<%m2|*J~kjcKNUu!g1d0Bdo3zvFI3Ideeuq>KR zzFS+OA;MvNbV`sBKR&OtE9#b0SVVWIA(_3mGP|$Fm|7|m#?i+ASEglFV%G-pXy+A? zB>(?k86cxS`%!xGN(^`<30TeIIZUw3+dUQ+a3MSDAtcZYS1+ei1@M9sjyyv$2? zJV|ynCoPdT#{*)>u?2~JB(5!^Oxmj4&YxQzwaL-VWUmCeGl1{A)%k!rFoz4&#ag7H z)b57j&|zh&RxQIM%#Q!J$r^?-Nw@587H|C_cjR+A*|lQkxSp>4;K)KT?(2CTZuFJB zz}?ta5Nb3(bNBu`#$SJ%YFcCIwr?g{KZTXHcqaT-;VaM7`=~uE;U@f~&-gs)tCW0_ z0%>xcIGR@UmXE|8;~{_}UiC+ML-TK8dKb~LGuBEz^rl-r`+3zV2Eo3k0Gdx1#pB~I zw_T+9IQo#gn%e{SM1(}@!k$`aDvgcgn^_mu*o5MKWwc6eAu5aYBwCy0MBU4qntEzM z0%yD|rpTTxPrRhw!iGs{l|T3yKLK;#J2RJCE9(N<57xs!uPUbRdGkwlwFczxTTDUn zQcB$P~rR=*|n$(g?2fu!G4VRz4uJ>W+N&` zuhG=L9$+B^TKf_gNKnJlT`$wk2VPVLj$fhLFI!JH0> zeCusQC!Jhe^hO=B{H0aZTfDtZ|08b2!-%?5R*q8{ogw;}E8q zH*D+8rN(F3u5WVS;3H-1NXhfnH-i)h=%=G=1~TeMMq0=yf8ELaU}VkQP+uQ1Z9j^J!)Mb*CaQp$#CIi&#C?y8oon1=KR$jT<8gW^?WULMCsJXB`nxx*8MK)C(Q z=qMdx>Har(ZjCSn%p6wuQ^h6pEu^NV3K%DN?Z+a!8~=3Emf!7*>0sd;WTj%uP;RY7 ze5htu);b7u#AKQVVa?Lh1{SolGxNjGp3hhffg@&7+AW>WRmc|CMr7+CRZ#C3pdB8g z9nQpIa~LeB(x{;)+N9YiTpgzsW%tIKYDDLVp2kGW6cEDqukKB-es7HU^jyN-{^+&m zFoM-#;MJO%ww`4;nPvC-^aeNSzVyM!gfi))}!tVeMfoT-w91rt+s!vJH6JJJZ?lLoZGl7>kCTsqa~ zT%GBq+OWUG-t^ANh9L}c`k=Lz{hU+~5wY1J(9#vTHmdGy~i5k7T z_}BM_HL>s=?ldRxVC)PXAll9`g|j%_*ghC*#iMYS7S)2?-k3muK%Kmg>Be%xtBePm zgr0$6L9ks-VUr2kAf$aWU}C;j-(YjaX}=)a6e#tdd2&Pwq{C~r6-l4jE>`dA zQ&O<9k&}DfZ}*$NK2}rP&z0Z8jkhbzoX8i)0pVJAW(Q5yPj>^FQcA6)^RCPlWtZl! z39Jt@kEH^Wj@&Yh&bCKeL=Emt=9muxhb68z)4pMQPJ}>!wxLBd>hiB;pZsaeLZ2Ehc3=0);<#rS zkIeeNTgv%2K(mdFglbjG{BQA+iMUi++5OOqT&q4;tN+AbDnQ<5=8Hrn)l~g)^%WCS)=l~d3#rrz3J-J0Co2w^LBvgv-Dmpm6@p!%3V+T&CMuI*`AbfBqLjb) z=x>0??odMqt9bq@jZS`jJ?ocdpQFRsq6WZ#5O_~PEVu51`(i#R#X5ofmqY!@e!{!U z|8Xg{%V-%SUYh@l+X6E4$XG4hGa zye>Y!h#)tzPilAsCVzHlD@Il+^}35K=ppyR-R+lTJeCM|BOt)(Z)#*5`@H{SL2U}|HAM#{*nFOaKquIs(NKNH)XmvTP` zV+6c~{ghw(>)tPKNldSi`5r(c(!}0m0p0l9R?MLzJTBB$i6rO2-i=d(@VKx4G3RAM zwpfR0F#5->1`$Wb zHxP}kZjLB;NBesTg&L?sWywLN0?xZRlX#WG44WsDyk}s~PrnCod*6$(Jui{at3O$Q zlW_n+?*~no`1vMeTv(gCUFvZKvt&CiOD38osEf$Nloy?{jKj>47d`nBRSQ|h>HshM z%) z_ODrV6k~5z&GMzBno`3@3tZvvF7>h$mPBl6Z6g9UD}97^)DQV8S-*8b*(k{CGdHAG zk4I#c&RhMPIKhf^?w{yWv+_nKJ0yR?ATt@jP#x$AUPxM``BN=5cy$X0P9Fp(R+~aQ z+Lh=qt0PV=dGtEOO@9`)E{?1%aD&3lur{-9>nlaq?11Ck`h#7k^n270#KH}J)1ZvVQ#aW(T zC~zNi==OKNYIpR$nj75KLo&YV*NvBwa9tiEI83d`zlo=A=od61m|$2NCFJ%4J{J~t zzC_TwwKH|Tvqa0lpz*uq0@DJ0%Mc?`yJa3tQx7i|_G?!97W5q&;soF*wZ z+3%8W+5(szS*|-83I5PTu3*(qAIfX*Em1%n6`c_kZ#zM^8cd7!46DuUUvKI)?sYV> zC`k)(oL_!Z*VrFb5(hol+akG$RO43G0IBvvsbAGGFk}vT)pjwzN6arcl^08qS^@|n zqn63H<94aDe&sKeN_HAbWJwjNoc7bBE=@8 z9fI@y(BEIAsfdt6Sd2k&)BCX1!$slu6i?n|TEVqW{yCe^y!8&Li+!rJy^>^-c$#J;U$iZV2WEV1((MtOFp*g6-YnM%S|m&~6Y+d3|dO+h7^@e0ktu8!YCp zqEC8&1<~?!m$P&vFY^Dg6E)8nFsH3JSZR6tS=DIoFUJk1AaoHsfcXxf#>3>T#zaCk zv-se}eY=E0<{+WhJ;=3&s?XiOv?z4uIteyi%{k=VkEhgua}?Ipmh0^I$%>fA#T4Ov zmFylj{nA8RWL+QBmj?MR{NHa6NvVIo`-V!ofO%%1r_0Wq4yuk)(ab@cGQ$t<%B#+f z>cY!1U${R;d}+5(ht~PnH@h$EMSozvMa|%lW42Z^KD);m?H@XFAm(994Y;5+4E2qq zT(od9Y$?u~8u`LoOJaL_&PJD_I#n(@=+!;5(2u>VWZkvBW+l|adHdxP^p}T18y~s05raia3_P($h(&XHPZW}NK3-zE!%h=J8AR^b}TLUvj z&h|eMG|$qsZI<3oM``O9kLldnkYPIf{)wXaTp=GO$xH(2!MtB+$o4SAhj7zJw$y5t zf)O9&Ee31aC0HJs9Qi+QIP7x1xR=)sHQsGQqc52WbTLicq04c^Y|bJyK|yZL8avG&7G z-PVmbW%{wnlzT^jU=db81#gkLM_drKxTE-K$53I(?DQMBFDD;NNr{9n{%bMe+zVZ# zde>l_z5ejg;v4yfz5Y6@ zF&MWB_)J0spLs=2c(;LlLd?@72g+qjv9s?M(&)JGd>@~f$u@G@Kri}Ub}qr%v3t7? zsNEbwN14*=lnq1hl&SW>dw{hen6{iBM@@B?0>9>!K!wXb8zgd;%8b)gey3OhF zc>S}aS@TPlO2vx=MW<`L<#j}Tjn^Dz!)P9fy2S1wiHBuBGJX_SrFl^efgtv+asZRZ zg~8+~uHW|;@?_c!mLQ8|6&3Yo917HxkIPmq0FR^P%|b+#Hr@x|aJZyd<~CME0mL#A zi8_oFFAQZ`$J%k|_k!F&NkKp5GPPspqhexi2Gmm&Py%D0a>#)Wg_9L&6486ExG9MB zo;@llHo2Y8i@@FQplp&i>QEtM+#c3V4%GJabqGTdU-ky(dW^{3K9ps z;AIwpm?j1B%jt|XMbnVn*YR2XN+-bc4h-CwP5PyHHed#p^bWI`fIZhUe}q2y^LkF+ zC8J&Q*|wYoCII<$R!|f%WE8aI+~S9Gd-$15g7ItC8{faD5_@^kZhR{bhXlRb&tG6) zUpN2FyklbNo*eWRzW%UB|2K zd%8w$7g&ZGSTGep{Nz#{8+UZEp_}ht9*7$5t=r!&eqb&|yRVzgtch+2;F~Yhg4qGE zBz{N948cK_5vOCXQfVctBp%a+H!rr;ilq3V#K&mqXph=PSk6y5(0}go4s=mhQ7_EP z%HEs^rf;W2EQ5$vo433r6w;i%-Mu>%Efg7#nJ@-O&8EtCz3RW1q?7Swixn9-_{?>H z39GpnIo&rrOzV#1fcw(6-xUp6qJ$FceTi$5=kesc`;vZ^|HKEZV8|P{k8ve?gQ{Z_ zJC|mIHCF+g-7AtMbcwlQZt2>BS+qD(PiAA<%t%HY zA9!4YUmW7>++|N~^w<0BoS>g}MTt?6KdOkknm_aRJ8ly?d5LG;2B6AHtJm7KO+iKX zD<0BxOj;zy&mnk9b9s^P_oX7na~A?3|C}ClGk3p$aAF0NjYTdtF`=P#F54jQ{H zP)PCRtQ!YAFE}tF^GI;o9QJ1~0PgIySXRbPDSy(|eE4g?ydCeAGjeUHe$}wL-!oe& z&}zEK1P?r8*=xVNpo?EDKf?JFC2mBA3;RmT#DFxvHa__Km+hO6&CUJ~9iD%2vVMwM zy2z9Q+z`H^3ndX^WQ+&))Pr4b=;hlPk%d(3nfw4iq4RB*@`$*BV4I-9VB;uIo9v&3 zSUDxZ?*4S445hq>HL+rL;(3hL!=4pAVA442+kZ0hs@4=M_CFyS?9T$`RO)VJD;}AwXwp)fxo*O~&`X>DsJyh^+oZ&+q;Y+LREy1Yj!tvR8sCfe z74x&b>(DMK&%ih)g8cWMPW0C<63!mfHL4B2qej(oc<=3M4=lf;<9Ka1k2GN2+F6X) zfMuiclH%Jg5z!NhGBZ*QO}uLn@^h+t$%?U7nwoRnT!A8u`FVKsxAhKZ z#P-iyLSZoyhi#q{MuWF~#LRph>X*o)oV~>FqrOp$+TW84{1;2tEyhk2cRt2nCcMSdvwJ5 z`EtRy-r&hTg9yA>1;&bLKjUbkl>Ex&T1Cw@7vNo!R zdHg%qA5MOq5x~YK%ati6Z-Ui6ZC>WJ{n12bt`4TS>Nv9waHh*4l^gt=gnM}Pr0RZv zs^VJTion!@Xqcz7NYL|(VZb00$AcGfAyEjW${X3~VV)&Vw^8AMJk8Q|#q765;uT#g zePrc#i7_?H?VX>-Z`8^xXFle{?e6+vhTnr})q8LLDfpV7f%4^ak}) zm;suVZWhL`DN$)t4E`~SR)1Q+CZHxr zO9YZ6-Bh|92ZvW&IqOql1K~GyhwO;#n%l+sqE6ZZ6%tmw#p2BC{B;;%Was>${7p@cwN%sl{Q`Fn9)LXVXaj%jK< zDF$kaar2v&^$mX}URaTAvHij{cSz=-JJOh!uh9xlXgOa)&mP00z53_-omlo1mhoto zWoL+g^U_Fp)ZOg$fk$@Ka`Iq-poJSra~__Eht%v@naK%Z?&>n~>w9bbX0I0@=&(}H z>6Py0pyu(ko6O9PY5XJSq1}Or)Y(|gcAsEjH|b)RrvF7b3F9H7pUJEd=@^F9ci%Mt6SUS~row1@!sCa(fd$%K+0uGfb8d(>tlWg2Bi|X* zF4ylE+jhib=8{6UsqPiD(!{}nBOTR)v(yJZ&q|+jW^7a52)_;-U~wgn3vVXAZuAd% zJy0~>tF}lWhH|SPN$#)SGJQjQ=Jm3Q2&KY(;Ck&9q44hcu+@S)p4~RT$rXKI%l^GN zp;YNMX;4OYeaG`boT222zJ-MgvaEG(lh8;Y)uIuoyKvDVGh02ZQt8HuVN zmO9S=sNbFTZ&!WGm|p#H**cg@p}F=s(%Vd*By#9u6d)R2{XY5-X=>^q0WYpLw=?09 zFldYVyNb7TbIFJMD^WkW`?8m>SnF3lndt0DJOwWg&*1W&DSOsT2qdm9Pt-;gbY@l= z4O2B+4RDK}ig`3BBby;*$nw>W%*@xHRN6W(=L#e(oh1$wTc0!Dc!S@vDyb1UCx5c7 zSI2D1=i1Yub-|)}Klc6CeS@JvekuY!y}+Vxj z5la2^2M*V{7pkNIW#yZX>a;{!-WK@j0{vp~W?lM+X4ze3ta4H=OJ5>ekXy)c+0Fc~ zr9a9BvadSVeQqBGUEeIKPe-Zc&qpGM62O;#wpYr~jV%`k>03!!=BC~gFF{H}sof#S zUG()SH;(RQhs0^A#lOoE@Pz3%x(TO&(;Mfz*s_vp*HU#@Sf(IktBAbp&oXx$iPn}d zm)X@9yIjV`IXi0Kz^ZCwIgKcF>Ojt*NSsGN>Ic%Mj%uXHR_?x=%I{Y%_bktVMg1cr z3cJtNTAu%~Ju_P>#O(3@Mk+aKC;ss@1%-Up%#by5%VuSIOvU9V1vq-}n0^b~n%=ZotEbZ#qHJ9(0} z!Z5jla#~k|YiBMGw`2G9@a51VA?$9+oAaMM_b|O#w^)B%DDRs0p*2X8ZiU+4aJ41v%@zrjG4O!i5~zFwq@?A{w@JIY8HnQe9U{+b zJLy;6`7cFt>cZ&*@AvKs;Y6!e3(c7?gti+6BWvRC0UyskAL3HE^*oaA4_NGd#UEEH zKs>c&kKPBFHhlJl!?v3!3)BcMM-2$d2$8@ah<#+Nf9ebLxix8O1wxOO>*wrAJry zp=QPVr&zUap2+Htou3XF{i=g*r|0K6W0rKrb_2-1>oz<|ZB&<0+J9ury#(9m2}?Sm z)N*7C#HkM_8!2wA>1a_3<_qR;_x(U#YeQfOMu4=aPgxNv9Gy|n6pz$AL6nCJ zQ&2c4XF%^d(zIb5oM)(ti=)LZAFZ41tv{EVDS{XfqLe27XW#N%%E9i%JKM@W21?jz zvpj(7c?^-YwS)B>{;-rQLd%caDRDA_37SO8)Z7v0lK~o|mip(w7G$^zhIVpbI~+LB zb<(A>kCYoTu(6&3Tg$6K2|=qAuIG=PJ2UWq#}1jyWf&d?2|7EDwW`7cnSS}`h{k0e zzEvD@2>V$%2^n78;DW?<^0R9Jx=K&|odTW&j0G*VvEUubG)5858@kc9r!5^aLo%5u zyaQJ_?D9(Ar_PDAB9y16Ix37VxV(~3;mj~?nJ=1#-prwT;uZJpZ(qyGuT}?z^p91r zR4QGr>uN4d^`4Yn+YPtDByOgr^p_Dq`ZZ>ThA!&m*nS9N#IG*xS*0o`VeG%^i;#AH zXM<|xMU(?-|;xdA-bCw1MRNDQ0 zT060L>Em&w0ggCY9u;ozz-|x*FLU9y+GGZH=)OkZI$yiqZgr>RZ7)X0obMLLE#ud< z`7^UPe*WV;ef+wnaW2$lT$@xgTp=ypT|N_W1~(tE{bTXc|9H~@769r239RwT`=1t| z4mpxIzgU^VvZ9J?>U#w}d2A&p$wdtzolmRTaM>9n@F$p5lfOdT2C(;qF+Y^nj3Rvc ztNRr4RsiwxxKnN5$>eL5M=JGqS_p~4qF9X3dL@TK5CI&DAiwRu{^z|UhwM7)^>-NY zJ(3u(3BIk_CR8vzEF|?-4UiX@{vL-q)FEbReXB0#(&-?}^ikLI5>BS<$#81AM8T8 z+48Q&%d*_v>m2GT&t*k33l|#lzTRz+x-K-6WC^r+_iWI&|DkM4xLrQ7&xq1F{mHVO zn>}Q6sF3a?FK=dskzZEa{)#wbiYW5=PNCQ*ZF?5YaCHB5f-S#WV-z;;NWkbzX2$tm zv(|~Lr6oVk&fu%D=p ze4vL5TU<)U7|feG0du)n&tiLX+$qITB+6YK!S1to#}_ss_U`YO3Ca|Bs;&egOvzsj zI`Rx)fA{8x9vD(oyzVFcsGot<_@qRt-u4j&8Ho1=inHzc>tvg43x0G=BziHP$gKc9aHq2lKRSK0WSDdHPxThPM<}pO%m%j>+kO)} zZoe&~yNwxU(}@bM@>6i|?GBpe-W>KR)FV2Rn=i?vUG7QKUg=yRiH3hPeIRerwW6z~ z;8^4DmX|?H`ypGPyeno8vv_U3WpXyQ!$-&djOIg8tII*p(n%jttKaz)dR&?X?rDtp zcORdyZhm0_v18}RO0lfm8)`p3S4vVg00m&FW3i81XD0BPW#{eqb=}@$$D}S7)MZ;? z-MorX;R1SP~ zK{X>HFMlr(=%Pa9j#3-4b+>s%A6ha_77cn#@~BYljMMpbJt&ZAgPU(N&=%GV-D8mP zK-!|p5#bKk4&krw_St_C1(={PLwYr^*~QqhSM9njh_reJQ1J}!s`+7e*He?s##H9p z0A62fk|bpR_*p!U(g3}^8h@=%I*JP;JFP+@a zy?yhK4%nOeJM)K6CdBU*aT|ViTyv3cF_PhsA+*>YP~Zd27?dPZEDuMy+G!oZJ{^d?@dtZ);TclM9$!g=I!Xsgn0)9_ zQOo9h6CO#Z4|jub5>(z7ahWP!nK#AV1SnJDPW8tl15HN&~Zj_&iSh*={-m|e_Uw9%Q%`AD_dM<#bG0{-Z{XE^VA3I)gUNc z1c5AF9H{M?4Y!HuVJrZxp8iiRi*-0`ol4GWzH)Jx#DX(PALrSr^Z~>{H z_YcLbG$pWj(WpO4h< zH-X?pD~m=J=f@QnO%cgwQ2zk2nm3)&Gud!N3~TBxnJfR!?CF>x@oI=Fie0NU>YCL# z*e8EYLAH4%29ikitf)_YmBM__>Di7cqGk7HE)42hv)qO4L^qESBB_-9S^?_jN>$Zd~6Pz$wC&tqCCGB z88(ev3Af&k)oQN=#y3qvJGzX9$&U_pPY6tfXz^o^zSow2j&;9D(w~ufdlzWicy*m} zH<&04+qdQreH{Bl3#7!x23ZYHO{YX_UCPT!7}ULT_1O^%A13%wR2}HJzW%1YsI++4 zKid%>vVoEen52~fNpXwSt#tcTgAs7sqgM_a4ts~Bjp-O*eQ)Y+8=uOUgyfyL2%kYJ zu^tC1vj7)pmlXa0#nCXPu`b!XbWQ*Tr7DJ6mcfNWSVciK(_|n;SIn&qv$vjM2bc_; z@gK&OT0ALlyYqaGl=qZB-~re7bH1JYIQdGX5?I_uOdexzZ4o}Wb;M{W;X6jCWDxsY z^o^#z`+BVDhxf|wTL3Dsk{x}pCFF7d>Vhi)*?Ag)0m_WxDs+bmZ{+$e*_sjsCS*cp zJ{TJrm7UxIs-*7bSP$f{QM|~_!q7MgZV?w0uMPcGGTr-|P%Mg}H7_@%_5`Co>CUff zk1<%@zBufvYBTsBg!4M&UQlxC!U+p&t0xz#&A29NIjG+_&?DU-h?V6e%5utX6oJG2 zbw>u@;c4e+DI3!+&&)RQVk$;_C=n6{ zFQPut-2CEjVy|gGFtb)!!Zwh@%bs2%_#=9UHt!wx(MZ;G*n-?L z{&Up#FCq`dCS(%GvIe<-K7|$7yDoiE`OIJ~V*+0AIW(k8sJgYeKk<8WF1{`G=9+8} zHI&HmVBqxFmQ>XF-;fVZHL5L1zQC)nSpLn>M*RuRnL%@4WXip{tAd!<(jFla*>|$a zGfV3&Op&H?u3rJk2GY0#R7p{x6NtDwX~W<4x3_oj2hAZdc5dW*GgDY0YsHF&T9>$2 ztj?^MfNB|U{;djkY&MJoPEfcaqy@2$Y+nw^`BD!K-}$CBKPkc*(sm>$QyjA-@k#e~ zb=gg?`~_}g=g#~@|0I?HyjOX1k4~ML_OMRR5bKn-{cDtUUcz(sN)k}IHtO}Sh9(u< z{!eYVB2IjO5T56-00`zDzXrnr#&gH(F(% zv(A@lXir5M&$EH}b_F|`0Wk1r##DxPHFnIgGc#KhNi1kyj%ziNNm=g7=k?WeP`Rpz!rN`;>St2>Iu#S9I^Y_}<3yH4gg#=hp2KcStvJ z8#28t6%;rCrERHu}QK(gabh5?U_{SF(0>k!9+h`~W z8`ZW^8odfLwIEM6y_MxdlQhS9DkX}^sXB2v*EUa?Guv_E#W<(^NTR9HWbp!%LobHd2;rbSuhPJ2tT z0qLWCi?nC5mrU@y@?TQ6t@A$K5?^DKSYFHgbtvM%fl%WiNiP%psmXpZ&7r0`h5kXS z#QesDh32Z%EfoR6;rpB*D(4OEP|vK_ULuj=L}#{QflQ#Q>MPng zn8>l!u(DpnvPF#mkA``oy8K4?r3}RZ#Q`;W_!ds1+SqpP2Wy z#|o{Dd)Bq5O8@&)qAE@CR1kcR8*UbQJCT3XN0Wf{_lzC{u`}8xt#kqz-iJ&)ZxQ1GSNm zhq@`Kuh}tLkypVHMSx+G@qlz_HVvmLqE+CL!MY{n6Td?v4Of}eX@go`KQucQh;L48K}utH025(g{?1n0ivOmS?6~31z zqut8|ZG7Wm;_?)IOR9c;nA|srLj9`O8oB;DH8=odS8aBQSnYa?q@^n}qkIo3=^8ze zO_Ey=<0%4s19X`+_xE>VEL00ib~KKbPMqy^;XQ ze`4YFNAcMnKW&#&x!h|50(gQixH~9*HTx~alqPv3oSR9lQ@R!*rS~cXZSAuB7nL=U z6ag+VVs)j(5#uM}{{l!iKBTomVL>bBSSiPtO^N$@3Hn*wmmD1%){F87a7uwTqU~ zKp^8yUR@KFAEWPXJ|qrUJv>y|sBCIUI+Ke|9?{H5UM#_h3(QD}23Sf*( ztE|*O&`|pU9FD(2W3^t{k&}S;DNkL}tXuX@xlTE)d*7>k5rwZs_x#>@ec{J$(otU2 zUk>tH%fp=P{egTnj`Xi*KoRM-s4$BKQRBSz-Q{DFFO`aVkr=7+-}H)QIJmT7#J5Js zM3au0D$j7xBb-G_%AG})*r=VLol?7gtj_P~p94#f}htESMO^l8C0e$&NA92?7)2jRAhHD|cvkwb$ zzPXob#Pky3jtxlDWu+X*2U#AyDU|vRBzL=?r`SH5Hvzv3w^>^cuy<7Zy6>9`wr%i{ zg;90&&bu&iZk&xJQI@r4U(1g>m`$6wVw^J4f`d=&)?hUgAMMu&)=oDLxI|ED7IE3JK3RY&ju@bvsI9+kSPT zji0Jt$F{%ino8B~T8DINt5BqR^HLxLwi%)dqKVhE2UOd5DYv*lV+#SSkBnZmt7&xXila@OnuxE)ug@vyGCX#2!qUXb~| zLD%W^G$z2y)b^oia#dG=^Ymm?aLNAsbKHvtxJO@{X*i3$6?qWRT)=v+-_PgYv{iF@+G#u#j@U z^Ne75>hwA{fAsNh0#qFk8X|UoHC}P=YlyCZX3vv{MT0;KxC?E&k3M6sH>LTcO3xWsCtmaKB6!tEb})AF3Y!2SfaT_ zpG)perKCfWou;hD_FR22QC=|Gy%sL)fE)qw98w84w|5$tna}f6q^z-*7*+Q+eYolpBC`26>-U9?Jd4OC zIy^oLtG9B^5F&*8Ts&L6GDE<=cq(~OIA3Z^&CysYIV~Nb-$ivP`+wh2{2b0uG@1T8 zAPNob%|Ma_=b7@o^@UPID2jDi!tBY3yBZMZ#IsXDDeMThYPwOL`suYzm zPv$JzGt_fMn2QDLxg{ACRf;hRQnc?c^0Y75AqtCygoJqMZpH1)34iq8R#q6`y;)%u zNTYL<)t6W$wVptAG;XLC{G>F9%xp}|?>zteE7G=YOjO8LBiJ+`*_i<@rRyo^Y=?LG zw{OU}L?8EI|L0GqVdnd;PtK_3ODa=s-Tt9=2e`A+OGe8`*iyDU?1ST!PuKM_YPH|hmd1Ff<@llacH;V=?|Tg$=?JdP+WRO_^s5+Ta_j!MG7-x0$%)rgr{s>f{<8Q_YCPW<=b=a#9 z+FJMK0^cDvCPeJ9uxs4yx%vLpdR)*S!i|8Vk>hrAgOUSlb@G~Uqrl-y{x@i-9xtyy zxx`?ePBbrTdE9E<9*7>_@H)8quAIgce|JmRR&ti1U?*p3>g-(3mRq)O_hx6*LYHpR zxY*$aC+06TF1s2!rc+W#QJipnV@xAmUjx=U|;wTP%Lk<-Ov%?{$ZHWy_L~+oc~Dy+1wa7bNqd_{(~zbPSEv zUapD4f1#E z*HEa+GtP9Z$2K@Z(t#j$}?l%#9urWjkIp(mhgS1aLD{+f4nW72XwgFbGDft>U+|8`C zv{0noY&DU5;w-HYLlhvGE&tidWR^6N1T#;oBI4~xw-mBE2kY4z@sqZzvZeM_eF$;n z@C((jT~Wk}58;VW;q2j}Kojv?|S$XWN~ zPca<0ahwlFEAnJmVsjrzy4vIE?ZB88s*1d`EZ5O#;HtM+^WTjW;FsT}Exk@$aDQ?4 z)X8vSU3HbfPS&4{Y28(}rEUMhn{(-_kGBb(J%d|5u4JZfq}TZKsW*Vqr!?$y0TdO^ zF3-^LU5m9)Rny{`t%>!AOLS7hb3VbP4NHltt~0U<9lDDF@L_-m>QOcpjbkfSK)aR6 zGif@S@3A6SI{O2{ga5TXe--&FF+^ATF4Vg9+1r1%j^tWioEL)KSl^#^*(HN7N)HLC z&_7&Ov12sfA#ycl>DIHDPmVaGr4B*jaZg81Iq-BMn^3S0{-6~>b)dWuyyI>f#G4Vs zn);o}MJ>NhApeJodFKa}I=|=hCG3mQ3d3l>B>4{to)73!o3DLxU}J`1mTM5iAq zGDecL7Z}R6; zV_XVa;)h*{G+D>R?jmGkAKQx=kVV{n_?2nql*mBO6Ar&K(i25^+B~71m}kNDzpwz0 z$Rx9lJL%A=B)UbrH)ddjLX#zuKom@7C($R3%YP1eId>a?j7B0jegkvYqDPVHqsAyZ zwe(@qR6!L1H1(O!MD_T>$!0BATOVtY*1fof#rD9#G(@Y98vU{SYh{StmBy{8668oy zzmb2W&IM+`BidZAvX9$CO8sBFhnL3DPx`cLtJ%oE>H&t6hl1>yH}0*+|EQPf-}a$c zanQvl>!`7!rUl*&$xUn(7gWHQ71QpNrjrnEEEG--1SPO?yJE66mUAOJps`(k;*3qh z@}S%&IpH`$I-)r|??r0G(pj7QSv^Tqb6Wu%;^T`SY5z2FDU-Q30(Bdr`;I|rSm=Ked^1>NRyva-7*V{k+Z*x&n?$FQSfuBEUuuf4pA}kDaV7JGO2_8i|l-D<5K(T zSQC|uV}0uMvx}X^<_#&)N#5>DvHkx1JDUIIhlYawO)7qb5(*4ejRcn_!p;sI5v19a zIMW|Mi2`Q~j22K2q*fVrcqTrPbmkW=$s1#`?0bifvJ;UpQ56z;v0n<5Q%h%Chw5RH?YK8Q|rsQW|Y}P-2?R)_9VS zJ3scSW;=9hP|d-$pbnkMnxy1y*m_$C5KMpLiKV!pi+N`s>}#NfZ!{vnbBO??T#gGq z#X&t9GN7h&7tbg5E)!KzWXS92rZX$9F%(2z?1{aB{y?a3b!VeLy1BJ5$_T6PA>6RM zLFI7bb@8*eTw}P!{GbuFlhcq@S?nAfmtfO8*Pfo_6oACU zXo)t2rB(wST-l=co{*9>i|EzmISn*{&rp z9e5r+C1#J48mJP_1ynaA>Nvu@8^^Wk#gz~*j0JK!>Y+Z^r6c#bBWXmuq!@#lO~nbl zuYUkY-qyiAFK{C)%Go`rYCPcB45q1*R$L)jD_Gqpv0P#`6K8rZm8%V1M*u6@jxKH2 zrT43qL?O3EyW>_yUQEri8%q&W*rNMH`)Tz?3|Y=DS#gzmui=@<^8o2 z$S?v_(e)38$AOv7)Y1fLPybcz=>kvC{$|dj<4;to?!#q?dq{}CqNRj4l=m?eO*HR#aFfWdZPwx?hS8(qVhzt6IC*HO^Gp$cInGhvu*hbI}|SwB0;7W=8d z&k>XFRWTMB^4xmzX2mInzh$ndeDc*LV7KQ#1192HH{TOa1m7n-Wz2ubFm+$K2I?_A zWD_4fS^9|s-D^nzxx#P5fu5%%*|57&fNnq<0I{`Sr$L8~3d;4C0<39g)$$}gR?Zp= z(aHe}c4?WfY42RCR!Rt7~>xt(LfErS@e7Sl$%fVUCU&-Yvb2FP1MiF;CiOv;F2+k)Z4^pHsDZ zxw3&*ZuKR4?sq$-DIRdR=`Z~RlU>WR=^=_7X?Z<&3a&ZtSgmyY;IW6ol}#faA&BE9 zUwA%tuJ*qdHN0l-s*SifemW6v>pP!{$Dy79I<90+Gi?7Wf1VpC)$El$?zeCBS_JL5Px^}P-_esO(`qf1Ldt1fiUbz&@&k(4K^3VwL1d=KaaB_j z9f=Q5?%{^2ugos@T$2cL+5{YOPYJfv zvu8OlT4|LHI@QUN9};c~Ajvs|@51GVK<8?Rva+#XpzPp!bY9cI*?ZmS|XOuoaj3xQR=`j6og z7tNO%&-ZR+^h_|?Ig2-(;a__HyGrzixE&mH*Su8X(((yKg@Y{VpR~D_ zNElIAH2E`5}P=#ZdD;`EREn9Fo7$-R4s0<`85S* z{vSymJFx5En2xEu8xT0)Fx*#4j+P#5n~Ebc@h1>N9v1Guj|z?>@Q?3*T)Wz%upMIM zfr>Qb&otwyHCW}!Zrehlzg<^APenz>8`~WP3oVqpC-3Y79+o}o!`E1b-=BcxJP4BM zo^{mFqj+eoadv&4;bc zFtYw7MTyrHLW2F zt&NdRT??c2C>^KjN~G|;4z~%`iJW9H2cc6V8A-@1Bh?DtX!Vix)|9$)+tKf0)UO8m z)#r*BBC8Jd$f(RsGsCMSK41R2vmVu2p{75Ns(n->0)CiPSeRSnj-DH5anxRbIJyL|0fSPEByV zH8(ak{v}RL(cd>IA7`|;nll>4_I!WhZwqS`COwCncmj3zZIQkwFE+ByBrhrnN+z?0 zN)677zHVpN)YRG5NvmmANt@#%*f#2Hi38vP z_QT48Et2xgcv+bqKz&040XA`*@$Ff)GTo`q#--hQEq&~^}kA7 z;cl){zC)7(HIhzu)n}G?IfB18**fWxro~H-rVo{-|3%W##Zs#Hwpg2yTco^w&-q@$ z?7_fPy8~Ac1&5@>a_8!lh>8*EBGb1fFZN1%^MPq2&85-bgUWGOO674#j{Mgfw~rkh z)(;AKMb$tmbQqI=9QhkR3*1tg!+3$+J+veYie95>sJ(Y*i`8J2}abNHB_+rQqhsF1T)%S)?eLEqk{O(SlBpImu zHXGXSMz+Ed3Q-a-%Xvg#V!!v*p*-ji{gdxQ>EfUc^WU5nK}A+ucrv}%5aO&$*$gmt zB%$Mhq^~E&P@(B-Z2#n&K&W@L%K~7%fK`x)F&$}s70lliXSUj%D9@gxTKKg3`L6|o zylpOyq-KM)w7jwxW5h2(!G9cF`bS=niJ;R4$JHfN$jIPkJI*g)ldh}5@OY`(voWs( zG1FdQ@%$kEEcdSgFprh|#?J{F<-_+^wPl{KUys3@6gG6T3{rf61hrT5PQ~{9i}Z~~ zcM;g>)Xj99qCt-#C0)3hP@9;n0ZOmea;-L__Q03-;M3f4PhS7e;0QwcqzpFcprVxz zZZ-AX6fnAOGkL#n6Bt_srZRLCE)%pijZD*y%)WIsx1YtBh8C>jXG>MsIhcOp&>ucA1HO)=_S?*m^^E@&+<7gzQrw) zGxMv$x&&9u1DVs1O|Z}1;#Uf{-T=SmRE9;-Ej@{q$r-j4shVviB z;me1g^7gx)ng?$4UKIuxR#Sj6Zeh}8&q44Jy<454#)7MZ>68_JmPqC66XbH!wd<*= zKz7NhXM6D8%d=jrU(x9AsjHn3ovZ#~Y!fm&LxHVpcAOz|HL!SoK6pM$P=*$}GMjD2 z@u>6|R|@)-%LsU=RrVZrWrpAr0z{rP8s+U7xv z`{+cxJo?s2HfVNUG|>(8|A|PR-MNLzbIdaG6P^6cX>CY#$(BMpm)R{8c{pujfVaQ({!HwI}%VF4|&gc9M7ro4o0ma{FU6` zcmbCW7Y7yM0Gzldf6Owo3Pw|RtKF30%9ePFJy`X){V?RtpYbv&nQLIl?UAhKl;Y3JeFSXKNfDs8|Txt0%cR4KavEcsck|z~PxBNt8KhJ4rWenlOcT)+|dV zP$MW2u%Cp~qBw9Md5t0x`uc9I6qQ3=ePc$Qs#@ay=_Qklc;Zx(4@wAt=6IHTi zO+AzK8p(~Wey}G!lk0{{9|6NOYm@(wyhtl^(_}q~K z1rIqql?G%F*RQb*Qh`Fbm(^S(A(-oxDiIGRtbPm+4En4%b@68Yc=+*kF2#Ju(T&4lA@z;ks&(d?m^x=5)Z;^j4NsBX(!tFq-_qnsWzKKP zBfJ=T`y02Sl+!ZP?1P3A6VwC0=f{(8khJGMR8k{?jwsy!>Jt^gvN#g~wA4;_tQM(? zBX;@kp8q;AN7Jqm=dTKe=HDiU;zul6oa_W|R?W-j|r0U==PEF<_ zlCE#+&#g9KF~JJm)aEnmP?-Ayv^l#uF&}rzyYG1Q^j$N}lX6D_4`NI4Vy&^q>KQ0! zD7m&JWU$}@G4j18!_WBzMYrz0iF8RPEO6m}xJs1h?O)MlH2x6X7>skhHTA#o;_5i? z;xCLl$1ZK345F@sPYh7?s&Qew8xj6sA>SAbc`u|D&Tor3p0+YJ^$=Nj1&jOxdj$&$ z4s0ZVo#tZhhnx}GdoUrR{fdM(H41y&*-&oZzh8{+-YB^>v!XNay% z=sWWW7MkPv7XoPkNh_<-%TtPBD7z3`e#yRnxqM9$|5;46#4VdQX*+2~Dr{`Rr-NR} z)h9J|=IxR+`(kKq+PWU!@1qq3CxV3PS&Hv6rLI|z;RG8*D}Nt#sK7iP4R zS|}9IDxYt<_Os=Sj};um)2||bNBj2;nJu7JN4sD;wlzHDXK_B)z_;GC zJ`U$9kQHqHm!Z+=Udc$L>3GwZ%Id65vOGm#QH7|DIlD!+aj{wVp{3rLwE$*&w-5~yEH5sHL3^&<0btDUJi)P$ zlIm{nUzx{G9Fzz-^7ndt^>*;5jIq~aoJY0ID#IgEEdX-eFkI=wCCUZYNX8F z)%afqKD9VyVk&1y9q*-e{grgc_*Px-V>b&JjqbR+fzlvILfuPf7oYT{jSImtEKFrCZmjm;ojO00q{yq$zCq_&K$#uX;kW3OY^!7rNL79(!xB%`tga(rSR$7jj(ucPp z79pkk;JXjkKLoq}xeEvGn%M;^YPtrdY)!$_7YQF%o4;7Q z%vBnSdab>wLnV06n4YkzkmPAh=QJ#fL(N;8`9A-QhFsipgYkFbMNZTt>n(yO+xbhpkZyK$3e$yA<)K9AR^ zwdvV@HrkDw$v>qH7vbOb)8C`=nh_4|ENjQ|@@je4<6q8>!+UIR*4a5wq>o#8tD81C z;bU%Roe&y0>(b<(MLZ?KIcYG z7SHC)*0a-t_R&v%*naQ#ey{z}AO2DM=|>;8)3eLAyt3M+!q+-G&Ze!4i?e*51^*cD zmfOSk-Y)}#Gk=_OgO9ZCz(E^M78oYNbHhzWFB@Bo3uXFvaFY>advM z&(D^jhZ2whXQnoPO;-P{)z(-c$V#CZB*1$wEv*zzGc@5_A3nHW#xk4QYNJVTJb)_x zaw>Jqr4F0m@D{s!J9YMv&}iCubjT>%!@f~6rqa59!U&SG;3lQKHCXs#_{+G)2(q{^ zSB6b(4g_Az9Vg7JbCo!aT#9l7L@(+_V8|C zY%^ZxFYq$L9x^(-*xW4H{w-S07 z9@RRQZ}1lHOCb#BtxM&-Ngho?^F&ZtSy^l=%L_#_tUVPaA$VhbLi@|Bb7wcQXb+$7 zp83JU)A+(q363#h+eAvXaDFw~AtbDJSPOW6;OTi~?FW9o^K_dC9@&iPIfGl52||UL!f?*{wKGR ziHGm*cX$rz>RFZBfA{(2vzK}GT2eQJ^fG%X%I)90Q};)|uTp-N!DsZwkd)xB|LbG? zxm4x!tMZMmo^8~IQC&Xj`{)y`#*e_|zKPXl$6*sI*{jR)mEhK>?q23lcK_7h&-Kk` z&)x4;rK5L!NrJ6cy&1h%PbzEAQ{R=X9zT<(;5+2^+q0^>Kd(=JxvyR3eW$@avQ9k@ zsL?>bc`SCC(`mJSciPhXRR*xpnAUHf*2cQujbYVBSGBXZ;i`?fUvSic{;gm+^u6-e zLz{+eT($O)#rsvMztrEW%X&L{RL}bNUQSO{gTB_)?|1m*(&qZ~u(!L$FMozq>=%K+{-c{&-&3+rl5_SC;>OO-tO-mhw-EBF2NI>58%?T`E? z^|ne?{;1q4f56d-)A1hrO zzOK`C`WhuhnY-^lsNJq+CuY2iC3$8?5Tgc#IGSRS@}(HiERKXmyB#qq797fQyT*j} zz?>7NFy)vIWtL(Yvz4+i-*$^GE-jV^MtPEjabeWKY^cWqjA`L{aS=g+qD1I3tDo{M z#GTl6f@k;bbcFbs*|`dNSc3oLR6l$-3%fH0v?tPb7=d(`0H8hTm&FzHjmbGaI%tOx zaD-PRxTLZYObCPnV^GU$7HM$kM!#ISMd-L4m`u;jx7i3fln8{YWGYXxD*M1e+b4Ce z3`ip(N7$n7?KPfubi)RL zMqoKSPX(3zI(=C(27zPk{tY7u$1`LFQvyqkksHP(m*4d)V+sBgB_0h6zq!L3LB1|b z_g$NABu6rutHFJEnt5Sfde2;^RDur#3d)Ychy0npgr=c>2eP{l=O)I5t%?wyKgxv) z^~D<^0@ffv*lp-Mu8yM^+%UVL8RnoiLLXoj!FFExC9Rb1?JS~5rS-{&s(hWo?!pS^}6Mjv08w5I3%d6$nbuH$o8mFWMU zcfCyoiK|=hJj++YwC6>^ijEB_-$Ucj6P^cm?=H6o4|<3_YgsAADM~^MltWQc{0QMc zZR{I9dU&lNWR$k!ZERdXMV&t^k=#_}Fdf`c|UE0iIl7p1l~qqnE+ zO=u1psHz+4%Kh_`=WT!IMc%#0iXL7k{KuPi5k5j$+qG`F}0rh=i2Nv4;Wzpd2!jX9~yZBJ?6Q7RK^K#O7}vmU$?!j z=k3LdjqqG}C2c2nN- zCj8s54y2;gdDxB*p4GZlhQ~54fJa6&<-K_RsD1X?qYUHi^l>SC>;3Y6-`?72Pac0% z`IZ*%W{v7+WLay%x)cv|dn{vdV>+Lc?al;+%Vj$|+HX%DeVjFBFZGQ!QDq!TVU!%( zTaViR_h0?1_V54we{8?^d;hup;BS7?ws#KOlcyW)lTSXY>+z#U?bFXbYtNo)_hoZ7 z)q{r*+j|e+D=!wCuB<=q*A6Z76tnbEhb#=L|udk+_z%=h#7j?s#Y32i7fniN}Hj2;M{FL=^p7+x9 zY~knDmJpK@rKGn;f?paG-khO#yu5T)>U=zBSzWZP7u)roIe~}4@7V-~U$p+a&r8Uf z>^^=LT=A&poAsG-mH~^=OUOiqkiA`olf&X~r3yV)^XyG~_I#`DA2@F=bA}?0F+0Wb zKH?#=v9Z;7xGyZu7yrtzR_BwY&+y8+FEk!}J33;xJ1ApB8U51tmDS)*`ici)K;3+? zRmL-8%d22{#U{P3VAU1MKycbiIZrc=LIAq2jQRA3k&v-P>TqxtlQWQ7#@`OBJj}8icm44Srg-tTNstn7BUp0^uhjd z@Di_zuM%?l?8aKa2(!&`^Lsb`gKrqdnqzE10Y-! z=2JMq8mpR1oz~WT4t|2eROt5tSvGwzU(sr7XFmfh)IadlX7j^bQ!c}%H5J_P-_|AV z2%4r($`5QZe&~cTgrg-tgvQx=x4XCBo;};lJh%Cjj7sP5u96+kP#>cU|4^%az7Kgi z?0V|=3WS;WL+Zuxz^R`FM{~K_4(7R}UUDy^^afR*yra+DSC>^q(w5;{t!@45DD`sc z-FGhOZU2($mftDON3M6D8=Ib~-}Aed)60^w0`$Iw&eYnLxuRcE$(?~KnNPVL*BFD| zmQx0&WQT8~*Lr)aj!~Za=%3+W>U%ZmXZlj_e8DH9%#gg=c`?tF*)MHI58U$!_swH# zE1X5=(FlDU)*gI?eAWs04EIXk;mc4LJ|&;kj(l_j82NC3*{E$`pT7>55hmojU-g+j z)Gz<~P5)Kj^rzsM2WVT#?Os_y(76hpDRV3}WPJg#FjNi{o zUw61#ajp$t*XcTaP121p{;Ln}wS_Rl7h#}<60;zOk`!}pLA97tXlGe0;hB(S87amf z46RShhTXT$Z0I{z!w84bwJ2H~g)^x|KZ1pYm7&YQ+Cp5|8HuYRm|9c^X5%7)fHNKJ z^b8+T#KSH>#wg5=%bLkxpllvw6e+?a*v&gVGgr*Cwajj_t{lIa1)D&UD+@Qq79)jW z!Uzfhv$yB$iNm~?gbbrT9PFLvP)PK*!c4jhERJ4^Xp0O^Z|Iv62&994+BYH6NJX}B>YAiAr* zVmvS`ue(w7?DV|tZ0@)769%^H^p#S;%i!}WA|Br5m--0^Wk>p!AaFcD6jb%T2Rb# z#+sr+`^w8I&&`Xmu^vu_w`V`Rmas&i?YqvQh&hKr(T3rWZaE44+DvhFdK@|tq5mwO zj9ipYn|AO!Y&`8Vhs*=z=sQnO#`}U#`drL-@|gqjr9-8xD_o6eA};!&f14ki8@H7hi9`{KE9^Yd?E^rId_) zw*R~&$1nOT67aV2FS*R~zm;;o1fL;a(pA3E@8Nkw{QSzA9s0#Ygw+syn@o0y&pJ#zjN&!Ly?=wP!v zD`uzXOF`2^!&<;ex^S&L4$+NVGLVf)@+{dxPtKlrch2S5Dl!1yTr8q3;BX@1dOY&>fJ?Z5t) zI*)5>Yd7~8u*OS4y?@XRQutBp3a^oc`Ng)jw%%4&R?6TdtYwXL+HP&0pIb;@cvTIN z1m2XV)YkTH%F9}3eav62(}6V}jv)jbDB3GzTGl#><-Og5^x{q9-32Fwe|!JEhi!Rz zK5Y@*fOniQa~CP^O|9j%2_>+g7*_|L8E#WH?d=_wL2)nZtMwee53UsOhsQ^CFBP?k zsj1>?m9-yy=22v$mb0!*;5%7Y%@g>dZpv{6ER(MriPhWr5N;C-TC}m*BWpo=6O0!t60D()Z zAY-$*yx68@ri)j>Q&7O_1014^ESVyG1LtlW;>nZWX$#(j7trzXS>YP~UAg#kMz06= z*YffY`b@Fz3{j~-sOEBWHzD+U#H)~XyS8t)9eI~h7CmHRk0YBd z-FJa~H+~6E$n&uqZfV4{-Pz*7Xp>t)d${gL_-^=_wul5@QJR^SB{4bBf zj2FDNany!PbH{}@MZXw2AARdBx!^24u?Gz-1$A>JbLD_v?1%?_7=VaqwPPLNFu4mf1-kZmwue_;EaB#}FGr++$VMIOa;S{?;67OGO7SG7LUGc9Du&;BM z82Tpyue8A$iXLul+aSs~5KyELWey5(Dcvp@;qm?GYrEP;sj|M!-&0q_52?x+rQ#8M z=C6!D!P&uRA@+sm!{3mve;@tdzrMXQx>4_qt|9r_fA)K+spnB|KJ|3yO8u^%=taNz zv*o?p@5)kT^iTN)1B_2~%47bN7ii(`$f#KDlE1%KeFp>gmFI0gu7363{Z>AE0sVgc z-%~wtzy7`btp1Mj_>!L;?!kkhZnVN&vL;zq(44v8o!^SIwsp@<{8`FLH|TTVxHb49 zbKBg4a|OpjsMM7@x{*)iZ~I=nNZ_RYdXkrF{i{zo-;P72(bp;`{}nu{u=>~g1BUtQ zWsTnV&!>E&@4X2BC&^b|WEkE1nIwltRY$&{VFM2J2cz$!y#DWLRC1mT?I{D8%RI~D zl-6bWp^P-rC;DSNykovw1Le=dtFrX9&$GAfcw4vB+jN!cd3~v?ehs(K!r|4rH)?zR zpLA7z{dnj4eEQ1t_@$;={kLll29)z_wKgE z2?rERvXD3gHq6!cmcR`0%Ht=w>*2Ssove;3{kmuM=mBl{ZfA zRmz%6pkS0E5LbgsX!a52BlQXM!;?+;9XqVLr<&bugqjFODUUGrMjgt|vp}Hw)psn} zb>72^REUtkup9i|v^yo-Ot*SP20w)7F%|^NJEL9i-BXJfX2v69M6jkDWCSxeF{P9?71AZRZO-)bR=RK~ z1Yj9?QwL$4Fbd!745gSc-h^pqc~SN-#1h;oJ2BT3PJ^&Q_?}8V=z?9Llez4gHfJer z)G-s`V_FEW{4vgIzy8$x3%+PG4uy1eMGwMOT zVorZ9jq=pj`rg|)T<8$Ga~Ar@dt&|GdU+G@s6jK(F0=-XwCmr6b|{C^*g7a*h4srb zbi3%@OP&`?;bm+vppd=UUY>8a$B#ZLLxG+Dy}f8k*5$LqcCf#ndRpptZpvkyzZJ4r z8+WE=m)f1N$xyP;Ykr!W{JpFbE9tW^cj0wf z*7sVMQt<2Jc5<*)H2dXc%04+P&-SO!o(B#*x^A|kTBxQI>!3!3XUd-}pwmcmIA{URf%`ma~2Ct>0_+gFDvEQut(Tf|s?iN@4j?-VEuZ za`0Hfobim{A;e>hhlzD?raW4l#nV0DDC@wejAp6JSwxHk#^~VSB(<~(mB?81@V(wH zydb{rU{6TMuILulPPxi~W1Ve&FwIoFG~mo;-NcPvZB26haH ztHBM4(L#H9*=@eqDMPM$BwQ(8)cTFb9X9AN;>W+K((?Gd135UTUeYe{^!+8XM&PBx=~2DI$m&d3$tlgKTpb;UqbpZC@}^I8)pvU zi=3+@Tq5Ob!6IX6eldXX>^Ya@m;eC(^hrcPRKs(KZXtP&w}C5^y66xi_{-df11{f{ z3(v?&@Zl^n!sEw}s$TaN(vN;EWUif+K}@^g86&7?&Q3$e`esCJ>a+phC>-@d`pK|k z!ytognmIBwMs^AJ?R43A2j?aD%h*(&Wf_wxiB{vM z8D_|*6z2MG+!)&Mv<#+~c@F=z*~UUJ2Djavohp|+Y&>hzL)xW3=8&;tEGJj#gSl+J zyKK6eo1G7RIxVj-9yVk%b(j~%-uR-yU{=IKZ*<5<*5Be~@%wqt`eeQoZl{er6lbQx z>(}P8&f_zlGISYx^RGfv@)kr`N6BwSFX1`K=Dn`2peHY&Q{-NFF08(>?)cl+4OC9( zNk%jVH**wB(FsOcs{HDWNJd-!yD*y1=-@i&jT}cJ|^t(33=2I@XSt&A?yrU-7 z&$rd(OZxq8+v;*}$dnK7lBVA^qDreR0$?(pQ=k4dvysD|%(Ce&s{L5Gy zt4@Dk6%NvEC|h3b@QIFM~_{s5Q$ z9SnFcc0R0VUgmg(G0b-~#=N7GGOzJxk~t@T;ZORajG~q1diXLptIwKQ`A77{d)lOa zU#bl*zribI0qNVz|L-Ju-nm!Z8@@<+q%Bo(zL(Bu7^I}CtNK5Bx9WbIDrfEu--k;Y zaPjKBTmuY0SC04n8|ArrkndHVa`dyV+^f&PDCNNW@`_9I!5qBkg^EU`AVza*1K18N z^ZrnO{hxpRUOi6gPwJ|FzK{A+nOstbY`=P&daifUP^gE$AieE>zlPsm_4=~(MR~vM z`eoA>mG#f%dN=)|=l_)H=e33Cb#3^%PS@#cl5S-2Uw?SNtwngp>|hekvyfp7Fc=sO z3m?xSOanflJo9Q-Rh1#gYy4MWqJ9cOHaFCGak<U9Ol5;76cgz{%&|`yO32xKw%HCN6c6d6nF>E?6j|Noxw$b zhxZT_?wFI#94Wjp0`NWaryI9|L-{U5Nf(T}Fd&~fWBklf;|6E!{Jov`%&9Vhm64TD zN^wUC8Qf1BN`T0_&d!^io>g4UNyeyRg3|`dI7~F91)&zMQOKF67-u_dwa2boM!T`l z5lV*5jg2yPF;4ULBq*5w47xBZ%?{2ByW~LoP6s4-I0#722D}M z9tPdQCs^mZ(Y%+$n>{2jv@P_Jk;Xfri+A91 zPJ4MC`j(0ome$(py>En`I;ZL~Yv)emsWLUc78s=T8Dsisjo97U${O*qP39ScnGHx8owW0^y?FYg_U!Seb!O|u z*>RJx$#@o*BQG5LOX?YM)T7UTAH`?mz-SYII=%sYF z;Rqiltk_C;&DpuRS~s@0w`*e+1A!2^ynq6<8cSYnFvrFU>kM>f41#CU>}+_tthJ@A zf8C8a2PsR~IGe2SXS_XZ;wZ1NtV#GuUNh_W@0MW)ue!an({{FZOF?ZNUtCWI8T2xax(m;`;*tXPRq-B-Qw+M+V()0Ta?KB$bDlqY(Vjfr zO!4Gtc;(vdOG95;A3tI?fCHFz4q|Iy|kGJ`kOKkFroyEnI|bT{PdHj&q|)T zx3=6?mz~+P)INCcK^ZFc_l@Ua89W#PYCdLs7hl?=pp=i_3}J( zXROY(f@g;Z$8BR{GjQo4tZfW5Ps%`*elfSZ}Yz838a2c8r~Tm`wiwbp7az+ zB5;)FS)Tc;ck_b3Q88EV8_&TA;Td_$cR#BiRb4Nu-ybe@_xj&W?)R5+Wo*u1|Dq~Uq~D?ISEU{kl=KFj~3-|v=< zj2ru2k4$7YYkoI|-Y&k$+Xbi5Cqr?0tC>3)57m{-mooJYeeL|(&6*43QmN_+{qR|3 zTSuhSJ?K63VRWnht6!sge>;61CY5{i&bv=a--Fr)_E%u6FY4^?jNY!#(Z5j{{qDPI z7}FuiQMuIp&izWG_WbQql9b~kSB*{GDr_iteEwqe$~e_U57gHOvOGG{YlTPZ>VI!j z$FCaWO1|eKFJ0YA>d!|Hq6tVq2ymS4ekHg>mNG(W7Kh-{{HFb zjnlQ^>pEShuTioKcxiRD%`Yw1svt~b{{FpLIC&CQj^WxOb zv?k*)a|vh!4&|<{-z&qHL%C(uemnV&BNQm{bLHD$j91Mt<8~q;ynY5tb?`$#fy*0*wM%a#U8HT6AI^{VAXAu0r zS2HY(-}%F3q*td7Ebu ze=@hn(+A9b=3eIU_{>Cej>gQwblT9{F)=lsXPIAbUIwOB+;#fRO<$8xhxza4U0*d- zR{#AYTwm1A&t30i|FZNY&w3Gm`{B>t^J};lG8OueHJ=hPwss4y-WH~rp{es7FJB(Ey`5*FR~JPKD@1fV zZ<|j)Edxf;+7P!2<8>R)7TTFVVaoDfovHQg`I9o%OiZt&?F(tkOq&WVb52j4AvNK= z9R@BiItt%$*w>uYRhyJ5bR!rtr0s{VI%qe-Gcgw0;ZGsTC}vQWSMRlj)rW0r?rwQU zZ9M%f?R?zU*VoIyH8H&!8Y*<+OzL-*%y=2z+RebD83Si9;7iK)AoV(f;MX{C~GU{G&f?o7+3>(UYg` zqmMpH+fS<_o&ZkWq zts5s9=acYOcuH%FH5H$R&n*RTZDKkEns)Erz4qaU-zuXZKAAxcuXPmukmuE|(0$2o z{js!H)PSsoyb7JmM0uTsHTX8w9=`XmhUD3^jV3JK#U)Wbv$6|VQgAoyIbM;DDA=5=9as6*OD*%Y1*;BcUb2<9cC?0hOEc<3TxzP zc;Mh?c^CD~B<30qv4w^C+62Z>2#<WhB;fq~ENvE=@;oxnt%4I{4lgwx zar0T%y=TK1{QAjHGpC+yrX4rh(h|ertuhoT5B~#p#sGhTH_%`0SzBAH%iLzP+}n@b zk-Eq;nxYK66~$sHnL~f@CdL?#R{VC_r|;;Dal_}#&+$-azB0Sb zZAnyskuUF;?gZJcgG-&h>Lu!>a}V zG*o*E_Y3yePMZ-k=klI1%lJ}#VmLs5$RDrDKxX`m5m+${qg%T>3~JqrmK?^IqkJAs zYj;;NK6Bkj7~Fvy}>w5UAB=I7?~>`vy{ zPT{N#i=Opx-IF5&w{V8zCD)dxR>llnFfS^i09qSijdxRd>Jd&lEi~4~ z-3EY?q41umv>QgcGQK{O7rfvY*mb3Na4ygE1Fo*D+Ke!rwo(4uXx8aMh2Tv&RafrA z9apt2@2jiYbjkaTA#JpAG;P82R)dnz1Nn?qd5Q*(@|4_=eAcze@VyMY@Z6XfZg^(C zrUylHz>ra|44SD^KNvCp|Lpx~lV?eGC+6K;BQy4l$jH5_x~tI*VK$o0KqfQli%6y~ zgO4H83rVkJq-4^FL!(5_V2BZj8GftNFD(OClFD~XTR;1Em)+0m*!9d^ znPdDzpcAIJLYGgLOMK-Qj^sPMI7~a1el(|=vpS+x49wo4W#|U{t~2Awl;Woh z^b!1mbmGHBX{Nk#EBsSmEusDOBN_`%soT)i{Zq8Jeve_St9!pyhkB@Y)8{FuYkwc_ zB2>Jw{j0sFR8vN;!c??2K6(kAZOgJp1GuL*87_zM-Kx#MBpm(bx%x%=U}tS(T{uuh zHqIp;T+s)-Kijb0p1Np$l`F2lB&z(UwA1ggtfSAbg6CJ?K+-sy$Ir$4d=OusP5FN5 zHOBvShBw0XHP>Bm^o92JO8(|b!77!IrQu;< zBh1yde}U<#)zQg^A%KA=Y;y_64;k19Hb6-Jj8-OI9&a8>p)U4|)Q@2*Lb7uVw9&cL zY2m_3U|1dIc$}q8wVN}v9z{5NHY&>)sGf#ta3_FNodPSRfUV=Sy_I^rQLJ9XpfYk$ ziY+ZK5A#-^M(_cT_IZ?ilSwmj$%sIM=}RY-pvB-uQ6L&#&;;3cC^2`{z%WYQ4mq$5Z(dN7z#8XW9D9PZ!S9G*WWBp-*rYrts26?k9( zVonM5R-+1VAHGI%Eqw57h4bmeF{TI=(^xT1@!W*vr^%Q25mc@*Xca8HDFsFP8FTJT z1LwfNc>QfGKvdf$F3nREo+;%VC9IX`aF3u}c#(1`05Q+TkU7;I4fmy zYooSi+Q~RN*xAju{lc}=HR367DMPIMw{^@?=*B`RB`BLIsTr7EWysA%oUx?}KAy3f z2PXwdDNhQw`z$buNbSRD%qXW_jBiS}b7!5;az6BMZkS(Q7?#&ohIik8clhD|>PN%( zfAoXl`n%VL8{fM=Ty;Ls%0k+l*Cho?(}?5n_cFW%hA*?vSO59<&B8a1_;(BFL92Sc z^zU;4qv2K3^?ke$pErbx=D*j%(RcNnt7u*_n-o%%*66|f{Q2SXrR6ddIFG8%^-4_M z)@YhVH9QoIZ?q7dES|``7utem%*`!@7F??>2v44x9iBfm@7f~kTzG=Z!|9nTDLQ$d zo=tx3y>R*r&#kk4rNmO~K3oqi3M~n5#;D%jThE8R?a%7`E41@v=={u?m*Kk}lt%(j zf%!R}H_!5WBmByV;oR)vaN^Wb$_p=Y#Z?9#!b-xy9k+*_4wUDMn{!7lygTwJ;+* z#VE1nhlP1E|9bcz|A+s6_}BmX z-wyxffBF9%e)hqK<>{m!*6-dM{^~FOeE6^atN(iV*@qtmzRXGCb+pOjM+d_PAAT_W z)nEO1*bQI88{c-+!faq>C|F%xDc(+A_)qwK;a&X=OR1rL6YGMJHvA&~N)0b+eU{arX^dre9{Tc2g# z4Z7n6&(4G=3*2~Vp8t;%$8HHcgWxS3-q_e4{`O}d4j+GfYgoUZxzxgv@B|dsXEQf5 z4)WaD+1o2)#?z;~TX464D&UP|0vrMmfAP z8Q?*C1Q99>IeZ205B!VqLcTbcbk5DyhLrf%u3s50rZ3>Q@g*Nd4MsOcj(chUQl6*% z7-=pnFP7npF=#${neR~sUSnWlz@1;5t@5=yW8$Q&))(r|D1}E*kNLSa&e^Tt*6sD- zlTU94@7ELe<#6rVT5Toz=+T49kCBOSR4^uZS+>X1>EY_tYl(lYcwt-M@s6q$@wvAb zdGqmhpdcG5yS&oz&*;#oxW%XI>vC-+h_?#brY#uT`dm5msf;E0 zu(`ce_{sQ1PQ&|H5NCD%`o>nuXUIr<2NvFN7gv|l2F7K3dx^(0ZEI_*_&a!5{hl_o z1ty$eWP`U1VwC3iJp7k90vQoL=_~Dnj-ugcm9iP{ioT|fG`0-Ia|^Sf6K&W$bH(xZH89qFMPkYWssYc z`V*YyE%*mc1IT+1a8O`WW(;SDkWU%@gYV`8W5(91%GV$8fM+Vhm$uT@cyIAr571k6 z@<`M#$|(cDSZ>iF?@}+@nr@K;4%%ZDIADTL#Ve>oK{&zOzx4gl(BJxASLjW@8q-WK z>gt;ZH+g{%{(!OCOK0S38_a&7PWj64 zNxIUJ1h2s{h1ctQ7^DZgHiLs1Yc)=DSD)ftlD3P^pMFSy+wie*F<-$_Upig^G`=}n z^cc0S>9^=z_r4D6Ha=GvZ_0C38wW>>E91)o$)bh1+DO;OHB7Xu@Fn%pj>d2IkD{9% z;Z=ZH3oMO;geoUE?_TAPjVupkmq(L`pQ~Wsratjo9jZ;fBuJvJm1c@pH~)1e)BCA8 zD$yH4rO1C3yB?-=uM+f|yn~Z|<=ZsYzb;5S_09CGecZKG*PMCT}nFt;VR# z#?a+7zCtU=&lXv`V9RQ2f&; z&q^p|5MYqNluAC6u|jOT5v(;um3w{MshOd|mb zgD(aFsu@XdypL{`4(<28Rg^kq1U0G>ofw45mQ{37&Z2#+kar&m(Zi&Gr_#h zDoZ?cK^-WLjNNl*XCi1n4t>}wLpOS24B1A@m~akYZJ!z;-#I|GgeCAh_h3Fk{6ens z!dz?v+2ZQb5Xw&m<}3ijSp3Wl7OVwneyxxBXS3Jqd3cTS4AnbN-apU_^b)Tc~~ zw!X9tRnpC_tb^Ld&1&0EKKZy7(pZGFbm8K#vUWZE&!xb4emHybc`J`*oO8vy zhS=4LrQzj+nn#M?2%W1Id67EqZ4Eoy8@0&D)`WVm7&jBQqn#-*cm?h=)+-S zb1Ut_!(97l-V?+6osWnA{6G7@4S(?O{$Tj|N1qP2?zE8zFZ0pQe?I&VfBZiTfAT;5 z>F~kNKN+0UL*aXW{a$&J+`M^n`1I3HL-%KfOP8*OujSQqwv@Kcmz|-sP2cez;q7bw zvW*?y5RbzkwY9ZbbCrom{mn7GZFL){T;|x?YC7|+In=q9JWF`2n1h|AW4^(^wWrcz zV3-@Mmj3xiA0I0155n)lCqD znOae9`$*fTneV~NQ^dK$_@NAz;D7U}yeMsD?o6liiDPcBZ3+XEgV3oUSth?w{Pf$ zt;_XGZSR@>XAHS~d9Az$Erc?z?L1+;suzQ-9UkOr9OB^^v-U&JEVU~cFL^I7&krl% zTiRH0Iyk~JspSsi!k7V*Gfyd)mzEhFm#RO>RbUO6xhL0=|Fe(|+zgsv1k>)`ZXgMr z4IO0=Rb9A^A2qfZy%vL0a~UVfVYJ-1zfo-fo~_O8;^lZzGPp2a>1PHs#xH%%qrVjB zX;)i`s-tCasoLd|1oMRifXh0sWbUca|O3(BZ3P3lEQ zupC}o9m@Lyt^}_b^2K3zWX#2b!%KBmW-WG2JY4! zUf<2zxmD=*9ef`jj|BbN_oNJ5g`3(q_iF3Jm*F_uD((C#0AILwH?NC zWz+dfR|yY;Hmoqdlh@P-z8%6bMyq(9bN3!z!Ci|{!Cf#YBXRsb%zsRCG?dXWGX4ziKNREs$ z$gBP(gDLMWsYBJGqt@+JUE8oV85M=fqaJcqvi|e0+B5&A^o^q;cV2lRQl~#GOrBh4@MYU>;wXRdLJ9>=AD`+m0Nh%^r`&Fcl#X zSmoTpkE@vfz-*Nug$Tt4q2GS-XHw5oXS8jvin5}v6fxQ-ZHJkjjAv!A)DMYQOm^B# z-X#zvLNlPfCw9Q-zQ(kqZz&U8`nDJv-;MUA&7&m!;#r*w;PSjxp@2~Vw=*1!5DT~fFKXG>_w%MwD#J&DUu2}dP1 zW(lj}5lSh2C_8{kX#_{CjAaOdm*Ob{^J@&&%F*Oe+oa@PD?}eY2%cMUYx~d#84I?@ zdQi$4hF1o!2Yb7NZHk=dMaWSXb%pPYUCJ+IZeTz+7@FX|ak8>}A@qilxz8>m=or&y z0?$Fl83vqU0Q0`MuvkVhu-Ddv5ttZ+OQ{#UJ*X|HC)hbxqQavXqCLce||H>U_rY44Pn(0K?-rzK+9hdic%^UztOG z?~TlS5#6r|6>oh0vLGLE-kR(4_3HY%k1t*iPA`rc8SFXft#9 z!{Re|Q!^M1!?WSh{+(fS5)u+XgAq z{E&Giv~hQ5C-X&krSJ?FFTXP^ufCTuuZEvl8P3fvq#Si?LsqDNX!yqP^wERiO!9jX zzUFU#`jg?${`}9=Zl{Ok#l_^Kp`WG9`@gYWP2V*4=yehnu%8r8$s-dX`Zjb4+dFmvYSAc)RAgd!7@|xl)XLySw}4Wp92q_a)=v zi}fF40iH}8#+RDgGan1i#H#JG&+*s*dwYnRE34ephawvv%Bvf0!1c*c!F%WInNxMH z)N^Ry?oI|j%S(MogamVVbHOC+9#jg8-Ds9KO8>0bvJyq zv!8l3>RC@&Q99{$MS2vjr%*_T~Jlsy&n>X(a_wKEiL4;AUj2CG? z20)8;!0oDSN<%*wA}nOX6SeX=uTyE|F{I!p$VshS6yR4Y*x{M-dHpdqI8QDkJFi2l z7H3OdvmK|Xw#T#;B~KX!JX>4B8)fKI%4=-}U-kF=ob$8JWo#`~yP}KQ883&QFC%OE zSskY~F$VBv@SexMeylnHDL@o&+4g}lFkicNrN+yH&`%`Exm30~G$z%px5{d{MH|fX z_(~bJB2^zAhG2l>;!1bz>g9@m_wK#IN#hVc@)U&+-~o`aQVX`y28`Y-D=UCZ+}>7^ zp%wpTY~qu}@A?HtQ@(9McX#$O*3e(xVre7om`ai%@rri)a6YWXSZD(|uIO^;8>2K_ z1&_Wz?B0aN1BIQ{Oi=LcGo_Zb)U&a2`x+`%hHXpzDetO>ia2O&qbYo zEq)B{gJ}XqpTG;3z89~qYL7%IIF#GvR9@g3;qY5on5>2vpCk9aJen75s|g3dU?Bjy zh5xBtG%{8L?UA}L7`Epm`ffqA=QeQ3zvGJMH^W(%p2E^DbqAX#uc{9$;u#HrRi&|S z3+Vi(o)Y+_{<+KH^)?+NG%hF2G^SkARjP{i>R$h(&%KRv$=9>I({E)w6zNEK^=nKw z)vMp+|Aw*4?EEVtxN=oYzY`j&F?h&zSfBiBy;0}Y^Om`Uv1>@X(=*X4v=Q>qE3>YI zWDb%l|8rr2tDqd8>;HOw6^`UJhHk6A#ur~m^``Jm;=Cz*5%w>J&%tvX4%_3GaUBg` z_x)`R$A+)ta2(#Yka_3)^5Ssi#`WQRgmWHQl)olk9uk<1+Tze^qrB@$y@eqjCf!9=deTCTd zp}uE(RdrxqxNsqixYcC5K_Wz|R`Q&fC-iYX->sVSTX|O6S;dVRaHf}o?)P`LhZmTw zl%?!qs$5~fG4c2xjKH+LLopT@gXDicLIR~s2?fa)!)#@%t=snYcZY+$o$?fu?iDlE z3=SdO850Bn^?&@(7KQfLx1#c82|Tt4Dh4qEkX3U8BjdDU}0G{&H34DI@Xu~)u zlMo18WhhfnFL_io@|)3%VAbAUwt#FVnj%ZykE=Z=;|ZZILSx=ziYY0!BOpE6?`=Jf z!<)k2b)s&@wQxKAsUP)M^<%!lO+^@Aa0R~dn1t^@6imDdsju=Mr_NUV*2?0fTe+}O zheXSJVw=L1bss|5>q96HY<*A)uXCkOm$d@ac-!&u3jlvj zFsCK%s4PNHrZ5ReotytV4!Y&rv!}hyoN)E(S}7b`$;5DeVtAA}mQrti0Uc-$0rbGi z`$vx-9nZ=O3`Qh~0`SLbBdop>2R@GUn2u+DsisoJ3 zG!<=SFrm~t@#0a+wSC#fa1efk!Hc5n)LH!4T+JiHOGY@}<#WUA;`PwN3!#xIGnefj zLtS(A9I}1?=J0R-?SDP|&5!?T*xa~3{LNqg_3&T+H~-D>@BZ+Q>P)8d=S~mz*Y6I0 z`al2K@cY02`@_HaH~(h%+rRx_*b7f{^RwH-M<0JY{N%?!9{%vZ`=jB{|MIVg-7;i7 z9&X+Iw7jhzw{4#-44)Jah1OFn1Ft?UQm(wd2X(ZG~Y|v6#tBAWsu0^WxB6;h4U6w!9QMQb7hpc zdgXH3vbWbOrSu$+K1SC*O9dR}Xo_lZQpoc>D`Q16nz6tm_*uCJMsZH^OiJ6iQ+^ju zTT0XLsL7jA!yNqXyVq+=N&Lo>^gCIB*VXM?w@Z=E&{MlNVZO~8Qw{YmNI_fA)gz2>A&jl^kI)b1yL6Fdq3b0 zBcwjoe(F)Mgx)xJ?&8G@wFM=9TV2c#3bZXa&o#2Ma*aW4WQ#!kQoDTMaaA^H6(4l1 zy7Ziv;xnE~zDrwadwqgV;ib_j_<`;)zB|iIJHtyf!PvBAso#uj7Kfl^6O7K_O*INe zaA^-P8cP?hQa^PUGJ)`l7>-w|3PSW@`dl(X>2Y)_f-`Trn{$Bgu3eYVVo&? z<7VIc`PC)!Dj@$?POtJgj1P`i&r=XLZ;q642HF0ikdSLb?{XudbjhEAi^xr51F z9jbkfUP)7Jp#IfYU0;6%Nc~q26)H~J#2ngb`dddG)79gY$Mhy)dQQ1@jbVD4@|d1q z#ps~t4@1!leGGpCQ=WZQC*#`KpN!Prbr>OW8_W4Z$m@dKy`ofP4@bhA-n|M_n|xjP z>Ri4)Ozr<=*RL|Xsl2!S`iB_a)DF{iZ1_43$Kfpuvx~FC<#*mG;|=EMLI)x?ic!aNj%k?5^JZX=m_aAIy4zsg_}#so1SRA8_$93{LwOB+$zFv#H%3C+A>9@mPuk)cSu@-|tZbm{h^SWrJ( zz4U51%wpOvaS0{_Cjnzf`1VZ*+cG#ign$J$iY0L{Y$ZgUo2@=cQy1e*sKPYk8Ze?| z{7W0^Xl+ppcG_4w-M@2h*t)k(e|H>yl>sxKvGe>1+(@6-Sb=eEge0t%5RowhH}swV zjHNQ%14_y3Iak6<%ltfai5!CsQ5vZ+$pqLaD@-XP>-!MHRioHhHQ(32?iUy zg2&|@8NA`~#k1;3@cT)GVO|it8PSp+uYomr^4=sgQ+PSIZ((tHSXo)knCgSYYnzn7 zSBAP;$!$zMsd41ovT4;O0lWpdKI?-*l!qIS2JO=;np?24r79Skj-9GAIQAbtjPU(n zI30MFE?fvqb7k~3R%~e6DYGb3jo0&Y6tax*twf@f zI1ay&;Vm(IdHAZ!|Ng%C<<<2~{yJ`l&!_%k_^NNh(eK~vYDL8qruSbF4x6z>W1%_sEt_HsctE?>SlEH5pE)@3~BeWC=G=jDmsN}8FXH_{sS3c*M4fC*_y zuvllWw(0x$c#UX!@11gc$af?i{V`;ozJA~7sIL0pL3yUr_L>hPA}$n z_?&r0`s5fM0);q1lrH=TT6DQlyBs_k&Io!Yd*>JGCJ#5~;J^aCc z`v=3n`d9y-;U_=&V7PmCWBAEWe>VI$*Y@`A@bIz4F(-!Gch-lW{>Kl74?avgr2Tl~ zI|piazdaLd7l-zv^LP*KWWfX@%++hxik=qNa`N=Zvox(oUu{WtadoBm9ZGxi0Iw?w z_e*vz2tCH*@cu2{C6}$=cyZw0@GZRPotaY#+2k{ofsdM$(iG<6;L-4qw#Zw*w^3d_ z&!4?4&m~3yi!6F^MZT}!Pdy$F7nYaG%M6|{0`QVxK)G{wz2;8F6-sqyjWO_1z?qjV zD%(pNwO7&e;Y=A@@z|7dnd#F8$^ugxy>1Ne+_=$(quY1NFko>hRvX?*^7r#Wz&F^9_HAH`k`+-GmVh1lpfRp84Od4(9TW&COwb zBmJ+dG{$NO?b%jPh-Tm(m#0EGR7ngT;f4=!8vdj zS5&i%As>D8ao`C?mX}5^gb`Y~X~EyAGC1+NdiZEOuPx;iUlo{L>VxK}TJOft{Cg`^ zC&LKuyr;!WFii3KQGhzgmzO>IXmO76$TRV#fSR@l-tS?q!U@A29GjEW>4R zSY6!V6d1MJ{Gu}&XG-Rhrr=6F8A+vuqv*PRaW2~Z_1@x?p?Nxcx;(nl&Lzhst@G#b zq4F!kblQh;TpL>GB{YxOa-Pe#R+ck<;>RQcV;5euC1MVIxl z^AOE}7Dk}2;L(@Umap=(=uSUt8)@M@+&~N9A{wIa70#2*xz_5TO?ihtdi<=6ceT|o zn1koa0rXUZ3gfLGrXPLpIsNlN9$&cXeSepx)Aju@i+)w1>2Kesw4VCjWwaJVex0YZ zm0#YK@j!o#nNMZ==)Jx`Q}oecT7Q+Mc@^b#>dv?Bt})-b#`thfl$O&OT6&C3>4eHJ zzZsl+zUVleYlo@5>N(eB)DfmK#~+9AHc)=K`xvyj*&mj4AkKPC@74w#5PHUA1q(mj>>&@pKAc9^p=ef+6KjAuLR5Po54LepU)#%mGG3ps@C2;y3dVdNID{ z(iXHCR49LQ<(rAL8A!^SUZG=B=2`huHiG~Iz{87T-nK&X?&o`DsB)}8 zF#%&J2sL1~0+4{^d13_HOC|M*(Bq(ZTPhyxS>Z^i3&Wi}5VI19^H*nDjSRT$+c0D% ze@woE@6%{yG+d-4kFZpQs7Nkb71=(BpzUf8D*~fc%eKg{;xn)lChM|-krK{UF%(F) z*63{%d!-$(HcU`z6o#aXb7_0Ush7AE8v3r39qB9e#ztTgYlTi=dcqL#xK~70dtpGs z{5E6WjJR!5y1%RnPW+?=dt%f(%vcGV$>-j!_2I#`1Bs8ruRK7lwEwd(p3Z_WV0azj zhkeu6#mtUsy67P*ueGNh29j`6v z;S)s(ydijRZ|@9`9y|=L2fqB~<@Lxa&W90bGZx^vb8#eqUvPG2X12yG!?CRm&sb#} zoIl4vT}*c~7`>t{6$~tU2m7U9q=c%ic`{z$du=}xnm|dWZt%XgSW0}jYfSPk(1z*& zeq*q1fVhiU|9v6!D++~Nqlc6n(Uy>n8vndlRz_op`L8@xrgB5`7~C0# zN{KWnFH-2kNBhH_+n){23w-kAVbLSoklBvR9BJ!UO4Qn}YIY@QS9A55q_za)y>4bb zb%t?^5$o}A`_m7H^}BaMFRUhcQLw#y`C!=Iyfv(^-we&&9k#YNhP}P*;q)oAzG)Xx z3k|aMn;Mo;|MXnm;UAn)xICOYqgI)}QwMGGG zKmT9;$Kj9u@DGQZpMEy1-(Mg8_GcdqyL+Ltv&+fX2qclGm zdcIiizW@FYhRc_)mZz?>lAOo7w0vQ>a^+gyT?ilNESsg_@|DZOJMXbV_0xaxM4@L)h*`5#{pFI`6ENxjl zbl^TW(*^0%ALu({?*cEW#)7MpS)iVOTo?6;E+5wxB6VR=IO_+!*Z2zEotDj zT_lW;%U9Mi2Iq@*iBBGDm|KY}KeC2h0F;eJ+A?}NZ;FvZTaiVyZHJd-5V>?|r3_YT z+y)qnq?(4p!`;38!M1#p;u$T4r_$EhY$>xBCuW@17Sb!h$+?0D4cOe;%s2_2qg{a? z+~u{AOPi~czSYaAMj2}KGeal*birp^rs~&|8Dr>(cHpJN0GdcCGdyYdJaQEppr7@R z@t)5GJKC-d&Yy2yPk-7fby5g}4Smrzr8pnkL7m}z$=GRod6a=XdBD4qq2;_LQ+(BH zDPu?7wan^9RPdy$9Qz@Sh%@e4zJo=hK_sJOYsLiH#(mih8%+#~%w z!sQN*DSnkV-u>mFo_j&x=$%^igDAe`rp!v?P5t!0H~lSb2*==om<8h)rQw~f{7(Jh zHN2P%Px3Wp=xgXflz}%9v@dupdVr5brvfK=P?>0@#fEe^U8nYpo9bC`B-HPEg_5?h zk6v zTwOD;&9d-)%C6@wwi~a14j}BoTq0m)~Ha$`fn`1!u0#~ck(>??e*)I6OQI~H20&IFx|h4FyYB@`1OSEvi*+@ zU&rA%yk)_eG^;nR4VT}!Q7ewa{nmtwp(w^7^ue|!7^2#WArl;CfiP8!4kj&snWk$J zb$%9QN=>avM*-X`{YGU>;+8;|iQeQdFZoDY3ZC3CPG%wI8Uj2Rl)~u6Q;U!|H#?ua z3I5I$u&4OR;Yl$gmw%6&jNi!Q(WAk!(_%H(cZN5#hH5xhKguFVhC@Rv|KA*yfP8*ON!b?q1(% zFlOL<#uMR5pSbI9eN3pQyllfUBQgb&^RgIPc{V<8V^Q)k4vkqJUghN{yS%TwAi5jy3BIELT8RCd5r~zTymOKoy0;QcTlAcp|22XjIQjnr!JA1q3?d2>L zhG#H=r4-U5UK6s>4_>3SwPEg7z02oW+M#eirJv5gHEz%}N<_x#b9p8_J$;t)lLzHa zM5ok`VAp3H67+3@Xv?BA=g^|$miDxA?l}BLgzwJqb>YJAnWH{;eZ!EUl3=udRrux^ z);#uwtIK)w``6!ny9N?5s?1Q!;nRFZojrgWnusUeYIJEDQfcDa-J)6dG@9 zKZ;#jA2JwBc~RJ!n<%I#+IUzn?3gp~nHN@8h8s7om+=f=YfjTY3=2Gp^f99+&p`@z z-pv%#wpYA+Z@tP~3643l2nyOVZF6I*Jd+r`7{}o8+Qqdpj8TePM6s~AQ0JX72=Ml| zEh2>~gA#+r&6~GN5yi0K+l}z`@R)ZBzL?RKCk}P7k`n)m`^0=2O^~RrwLxw>E$Ro~rWB6IiIJk28QsEab zL1%?MdeR;-a^KRny2ktd(=bv5Ii0Z3e)jrc;_^chcZRJj%nT&Z)oT7Eza$YXFsI%R4fUK{0E zk@E3QwmDRHW0rC4VsPL1GNviV8On^qfLQfW7qSYr7ftBCa}F^NSjMWzq3I8o{L~vQ zz@Jg7Gc16swj~^STl_FXDZ0Xg>_WzYbhQm=cu}z0t{d*)Pt~{U8NM*_@Py_P@M$yk zEP1bRf%3SGbBxC1IO%*RFTw$RZrfDGY_i(3lJU$-Z9Frk&k8{3|7P-X~e|z}I))6x`+E0T+WiXpFKL7erQ1hBRABqAlvgAgV2EVQJ#D zp|uy#X#-;cJOGt1Uil#HqD^^qf{~FJJv4@WfB4`@@Vh-Y^-&oLBbds+gBrP2&FY%! zH(mYt^S_1Hzbk)wcl7E!#p!r{zq)E@`@il!Yl~OL5C1nmQ7P&_6R@{w_k1W>O4@uf z+A4j~g3)DvtjOgoLB<3J1pDpAY?8*%B(d76}LU;ZYwm zK?gL|ZAy{!Z}1a6g6~yt>61oTl}0{QsQ+FC zRZ>5&7$ari%KNIb-&30;e~X)nuI78g(0z=a7~}X${of1A@qoPA&?|FQ8~fBt0aMGo zjvG@S4p2v>~V8mAQ+ z_rE^8g6VAu-wf_=7OH)};yMoBZTNMz|FPlgI2?z!DP;UFMsT|RgZGBj2*`{$6eQC` zO4z}mn>hvG1$dKBrgI7#)zVPVScfMjhUIzV3fpGSu%#Tv8{nHfrGIo{alm}AR<@+uZ&_T zi?@d@*d9LE8=gFRK(kfv0d*>ZZwvNeB9bv!7{V}ZPapNFKXp*c4Ko7Je`@gqw$nUxE_LmPSgs3}2YrYA@}S_Ez6wc+y^H@>@HVU>{g}`w82& zbUiSO`o^&z>k+uOH}(eJaL3`h4;W^KT>V*F@T89kGTpZr?$H<>oT>fOBODYf4<8ds z;Gh&pKbMf1dykz{HEtQYGTLjbVtmmB#^2{hPTzzE)ROeh&_Ro9mm0uZue&q3O$uB=DQ&Gfp2pI;e4e_3EYCV$9e^L!~sAnrBajKG`a8esN`(TfCZi|8mCj z_2Jr$_lD)g*`&7(-D2q2Legc99L|Qm?hNbqZWjMyZdKli;o)%mvk%I^#QWm$gZ<%? zk3IBmG>`SSRAks+H5?o-CqEtj_>cdm z;lKTNe>D92fB(nB!T!U*b!zzd)0_GBj`htiki^FltU49;lfgFJ;*DCf#%_XGfR2?EYx{Dyq3^lix+0johhS)whzHfKRix* zt=D{2yv#_~@l57BG~Z%}gXC%M;-$8HVWoIUUQawXC}quw3`3X0-|{Ha>Xcg)?aH>* zAI~F31@qhK^j&Rln0Cg^Y;5lg_wH^~c^5*vuU)@7T)B3s6!Lf|ycVOFix=AE)Qi!} zA|!Ld-v0jZ(Z`<*pQJsVMaAR3jDGWT1se~qk3af!xO4kn%6M8zJM$wCk1JQ!3Qk5J zigfK;i!~@G!_#SVn9Os+7KeB5-49QSFLcJz;&A=i)!->((Vfhd4@+siFn@kny+FCn z8|z`x&h&X-S1%V|AaA@ggRA_U8)SRNgZ<3!$=f$xAK;o6S@E{QUs@1F31%Bh^)~mW z+foj1$5Um*p`1JjzikL!Tx)|VrQhlB);qfg!v`OJJpBBlo9P$cT;}%1DLgZU|J}Qr z!~S0Q*`zTqx1uymXvXfDw8z=A_|{&%Pl1a6=S8!UI`fRux9YgLwKLc@unix!_dK1k z8$8V)Wqd|UEr9XuvzxawMz^ah-&_7^51~3o?5TW4Pl3Rh(OvUCxy6~hbsy!ZL@9o% zl-CJpPAfa%G>`RXHI^5HAB==#q4o96;Lq)}NAk}Fe=Vq4y||q5cWT()*&OcPxmRt5 zu<(2^wiuM~9*nt+d-{xbAi9PJsfBMrdWK5!oiWEi1uwOWt@HNwcB^jF_Vr+7gu;KN znpM8-_==wkPBEa`y0f<{v^^{%2_EW6!O~mUW(?xR!ZSX7`Z#@p=Q>|`qpvIEsS6hZ z?`+|X`0#%#efH?#lY$dW)d#^z7bQAbtrlQ~zM`}8((Y)HJ|kB-KbZ`J*E@AG{9E9V zU&*I%D)ont+V?_m##llZz`#)4UX5+g!zWJk3m?f??48Accuevf{L}y7VNha(t+VKY zqvjK1Jp`}vpSDJ2z=OMtjtuy=U$g}v1E97BUkXk=+hFiG-^BHP+NDGLv?9Ib0QDy; zf2mwwDMys<4UJYc*k#dq>VqiZ2+^60tJqO-`PDVyv-9yD*2VKVX} z`M_L)My64U_N%XLUyXZ<3dCy=+wiI$#$PGY(|^kD_MbwJo9QOJ&iD9z^peNx?@GRz zevkT&DR`W|`Qgi9T<`jgPZi2IlDm3>6`uPv4skKZeA+0G&!)KG3=gZ;0q6^T24~Qe zG);c1`?zo=ZBaQ)g;q!=HKuYqybigV!v86L!>${1CnJvET-6r&)Bcrm%u7HAy9VNV z_PNv5^BA%68S}z3HQzMph_3gfxI{3oOk-0kq2!yp1rI1`J3w2&&u8|MjiYd_GhwjCBr{S6$n9 zoLBu#yZT*nAbF8astv&MMl-b{LsHNCBfM4C*uD)x-lskgN6tyuOe^oTx1X7g^Py77qGI|AWay`6#y`8@pMt~1L`aQk- z)dwZL5v(!%G9l5f$KmY>zwZ9P!5kaDj>B8OD6=oFmXLhfHiuwf_)C2#zX^W? z;}?X?)U%9yX$$eH%>pP!kI-j3I2VDV;GQ`*EJpymbookoyH(t@H(|`G^7FM)sfB!L z4p%xQZRgpF3<8Mu%j<$idzZ1KRup#oFf5*o5KEasfGvY#@)rn(6ii?&Wk%xLGKRs; z_A7U9-W?w7MF`UL$KksVY4=(Q7pA?0-CUUMT9KT)@k0><0i0DsVQ26$6!F-CH@yv1 z?!hA-Q3PM((Q0&xr5f*vXM9h_VDC!69+f}5CLbs5b9qJ>m-mZ|sqz#}*^F|hBNzvP z3bs1WD|j?B8(f}s2Fh%WPs&H*H6;c|mEB6ET1}m?!)Rs2I4}r3#*`J%>S>Eaif061 z8oxXn9H6b^OQ-H6(>r}t?{Ix zltsBz0$<83nt9q&3%h6*g#iO3;bJD^m%xQqQ0hE;JPI|(;cX4yt;g553@zYJ_piFd z`Kqhqjk%8ZZxZ1AFC%2sD0aGP6n%Yo1@r46^+_JS%IQ^Z{iYO5NsCVLEO5rkJJ+vg zUSF)OPVpBMcZ}PVDij&EXFW5sko0FOA7wvzyi@Z&sO`HhU%gshR=f#*_P0MN1gxcTYNhQIykPlw&zouci#yIaGZTb~Yp{TF{Z{K=pE>F~ja zKOa8*^wZilO}-2fyo~Tx6ujs*rS!${H_J=523#4gUcFYHN4vY*RVQsyGGvvZgH;op`ZQi!<6M*tH))maPC-b??(}yI`a(V6#;H- zX&&Y6F>N(CDLENnca)JV|8a#4pe5U>6*;_O6$iwH58@fH<19;}=&IRv!>vI7PNNll+^Mq_i zoQ%t(ZgbO^VDRFd#*5`#c;4_lft5EP??8O-t=o6f{u?Q$DF!^S(9R+`MFT|2VNw~vvX#^SMp5S$+K@|_*$4RT(RKn?!Ap+J?-<9cepyG z4SDtP*4YoP8&}(#yTOqsNl#9rSmx;#IFoC6<|N(9@`duMR1QOvzCg2z=A~Wj+%PS? z+fBZE;Y;8tKEDD9PI4N)3x&szF&sH}&pQS&^wfCv%_6OU zRO1x>!*x3cz;At{Op7xae;5#z%`lOuJ@AmmE?ybk^WGM%+Blh2f50bv zYb)eicGh?0xt0r!Fb^4n%CwURIJE8LO-7#39z{pZW2u8Q>LV{o^2z9oJ{kZ#d?AH- zj4`Z?H7UQw=*Y)gB!Q-*M+|38^BCXSz*$>1K8oCsXYYGpxeKs)3`ZV?FQ4~2`2PB( zU*7cIHKyvn{BBrYV%w6B8|La#RoE-6{=5=&RKgw#%PZ*n^ zg2yf|WhL!lUMUNnOl21y26v4QIMnePZsP%cCE`vpXs?6m653|VZyiMSM^BU7{_cS zLHIz7Fj$N>d%HWOgt9f8tkbLozCHO=LwUryD9&<`@zqoQCLh@3bO*9h* z%xY8h&}NSwMvzGSXAz97au2%WCFU>qD2TB{B*6JY?AO(EZBVl0-hQY(g% zzjPF8#h4{6SO}u=LdRJ1o05n@n9&-Oelkb_KW#r`3#Zz`Fqbpq_7m56UW{v$0mhEe z2_{Og5~6}{@TZh0!Dj{_t7qXH92W=N#=A2*&t+a6yBRmS;qvo$W9C*~}#+PWssE4*IV61D1@G34`ccpJlSh~aB| z_$35WXooM)bYkuguc9(X|2p+AdigIyuIf`){Z03;_&XxhPnT4kWslRTUj1zfqoOeM zV_F=rc5!vMdi824FwrFAoD$hWnVGW`L`dh;;dGvp*>JFTXZYz~|9Re{y(bfIH*|v0 zgwk+!Sh~Q2XCXYn&akz$p2Vkzm5Wz~nc2(3iBpTAUk>{}nRlz|A38)S zG4$5QwJ0HUsSRAiu(SEm@RPs!pUaTbRed__Zm$pj`G59*AO6kn|F^^4dt1XNpWGh) z;xGPc_~g@1OS!2|&ffaLZ~a!T_lNhs_s($X(xqDPf(F{E@CQG5fB3E6`ayXgQA#lu znOAs$-2BW|bnC+&9%}EPl-#xo6i*y9-R!@eV?Y&`Zd$-!}@uR0fhttDl+ef~0 zqYSUM5WaQub}6LsVP)hC?6xZG^UcCXW}aGHT(0@jyd<5iC(TpZetUbX=5+JRZ00=1 zNCvs$-!l#SvH~9r z3_rb??L^JX6q8_<*XGvtu)p`9&f>at>rS2JWjn#$-S88Sds}5e8F*<=cmU`BP-fP+ zHuk0~-|-jbQ|-V&WHmZDfRc4C_`{H9%f|Ke2LlSYWde6v8A}n#3w}m31CId)##_dMq7C7R&@%9$8Sn-EID72; zT==YvCu703my_YaSkuN9_SG3zxfth5{z{#|ubseZ+>xEoLj2ccjFCt4G=094F%D-b zdR^Y(6O~C8)Q2U*}1}&$Vd)&!J zJY(hCa{!vzyL>Q8S3dlhz5fjl@bTdscj*XRy=KvA0{sv8`@Hv^X}wPs_hsN z_xJZ|Y?QZF+P==~GDhpNFk+O|jhoa(ut*Hd46{7Uc+0>oo@KpdVt&*Z%g9Pw6pp9w z>wLhpUCHh#(|AI=o&-jC;LJwhAoC-+6Q2$L7(Ja=Hk+}Z8d6~wK0)VF>N>Y2SDUhsr{E9#d{h5zU!!cE0S1&r^*@MwLZ(-(mE|NxcW(Je0zrmpl!ZYE@NKFtnS@M z<3054uz%dg_?2e7>UaLeD)##$&tOAiI!)S8ztly~=9QFaY3BtGtIZQv`!IUZH}x4` zEt@yqDc~0i1wviQI{N$Q)o^^qx+LO0UFC+X#tj)7Szt5I8Cr3DA%xd<0 zIu37N_|6SqX!g;+ZxRgQUrH!??!O*^Zw`U#bD#3Viz&(Bg}A)_?yIjaWaB^Kb1%Pm z6%BhWOs`&jsfc6TzMI?7C*BRk-(-B-l8T3qZAsCi<}E^p9`Jsq+_M-3ynEB?CfmU{ERm^J(KIqg^csile3{Er(O(6D8yl5FiSU@d4VtDyv_~U>72g4uy!M`3hx3-3#|NNujgP%DY z>+bNgpM5ZFZSme=#CcqN6eAG&#@hnDT+Q#*+WM@w3QDdizt6>a{|E1v@s9z8*U|2N zZxOqjdRchD5E1fT{2UmIhe#f1EM7_*ZQBMg0Lwr$zjK3Uw2=W2@3_0SUogQj3To#S zUAuZU?Gt*Pa`cG>ROm6@(N=;CN)JLyd5l<`(MGo3dbj%Rlm$QLAKNviMaO=nr~xAw zc*vNeD8(#%;&ElZMB}w*d23}3!vA^C8;h65h46Z5?K-E6ry5TY>G6Emu3jonDqdUb z_qT=}?Nq$#v)b-a99~xD4vPOfckU#Qo$z?Jdh50;{L6%(j~Gqi5~G{Cn+Nf-(mVf& z(%nK2{l_y&xi>$%nLgPWmKW#C2uBI4tm>!Co3<~$xO%Y`QrR+YJ-jJipMjGh=#!5> zEu$mc$17Wi1)q2W!eNU)z~ycZGY-_Rw!b!3Qa{_UF*Mo=(fmuvkN+s+Q}M>9>nyW- z_ckg|-rtm+7Nga9bx+fOk9$?Qq3KHZj=>AcaQJDQf+f6YV4dngi3cuosD3?tiWdqG zo3rIPr9I(X@yyAul!qo^xSO;WE-cjcc0A=M?r-0^Q^vSbT!u%67YrP5#aJo2k<{o0 zSSQ0z)m0m&ZEQ2h1BPL^@HIFkKi~0W7Rtemnez-xd7nC6y?P~ZEEn~yGtw9%o;EBp?z$l z$G~2=mT&T(ye#F8l>L%X*j7bv^hAmH#mCh%HGOc zU26;d;CAH|{BTAaT6eH}P;>we)OPkG9cZJ4@ew=?tpuDbfw>p_0dQ?{k=NPYAp`Ca=?@9MjEX*a(;ciM(Yo9HLc6YS`( zXXB@J9!(PiRDaKNeb3#T*5j*nBMo!IJw3yHFT5KcD=*(<`6_;11K8L6sIu$cdDK1S z80SS+leqIs`jlPedoeb3;cEVB;Vzua*le9emp#GzDrghmJ5TbNa?vr18_^)qcg!bx83KAGUn)sYV0flJ;` zGj8is($u?*OA8~xI40^e^(7kd+}OaWQknc0}l6L=nftX!7*UBwpSWVFC!%gl^vn zDgr@ZrWDFnm@!t_qOJ2_l*)(t11F}d;cplSpbT;q*W{hMIo59iX&sgvL3r!_`mndP znMwR%#mD3m1g0rjdth>uk6|TvD8qJt^I_t7%UPjaTO#E>L2~{6yXvzpJm}*P*GJs%kR(Zcz;R)T;{L(5&8 zmd97Vqi5~4&`LUrz81>Be!7JI-mW$6p1z{2Kr@fSTNS=z!Li_&x&6=YZmsi6RT+iIST1NF}PaX`; zT&lBR%6p3u>(p@ajPpW6Yfhd9M#FI8Y|7gme)2beR&)#Pm^qWUrx-pS4FCSW`@`Y? z_<#C84?p|aN5wBuj_z#TA8vm3@$kR=*`L*xe6w@Qp?mFNg=SGy&RY<0zPB;_$N%Ja zhJW;rey6riM$d}2rJR&r3S)ekZL@SCCFW}Q4;}=()^~PyN+~*dKA>R?XpAol3ly5m z!)o{-=lf9npFMxBX#R;4r-x^u<#-*+{FRjz6%L%d6&@5%<^A`*|K4!@`qhGk7lZb< z*k^8bzF@MIpRL%;UDbtY19Ts6gQjPqDx<)eGbclzZGmW>vsmg`c^C0$+ASj`?*nIG z1umsQ~G`RSk*iCBO_c|?h9!IAlcA?Ic2Kaaw#?aWqv5kpKMR~^%iD|b6&&UkMj%`DS!HDr6=l`OAAL65 zxqYkVPm5D-es(K7>*lb$v@kepuG%5ID+8bYwmsVX!ujBAuMAf={4hkp=i@c;nLLTW zrmX$FgMynURgI_gIo@Dv8}IO_3@W^ucor}m=tr~znxK+hcYk(ZpJiY zlZTcq3T@q|T>bv?<+I@1$ufGW6C+c3rWLP{a_|wEU(LDl!cWYcJ3U;yXgkm4TKHqT z&3o&;?V>&?BSQKgzkT+MGtQi+SDbx-L_$u~)_98<3+ies#rr%WEv!pA{C!m^FiL^d%S53T6KR9=_hghJd)OM$cnw+>U!_e;R!e+a zK;F1S>$l{AG&iDgXA|dQxqOk12y#2k2DoJfMHmRxLL^3BFm_ccu*T+NXB6NM3k0#`kyMdnfolUo`f92tKB>@P7>2+MJP%{HK0+ zM7(q|uKLv+RekZSVAF5p(emIZJWl;mrnK75SZ5SPV{PU5VDvmgH_5uKjPI>s8Rv}G zGQg*8$mQr!8NNzJJQF-!s_*)Q0grJ~VEogcXamD3PfmEk>kX{n=`$FY3NN2M?QIoZ zn!;S=J$QMMF{*jrc-{5tQIj^C{=6I8q=a>?K(7W<)yx8BSOEEzVAs;KPsEtQ(m>ilzAJJ%thewY(67<>0>mYjT_yTu1f7b zX5&_iF1$NQkK;b(JL0vt;&p=LllK+R2XDQrvKfKA>-S^y+`1ptQJCOTHRHs1sj-pj zCZ{nG`cTmmx-H}(PvuuxRc7!rbO)ZAj~K4tyLN43jsPC;cHYv>oVAF=8PbtEGar;; zxW;bli@;nd$29#5-r+y;&Xs3vSsyFT7%S=h`Ji6L7P`hL*H!4bOj*xWTDk%>U&g+v zp04M&BLw>ZrPkH#Nmf3Zc`QUM2?yZ;^yBN{i zgSTLZx9Xa>)i-0Pyxs)E82VF}{kDdqZTVH#uPVH$tY7px4sQ-`YO7z?^?Eoqd>x15 z@D_xX>z9Wg{wM!zc+c5hVMw24lENgM2y-Nqt9K?sOcq87gCW$4rF?7Vr5U7}jQ!== zBx)kWY*bG9kI+?~Lt$zOQ3TeSTrp!Nb-dz));vxBbcDS2@Cp}BCbYdcyYoj1B@}mDCG##62CO9kP%75R%x%ayja(@MRq?B9)Gu8y@TJ@}8F)izJbmv9XZ+uYQ-21O@c zgyHA)YWt(!dc}We7Mey$N8xesC<1$a8#{!t`B~?2%w!w~<{E#-Bjp=`O1hJS6~bi* z%ow6bL}Oh%T+yn4RNfA=^Rrbpg(PG1ad>OOugCE9jY7>Tb$zomQ~a+8pZh$;e?3jl zl}E#2tRt_*`PyqtP)~3A{uS4&!u%c|UkmwC^g;X@*Oj)vOrgeL?i9DYMR>9vWFB8y zUZ`yV&z-YH*vhc7_Rg@l`pz)7aB;AG6D6;C(YC24PC9!l{L%^A+hmM~CqT1GNqmAw zRp#+0+rwY|#Dhn@m?CM- zD|jN_Ar!}GE?#tH^}=v*bvf;03t4l{sbN3q(D+hbWv}Yss zaja9NNXa>|1+mSh+qb!OP%-|7|ZOTM6<6;(>@KyLIPIwTpJPC7-$ETD~)~ z;pO#*bo!KW0B;KyZSTnAi;-pZ!eZ5TH*qMs-hJo#aA7%faL9bc_%ON;2)!*EfgtE%i~2}!K3cm(ep#wl;ZiRrpfp~Kh&#v zB*w(+5ixqD){d=nk6c@wU0h5LrrMLm1|eh zm$SVvGCU->Z99)2Q^!L3gfd8^edN=?rDqev&Z>t{E#01DZB2L`;8rhquJb z>ciTSG<61xdK*8=Kp%SU>T-JlWMtWt)A3rqR6l7-mVapxsqX59UcIlWz=i7B#42^Te440w;W1 z$T*NKgPlbW@WUbmIIMrvskVL1UAbVW`5nRoX1sYCe^roY1N_C%IMMl3Uay5Wz5B`_ zdZn2z|I53d4&Nzn{Ee1Zgd^$N2#lVEzKk@j>Q&(ObEg-i?Wc}o{>YO&>b>$iLK(Jl zO}ORqT(U>{Tc3L_TApXy<<|S)F$0hV1ICvNtv5a^6kzg(hqM}>56Uk*t?%`wVe;Hb z>kc=~gXR@D4WHrrWDxUiiu|hn3ED8B!DwEtWX-_nUW*!&uY8PY{0bVQojR9>r{R}g z`&hs*S9y>D;q7DTMxs)2X>h6@6EvRP#{9-_6~AA1ALYUWc&C2oB$#}t_D|k|@!K#? z`E~obO21a`a#z3UIhQc~HXlv#>hf*8rr>?u$N&AD;!iTGm&H3-kQMmQA~c&9rY)`U z9q9K_L#0cfxQ>RYye|u1_xDR74pAXQ zxHIBVT1!jFq?kF6(M=xm!mt+;kaQTLRz5@s$ook+3NKcKhaiqAX1K9M3OGTD3BufA zA}GnH-vxEbRR>%DVaze>6gjo^M3|kYc|IA=dIobJ=G^%}Jm3f;RzX_bi6NwbpqwXg z+M4iG>UTPE&qjzk7r{yUJPgynv$a`zLkClOW9)XTSfnPv9a1V~}~~)N1a)Z*}gyyZ468yW4@MiZ~8$X`qWyO0*1MSj^GYFn_=u4 zw_tMah?S*93n-p4P|sw1%?F>+frZ7T!Kz_+)@2cbtp2q<&hru!jBi4TK@PudCqOQG2?^ znRZ`Zyf7@DUnrP))iE$1hqoepXNIrUm6hLX+d>~{^Km#x#;D!BI!|h2b8EP`da2Lhn&ZtuadWl|Srm+=R0-V67nXK*PdJIP)4SwFNVF$9e5se+9Ds@rtzlYeM1?}5W2Fm93J*$^0GDFO4@F3`0TUW z!=3f@wBbSVuXpd<9`4?|S4I%@9{&l^81yE^9}iz;JLhRRd0o21Yi_mLz(OTxi5IoF zg8{`Hb@SHk+R{=R`<@xS3>~(yRE{kQDaUzoY;9~6jxeY=AC`fW@ogC9^OV@nDZH5;Vu{$2N(r- z2wJd{R;V_`H%&$q?SwDKQ|VXrrkuoIXx~d~Yh~6*6c ztLn3~fpV0A=i@CY@J`Zaa9BR#JbKt$oYwY^DGM%8oRZyIG0hm>Y3j_f{CUvTaw!?5M5sDW z?J~vJKb=>P->JWf9#8k_lGoASuH+>@p+Fw5{?KhI*2Jg3>Vs|{ZK-TD-B{c|U=Vc1 zJ07lSO<&Cm=uY{Jr5uLO!Ssgf?{j!leP6$h!>>1dmwj+-_&N^9;ny5ymga_c-hY3% za^rfWw=e>k=m>-+!b!mC$#0y>@*e|=hhnJm4Z~y-#l)Nmfo=n3W~_FC2Jeaexpj4FhpF!<%3pZC($wtJ5$=dCQWb;xKKGl?f3ldyP% z3Ce4E3zH!aZ1z$vFBM7{MycdU;4EWY1jci-Gv$TC(1a0mzRzNW*2M)%{0PBHvqH@l zX{pC-g!+q@Y=bnPdOoWyiZ(ayhk@E3o)Z89pY}SV{b;fSs}*;(QaQ|}_NJ)E(h=Yu zMj+UaKtO;zpFGzttqs?&UmuntKw}3f!krsJz+%9{bsP$exvIYsT0zlFmcG(1%Bn3y zv~9{OqZcDXzF~altl*Ad0$yAYL0+At)6V+d`2+gHYQj?|&eXx*+xPcgaazaWtq#TH z5`qcz8Mnq;t=JE4+hWLAH8$Z!i5Z1QFN?|5?}QAJr}6IDwlY@!TZIdUO1YZnxr`a( zyvAhmWAGy2FDxw%OG_(dY$aeDr<8=~4;bKV3GKm20mDy0g3+dUR4#l*W2}-icAOoy zyttIQ^}*$g+4t_=sj-BH?Cb=}mWHL}mD-|48Ss}(0ABf@Kj$o!-pUAF zq_`-Lxo4Cu&uVO=Gn5__#DpYp?(A+CjP{L}X}1C8$;lG>8S5z-ltD4VFoy<(%4M7- zf6BJ}oy_=hHkoj+XPca37`}ur2u~I1wTRz<7Qd9F{yQ38PdI(| zKF`YRr_aGqZx8R{cPuzv zx0U&MA4`>K`RQ=$vk!;=^Z(`lI{dqT_x~&Y=|$$}JGVa@{_@ZNZ1}@J{O^aK{KpT5 z`|I1eHiuicZkKVZyim@}q>QzqQRhN4mP4nksAsTe^tu$Dz?od&!52`zoBPr7>*48~ zP2(IV%I&{R8S=Khj=C|-QEuDD5C72Ho$)^9QEM>~kARt?=M+h$&`vrF1<)*X+O}X8 z0O8*(T2L?Lqk}~wLkFePr?cl~+gNq36>G}j$+EM%Uvbg@#qdy+(Y$<$&ZSe#CE5XB zH!0j1P}lVsX)maND^(3*5VDrw8R3w6=C3d|bng{_pM`3^(uG zDQ_xX%-YHPP+kvd6NU`9WI+ex3?qbvM5XA;wYV^szPntWd0^FsykAQ3zqn9~vfwJC z3Qs}#nXmAZJSi@&t)`F84x5|7$IN-=DP?J&=Jis>()=(NoH9>qL-RL7Re5xs8x5Fg zQ%X@V@^sO+71E!@XTzgh_*cB6K3xpY{O-H&mI2U06ue`dUlu-HTN`J{jk7HSSkkl- z5D&1jvRdV<54@nr=kYc_+unT2M@LQv{(u~~oQKqgEep2rtKyx`1$p3tx`7uS;qPmn zO}_Y&gTRHyF2ixI8+K7PzA%;G#_ ziuZeD1LHIK2F&VrW#G@yx>I&_NIe-V%NUrpF+R7qHk0ScGK3k2jKqvl8B)XU&Oy;0 zURJgcG~S8_NuA+4I!dM!v>m?BqCj|IEHiTAd3yWN;6@VFSyGRl9x6(CX;PlYA+m}Os(FE;Mo}w9d zjF0FL{AJ`}=vRIju~HfQG(6NVcy6#4PLFM@!um1bCya{hd{l2dv;M7xjx{G`34i)6pZ(ww#O>ty4G} zAcS-bLM_L+rudQwQ(pSQ;tu)<&*Jigf``VFxmRDqziR(6z0i0kANO4KvObOXS3hcO z27l-g%opy?a-NLem3gAeulpIUHWtEpdMz5j^g|`xp zV`FSfIE{{3@NElZM%(g4O_^0M04cEGa&?>4Z-3)>liy( zQ2CDE#A7VhG^#R*B}h z1naYeYloiq_KfEvAYQnzI$T&?8O~s|!pPSO*R-LtkG8ir2V22~D>!T;ZKqt!qZhVU zDQ~o-DJHAhD(S=UTPaOZF}E;3tX;kwLG0?VxV#+U%f9JbwRM{_B5LJO(i2eBhj2#8 zQ$cb0tA5N6%$`8NrOeTu`CR?Q=&2nkRnDcZlor~q=Y$C0grVf^9YIW8#mmp(;r@f+ z?(OyAV5henIS#)eA$?~Y8-H*FUSoza>BdAGy%}g*SQp?HBa(OojPii2ts){g@rukl zMkGck-d^YdCBVsyui1xgDdLhR;fOK-ehGvV;}*WdKZ*_C zjmuD!!prmUGUK-tp}|RK!ckkO2gK zE3Z@C8VhJsZ}rngYU8f9JIbGWQjE#l_B-lN@oD8We7Z}iXBo!>Uc77 zPRtB@TYJO$?R&%az0KiX?wj{F2Ir*MQbxNRhhKa6&J16d*4ApPLl^vOCcU3O7p8%d z07v{p`@Q|D%S!Re{wqVz1(l+KI7|Yb!)t=;wfy?M|EJ_eydSyO@BVJiuDLvyJ7dT+ zx7Y7_7PpmzovzdO!}xsoEzecSSHHb_^_+ZsuOMCj-*xqXAIaPr+T@inY<^t1uv|tZ z1{g}ufR*o$h7UjZ>F^)^!+#il{No=FpM83Bc=X`$u)VQ4{7--Kr^8?U)nAtak<$0h z-8;jb+jmNtIy=8OtgNh+5sN3;l`B_jo4M7M)v7Dn!-MAHMP6o0rJ(U19L<~X%4x+T zuLz18!PzzzvpjtCusjwRNYENIvlQ9kd(bX?2L&!e8f7xiRdgL)oSU5=7H!`gUI@*z z$Vgw*;+W7d^i7@QJ)QGN`HVJdFv_Q;#ig_pk6wl^JQHQ>Vi|e_id(S0bL0B(-n;LF zwx24aA=;Q8$~mW=U-9aInU8~Ugg;yx-K62 z%roIe`p<#}M#hgm`Y82yP~I>Qf98E1Rc-IQXsdZVLSB3x63& zC~J{vbE>v`|NZX=t{cTK>MO?6gXF=}0bW&GXHHZO6%u2Q?F`TB+i~J)!z2&4_B=8d zFkJA`VNj57oiDjCSLO2Xl0QR>?b})@*9IYcWxZj3R; zo_6I0Lb;EpVAy5IG+)|6O_|=i!yO(y#-RmkwNNWVmcjM;%Tbw%w+WDV8S^}xg^%9t zrQNg<54*Xvw{0%rr*w>$6n?eko~_$bZ{B6_Q!h2&PEL9y=YX+rF?Vyht>VZ~94&>TGgZhy>2h^drMD!w$Z~q9Ae@ z+;oRejB#Kx26$4Efy(Hm^M+G}=RDN)sq>eNJN4y>r<|e}sb9rU$Du35`vvDFnrO?r z>f_*Rd5vY9ps&8mLw(8^mG|oJj_*{9WMAV_pg68H+EYK4VJPE2WwvL^$>3S|$IudZ zL{6%+u+pB4F4{wS?To%r+-m<;=9@Qofb!1k-3E*$MlZpbfyY-v8|wVQ%#A$$?uJG% zX5kHacCMkvk^97zXDxzC{nXi2vS`|gVW<`an2%GAFwH$+oBC{$h3hYERU}8g7?IOML)KeUb9Q22U z1Mslq|Kty5c`}yQ;?lr4dEK?aPdO=itcM@QVR0jQ?k)12!^gPA$PipjKJXPy&@bA{ z`0Fhr=@Z~b<59Q6>!H8bQ()EvM?+)Fo6z}x+dQN@dUby4H9dbm@6q^jc)f~a zjJTscvhq!+IQ>}P;i!J9`1R6%X-93D%g>^xnb+NYGe5vvcXMm$UV>wAAc@Aj`maD& zXjNf^*LyGOUH`71i7e0QEWFbUaBrA9wk7KHUz%d5fZrlfYDTKJ{oB zaV!Jw2PczTXOlDyW9~^~y!vHVoAOKz?VI8#V2U@j-}rj`mh`#fsPsb_y^h2ejEjP0 ztVF}zG*#qEQ+cUNcwFE7`Bw4Jgf64gh~Kob;^w;-m4|Z2XWysix+>4ZZexKg`D#GjK92>rl!*TdEhEow%ufPA^a3eywLxM9Z+o(jS!mEa1$P8DLYOnHY zW+c;Pdstxd!%$G>)`Xuw!U@KsR$OKxEe1I=qO_DIrC?9~1hparHA!RETe(Cy>lLO} zD)!bheiLM^uC;1ZTHYL1=2_`y)}5GzVv+(j2Kwk~w`rvtK?-wUD~$r1`Vbz@<(f$v zt8%U0wEC37o5FxHzZfITK-HBX5X_WquDxAPohK4O3ln1n8Cz=B;Lf#6PCen zI&_SHq`ZdtWeM+;unb*~4{XJfdJ%k*moWv;o$qBuFQZ{yJEcR! zCj+TqYr2>EpPeZq8$%$m27OU?ZDt%(TBCW!4tmB&r;Us`ih??H`Dw~i7#={G#YE{wmH_T=HVfl}BCmd%Q9qP6{?<*X7y!@iI?JV_eu$$$f&ucr1P( zu$ZH#_h9u+x~XpMZ9<{B&s6k^a!a3O69&X>dIsDNd{rAJ~ z|C>J;KK=Oiu)k-#z9@w?`n9mQFkHHPbvQrkY!q8foe$q-JGq%sip{? zbtX|OfSy(VsQ=82?N}d|qSrj{TqJZ-{>|GsFNM*7a`a4S#{RIixmjB@QcUA{w3F@m z7|a;O@Lt!$V>t6iKcG*_;n9T->MKh7M^BuE>O4c9{mn1nKejeDYk`42u~=yCJfm0} z*((p&lPqPi3ZQhoa`rMZ~htV994oMS+mYQ=~sl2_l zQ`1VeR zcQgGF9LiiGKmBU1u-Id%Jeb>?2R^_P>BOO=WiWK6r1~*J?QHLs;j0vR&s(AEj7vN- z{?vG2WW$GQ@72|dWq|T~XLl#%*m=OhFXNo@K7C91n|3K4IsME?aqr&7aBuy78BZCh z;H9ks8OEMGc~pkA=ix=Qcb##T9BkcYt2}LJzJmk$2_4wk+Z(pF_mV$lGHZJne&LXb+9{3bWPU?5y)`AD0nAA2WPu7l+|Ldis2DZciJ|jM=jV zN0JX~tE)!baOck5!m*VL!H48``N~=uB;`c`3$G7(@z9XQyZLHM3SRs{D^Qy!fJ3#| zC6|7o#51=u>gg-vH_6fmeP)!co~3(u(DH@;LNxFx43TwCSMcca<;#KRdDR7MU_uY| z+d|;6Z6D($-k$-fWuX&Q_HNqQwxxI&o?`N2%tOD>82292&&rExEBt;fj!FCI{}k4X zWP;oJL4V+%&=5FYiwpCfEMxrkd7~7|@(7=mI^x05TXf;>-TV38-jyXIq(0i^P`R9P zCUWXlIGyzR0`B-&TO&SfrKoX=Hkd!iaOl|c7ruEs{b#Y;_+J1dKW9;sF84BSM4@2kfoew?K5a_n_+uK{EFsB^msek5d^Tl=c zR`S8OmK>Z5JlYp*$~AVhpLwh2%)p;_rRdJxZ!%up(@yYfG4w(odPiO}ZqUnQ1I&V} zg3c216YW4tywi5@jS(16xw)}jThmHc{TrN_&f^0!oSSHnGT^cW2fh8I@p7X0Q{HXr ztN-OS@#=yxATKc6URFKOh?>jNCe?4jX?y?!zxJsua-V2Fcn%jUtFH}(v#-US;P|T0 z>E3+3DZDA(bbZ?}r9GO@^jufH>35}fneNlOwBuo{+)5s!e<(fg;;|}q;kPo~{d*PaO??BK{;zkU`L8n=-%VHRWn9y5nMg0E zF?QwIAy3nIN&P0=#-9{K$wOU?Z#1dk(N0O@UPhzDZ2qaYca?t`pT!x=Xk4xzGN`N4 z`^(+;iW4~co08NsS7=$+rCxQqDSobwe*~tEc9AvXb`tzQR_!>v7OH>$0S7oO{G#nJ z#s6is-_d+LAH9AR;mh*&=6I|ehvV>T3Nwr6hkyE?{%?jK{gZz(EG#b#55pKZ`^r`s z7+&WM*aD~ozl>JfWe^517%j+T0?Y`ecsi9yzKk%GU=c8-b3WC?z%ZO(a%F@VP%yh& z;aJ;#g^4zynyk-+aUsOohK2A*5#a##Ud@LIbHHZ*R#r{Yft}z`Ml8y(2p*>*Q1!NH zy@eVWFh!Ro{3*vBcK#x{QNCgR z_XCeJEnb{>F+7S8w!N`FJaFzp%H_4@tgsTso;(_!J$_WMQWQ~GU^WR1_QNM+*(#+E z3%)qK_x=xtm9>i{;OK|vd4F)QSIUTIPaVii@fG19?Kf@vs7)xR(#V0a4GKJIFkgg; z$6;umL}>K81nrcM0XiF@o;S|SOzM=f^flvzws4rcHdfz-*|`XZOX;&0!}^`|;iI2@ zJZ#?C83M*}_ze#5vlQwPJgvH%l-eir4qh2E@b*NI0}~H-FwYoZ3^OHWkPX_^_^#~( zGsc{YL)l6}RVzP}wv`{rBl#JZe#(c(7{;6+arW*OjZy} zD?TF^O*Mn;&gRCjmkTYc)vNxJ{`|uHuzYcKIAiQ4j~6Fwx0-Z9#x{it<)(45bYZc! zgqgNf;gTTe6^hnevt|`eOd{+y=2WUV*L3IZ{@KzSqzEhi@>qPi5Ekdf^8sX((>c z5p!!Rp26`7o>6XSF@q_rL$WVR4!FfNh?h zmI9G69i3Rc*k=||@>5>l-`EIkd78QT8HU7v-PJTGM?Pl>g) z)zR4UAaPEH2XemCLMgAewl>Sa#XzvLb5MrQE7F zm%?#Sn)CRbTU<^a`@`S-)lUcBLaVDwftf-&?H8CW4uE$&*~)7t?MwOO{49!@^2`a% zTVKClifxJTb7-}+=&^IP%II;D_gA0Y>g+0tR@<@7hgZ3NJem*nAp_>UJ9mb4 zXLwQM1`b|q=FeI|9{ilPvMn#3z^^aYRxg$knDXBCV2m%$*5VDZ6dce-yyJFs$A9zVg7Ms%732rX6TupqqKffhThrp z^C|n;aBqEM*x1-EB{ujN5UyOlG_0iE^tY`TuUuNIx${2n!SL&suUstnFRZMlonH)} z1&258Z)YwI9#T#QAO;d!wZR?m82iS$exaC$Tlf}dh+esLB{+RhXXhbA`jKZD@^|{o z$<%eR&UG^488L6&zFqvdtOR-z%7%<;(cO@KN$m;LxW?tG;L4u7zx&e~dnObzY0k+at?(Uj~T8VI)BJ8NF;J zsqJh5xDdI{_*Fl6`SRtn!Y%ZWK>=;Ch5Lf@P1Dam``OQj4}bn?;xXK{!3}XN(wCk^ zv(XV3x>-i8@K?qmUXWoG9x~7|$oAPUZQ!zfovk_HJ7cVV!OIx~_!)INcitkT)5T9M zhYpbkd3ot)GFiUD_qWHZZ4iAAB`Ui6oS0L%l6iT$MQC}@WjKTuP48o;e+=Nc|9p2j5-NO=hs_ZduGP0Kz#ykss z-Vd)+bS3i?o&h~XBZ|MTn4MdL)NsS4w>eC0eY6k0DopW@!<&Qg@eetC8~ix-_&N^9 z;nx%>yB0644)6c=Zx1VLYZ3fyPe`F0CV&Dd)7a?@YRtrmTxK_d8!rWe9TRKfvjt)^ z1|zdj%urA6C8Q<3$sUtoa-^`sh?pfO#?ANg+)A2S4W4(!03a!+|! zSk2jlmtq8SMfuW#M6Xl_OMprl&A=4H79o9Nq%cXdVFpX_p18`kP1>Z8F|VrwL7gHz zsY+;K1W^BHf!lWq9`C_V!T&UI_abN>M1X%1X7Odxt4p0DlDd0V7A040P^+nc{USKk<2Y zG02ohq&eJtnlXeX9K9&lj$RbKHQ$F8P3Duo2(i$(V%-7;2 z4THkMBE|iMf)R0|e6k&!ZPgf`cp==nb*r}3tF5B^g|^g|JDJ~k0O3VSQJUe8rZ^Mj zLFVI9KA#Cc68gp9g=b(yK+Dwc>Xj?y!NQQUaeuSs?04RIcX;o;cWe7(d7)omM$>jP zk8j-Hs0B5Y{OB5G(Al%6hWWq^c3T8qO#LWa8MnlH9Da<~(^~jRZ4F*4h0mpJz~+ps zpZ@L7ieAEjXU`s&(cgJX#ZQGcqW!$7dcgrtxo6eK&KsgMXN+UyQiguPzqX>vVucem zHsGu}F%~ium`k)nof{QcC~=3Bv3`H6;A2o+zrSAd2_8{-j2RTX3}^aLd)b~BOpGSH zqMSWdb5kY@N@1SE6w{0@79`bqS()STN$9@#w#{QS#9x9F&k5&v*}+|kIsI;-gl)jC z^76lOwfdA%l!DmYrQVMp_ZeX)PMj_ynXUPZ1M?(a5RWGqGqsgj@~70QIq!jmRS)Vc zBV*S&oA3e;YijgtrUi-dzEPc zO7f&c^WA)nHMhWw@|`!K@xV}*88vNSG0MsG(LtWUKR4Vuh zhLzrmocCiX`=2nghoB_qT_w&7EO4 zb1>rtd`FkG$F9wk+5;@ zOr=wIZ9-Wl()eexHyvJH0SbCe9u{BjJOiUOMSaiuX)(r4?mbx~D0bM% z7BBf~(E%8BIjL{EFpw5*L-m@c+(MX$6MfudIniFprQW{e-O93fvVV#Ti8E2OzrCJ8 z|0hYQsh7P35wg5l?BZC;L(Hug@SldLR4REcS065Bn@)5saAol zUyCmZ+X%uSiZ@QYdH6WNZFuI1qQ|c;?<7Cku|@;Y!)Mg*1_=ZLe81ibQuII&o24?bgHFdtuW&T(>yjGXqs~$9HaTKQLCqH%i zs&@-=eR`E3GNn?BC$}yd3a;iJxMZKi-s?4tc0XNA7T(dg`)Pk#x*5!KGYy0fD}w`k zaRgrQ4ez)~dz~LjL0Wz9TMPUU?{Y;RWi98m)*aJ2o4wy_YK)L>DhH3h3%EF*Y;Oma znY;IkMu~?6-DIrXgpgV2vmS6P+$dJI3!pW8uGnW9NdNDOU86JoUFuSc5bmIS<&!`w zwD~@bh-bL?ONNJDgyt>D5s;*l+W|r}!b|41NcEW=F;#2W1=c7`+pzORIYYE&A8{6U zd2_kBDt{A>L;pN_D4H5TgD+E&@PZ`0khHNbSsCcNt+58oR>|WE=WZ{72)?oOAqkq| z@~D4C;Wf!~gBLng3UMBJ=Hd8FFr!YDGbxn$NtQR>{VsjMQe#@JpclkM^Jj+g*e6{( z`)AW0Rjo2`U{r%Xh~VrcSwWWG_ntLkep7`Wl@<`Wmm{qh6*c11dU6~a#=#}{shFx06V-iUQ8!<-I&18kk3PJHh(OHs7onO%Op($Q(3aoqRJliIT~E3r z3rml`vlz)&BtF|J=5s1Mt-F8#uGRt-521s?Jt-V<@cjo}pFwu&%(RuMs(&u#HfSa&>^YCiS8*@_y z@=_bBbFC`#LzXonRCyTI-l-drNx=dSJS1yECvdAgE6Lz$1U)sBhk#FfH zmb>zpU7S~w<^>p3{vveC*&Kc*WuP=VU{E>f`?)@JLJ72TIu}LG6IoHnwIC)Y?zD*R z*$5VG#1s1UTgka|jh9o2&^4yF_Cc%_g-p?wec|%oIxAnI(wh$Vd5sE*m8 z2NmBI4cae!io<#bi$}63q}4kIb5a6@bk{b3|K_m7*idmyti^&!lL zXZ17Wb@Y7;M5xENe`xhO^ zM~f*zeC2PVx!a=UBgVyU(tWM}aGGjnfBNCMZSJp4ei|WwAUIGU^0iU8g}@-c0KYLb zxv%R#&O@%=mj?MA5c-;=%J2u-#Gyg`Y(7m z2|QK`wE}fkr+e8uW#vUVqzGBOg90wf$(ErSJH+tYmeProTC?_ zy9f)}e^=`(oyMb%QyZnWugI6aZ1SHy;lZxQO*;^uI0#9Q^=3ucgTS45AJYd#V;BCCYoI7u zVu~lbrh{`)Z@zAhjk=yq&4`n>;1&$P1FKw@`fF1Eh9Sp_It6mu~6j61NL&tb-AhOff zC?k${8&=X~%b}-i`8(H)z))TEZP};8~_zrc!xLYhei>*5U>S9zR) zC9hn10=)s+du$*lleql8S3NHu$U5n1;ld&?}sMS#}McmDtiQ!E`Mzjijcj zYFn)V@ke|c_eI#;2Ytzn`$ZmA`9D*M`-01?ZboL4>uQj`vh2RLi4~Hxf1a1}P{89t z<35Zjhc@jRn#Kd6kmm)+-LC^yL+`&C!F$U6OrukQ%eJUkLZ954gjL4>-5|7CF8-r> zz7GF#)34!0LkofR>F(@S!885!=))1#;_&>wX?J_CY;qA}Rpg{%_94$FS09ubYBQj^ z3jVm$ny;(Nl+?(wpbE7#&xKYP<^b0oR@M6l&=Cn7aMhIQ>?8|whIJf1i9oCp4-+}E zi}uHLPWVCJq^(plyjoD#H-Aw7>(vb93KS2w;z<-hemo5-J=S-x_`r0_66MWN+)5Bd zA_w_x3mi_1I;K&8vS1>#=@zr4-KF_o!)XgSR54+fzYJ=+wSm^QPl-CxA~TB!VAXQm zB4Ck9lADi8wTuIr}rIKAEU&5LCl!V8+nL#YcL|H<-;OMX2;L{zISt zQ!U)@M6k~=P=2NV*y?x@f!Q9BW01XFUbWg?^j)koq!zrfxO<(j{j&To&S^vY-$cC~ zyLop_n+u?RvgLnF081bnjry~?p1E9lSC~`Ailp@BzH= zkO}@(`L9&&wy-!bH+x6WIBL7;s60mKVC1ItQr3*HW>Z@TZ4jySbMvX&rmdE5@Ii(+T18N91nA}Ie~`Uf=Sm|G4wk*}u8K(eoqdR( zjcRPyBjPvbEh3QhDXvecQO#M2`ab9D0)2;lX3}0N%Jxh^5~;1Kxv4tmn}8SF@R*9{ zr2lpLijWRn(LS=QCP$MhGtbfGlX^v2vV1W@bfbS(C()%MjOA7?G5`w049s#FkMVA?P|e z-*woL!}a`g{pw*n@#bFxui$ZGCOw?>K1gjWg9BfL(2=h;!|IJGW0tmoQq$yb2zR>u zy2S@Y55mD5!qqYw7=tc?fu+qs>&R#Lp@J=!t1gSb@$J^3YG=R1D|!3<-kJ`+;Mk^F z_%JZ4z0Dc0FUJW^o~oNVLVPNL-_-*NChRYX+fszM!;WmNT1Gho=NF1h6FxyV%gfup@WwUbWsw{R2JzWiWbeuC~A(vEp)>FxKS2CNb`Z zkO&s4kLT-5tM=ig;(AH0De{V&5rCnSA@|{j|0C1|jESf?2ceP}q=}&*yN(ox#={I&a*0K7lf-fxd!JO1>V6Q6~p8li#uCe+_W z(#Wf^YJ}usdTWt-jT;}2K-3&+3C&PBLKSpggvy*{bzjCGgBRolqe1>D4b3K>@TfY? z<5U#}g3F_X8AMQ8!6AGWuJ=k#Q>)cO#YXZb=n!*V=l2)B344yo+JG~=eS#$~;H~?^ zZ00DAQ$l>hsVN{`??vjoNs!`ZVYWw@)46z5*^GE&8-H+;gf3QbC3FHKl_fL0XiA4l z6*&DH7Q(p8{rXnf0$tt1d`T|b8HD8<`jmT_4=Nl-c;IDE9mMx$)1yAwF&KdC0tlx- znTLhBs7Lf6Y1me=h+TIt?TKB4Xc@^tAGZvS z&KHACl->H?g(T6K?y$LTrwVVV=4jkYtWQH&3{@Nr=i1wpp!{5d0_a|x29Xh(hN(L6 zn`{Mjni?FX8r)J|j2?z0d#)kFlJ$j7XYce(Xc>kMDj69b4&yot4F2f})*`cWdde(>Oqqe{Gubo^o55S=@WMp2m*^6iR+O6>?>e@-Mhxy{1^*6#$dhq%lMlA zbD}zvlpD-M|Bvaes045b?lOEu>uIEmHVMDZ{*o8nKUdu)@hI1oB94?w*Yb7GE1H6& zelfWuVRcU+Nvu;1H#?qgxK(PRitOB{YO+WgJ5rH|{*I1JLya7E^uu3AnH}A;3J&;* z{?l1n*OqMzd9l=_k!H~~f;ce(fC=w;*x;KALEiAX)nw%_*ix$Smb8IuZCMQyan$bz z3pA)j>YcqvH{8^3ZeoY8W5(%KX{ji6gWN2{gj%0a*SextNjFM1hox)BN#w&CxL2AlnCdt&iMohI-bHCd@hR z=CfF=AML=b6V{>6Ubrs|Rc{Qb(HlgQ55%3ef}Dl#GFkZyJH@qL>W&|kRh_QJ`&Gt7 z58{rxa5GiqMFBXo8~oTU;2Ns)?Br9!7gt-?_D$aOGhTnD+l@iX7Dc3+$)w}~xy6s1 zWj+`LcUi`;^NZIWrUh7?`}G@kteTX{C$QexQV!K>;!JJbJdKyr%7Jq=W1j3pA}W{K zl*98O!r`Rt?}Fd9IeIPn0wk6v%91GV+ zbmI$4t+Zo=;*RSH*25Kq100_9 zCCMFGFxm>tp~$N1*<3mD*geZeZ_3>@Zb{i*A(Y(hN$vU4x-3xj^9%}mjx!+C<>j=; z@kYhM%)mr^$)k}Hj>KFJ0k{arO)*_ImE(5MB<@9Ri0gCJF$Pdi!OFx*_N_GpPXL@F z<;CMA)i&31)c4ky2!)~)xbYF&OZ~zv!N8;%w#`_TB2>Pkj)(b3ahPDDPqphf6{Ow;7pR_M02ZYQ;A6@f4 zM_!lGtc7?Yp_ zKCZEzZnLmof#Tm&l-2GPTL!Es@YH9KUu8z0 zlO6QWeu=T_D61Ah22U+v%WCr!gL_s9(HL9QTPAZK%s@)crP>n87T-;MKKMua1RmbH zV4y`)VBO^sR*7efpwTQ?Zzq3<;V15D8+?Zmq8f&@-$3#)dXFHePh&Ok+e4TBBq7F; z=$tNkSDeaKtiaXMnMq35)jTe1+yK`VM)EIGYeY9CQL8^c2}>qAh)ofCaF#%Pkt)@t zccPMUU1q<>PX5wJPRv!TWNQZVlXT&F? zEf2Cl*tYh2F-~@*y*(WX;~=Xvep$+5V`?)MWQ*nV-PSrp6o|5L38cBAgR-C#3l=uMtrYJfq|4|_7_e0%SJgnN)Vp&U|` zI-UKmLQeRqLgZEer-)xFQ|-5|S8_b;MdDwKLn0-Q%y2s9jyTUwUJe1W6P11z$};=? zPdb+9+M^$7vGCqLYJx1nS6dtMif=mmekxZydp`QEnZ(knEg9bz8HDG&-yZsBGh5$K?^MUUPHPou{qZ|tlDL;$@ux&{4WQlAz4e5#7re)UR+tQv+6v@9 z!JuJeDM?sADX{iFnK0UX zN$7S{vd6R$92Vl`e>B>3PjAo@dj&kHh|4p_rdH?P3Owa73_g0p_(5oZEsMA$OHEmu zouwdAS}7AxNlMiO?|~v$6gl{(j=tRPF~Kh2GxG`+g4Jjvm zjk#f^Xg{96^EYh4{Si-+REX*Q$yXWshb{Bnfdo7R-7>#}@e4aYCu8`qe)psGbj1CD z2lDp&yg)R6cAnQhRF_Lx;pXzXJi*}ZGStw+R`O=+ULsXD`W%uNI)Uy>j7FE^+rDX# z&oLW^xPHI}0V=c@!XWu=mx7y?| z_(j#8w*^bL+8Yb$=;7?M*bgc1T*LhKoUjpI>-n7@m5c^-Kg%OxopPoirsG-(k>SGc znrKkSSM3JNW+%SbEZ(2D|&mySaN{(beU?b2F_mf&!B6H}>7rEz^#zb^i3xaZf zKJ@qhX-x1jtS@S~zz@O$VB0F#yT=g0SwGFscEFRWR@&WxZ-*$%%>Ap%_}9J1_ZA}% z6eP{n60bijouQF)G~-s`F*Ylp){n&2eiiFfSOGhU2Ce8i;F8R3ar6;Wd;VSKlQx+` zv6mQyfQ{-PNjUBEf|uvh2dPK&VLR};mWBhGC7UQ|e9A+Oy=(uDkYP^JNHpCdFw!!y#N-L#{aiMA{e~(4LFr4Bzp5UsC4rWcE{0 zk#|E}sN~)h+P%wK+V8~M^D$9z0Nh5@1lRY_T7k|eS(es>j8oDCuZyOV5?M6+Zd-LLGvE9Ycj`_E;AfJ_3}Yp0?0a5M8u#bBT5O-wXgXsSmt2vcwo<<`)jN#N#`*}@>5X~G!3 zZiPPTfe<2Qg97djarJK#lZ^$j52tPqJ6liUZ==Kk0z2J#!ET7NwBdyi?Q7A{bZvXF zz4r^4wf8Tcc>$l}vhY1AVRSvq*&>Td__e|(4C(?0b;lyMpJ(S5N76@T7iiZeU1N@vGg~ZR4x`K4U{#@>>to*C(9g4o=xhN{PL-tAbwfl>VC}$@*Pw4iw zuD_}hrVRjcFhxFbPG*Ao4QH)h6uaba1)q9dN;G!P>PIJbn6Jut0%QFP!kZl4ZW%E| z9#NR3AX3Wf2|!zq<1 zLB?-7KykSq{_6)XCSxF5u7B371@ZnDUdlJ-8wV7gMeoaG?H?y$K61u0Kf-idcj{U^ zRqn=)--it(!%&{Wv;GF_KieD#4Yoa!wVw$X@@@NLAWOMpi=@dd#mLiFG51(wEMCya2FL9ld_UVd z6^j<{lr&Rr2cx&n-9LnwWmqU-e+Qd~h5gS^CQU_sn@ShWc+f7lfW2+$9#9YVp)}Z+ zk>rTpyk-Vf-Sn>-e{(sKd&Ew%3Kn#6r+Q>bp2zOpuD+6H!n5imYE#KAy5w5a>0wjm zOPO$zcJKAm{K7O>&z`>bID1gIAC`e&#P;Bh$q3y2HcXAo3ivEZ(d~KQbg^n_tXG|5MQ)LM~ z+P_|K;qv6<9Tpfo6=T(pSCaVQ&xuf(XQ#4v`C?z5IoEX28Gcm{?EI-!C=;tSV6tY5 z^#A6|xxuGy%AFLfV|Oc<*mEyFp_UpDvNa zBVzu?$3@Vg#>iBlgJ(}ZN%>yOpQql6dBO?6ZxwCl>e`1dQiZQ8r*0WaIB-C51mEfd zQ2o=8#`aWrj($4SfH>%?yR&jnf%O4Zbe(f*OmdxCw+kZL^&4jh2_fR^p%S(_qH+04 zM^2}-#X!EEJvfIM zr?9^2KDfsCMLQe7sBjWWhR~C4R*HkRE6p9};D;x($uZe`Z6j3(@u$NEu`&hQTgP?+1_X0t`EqK`wYZ87(e47%sy(+aAb6k|m5 zEXUD~;2Eh$(C_E}E`%+OqQKu2jRG7`t=sq-D8+XO+I4_s7WH`D52sN22#C z{#yCn<-wJJC8IL%^yEvkQ~l4{g~u5`I*iTDc~>6*IqP8NO*-bT_1_C-?@lJb&bzXU zJpRDzr#7!#$s225^0KwMjshQWmX{DdQZ4YX26YIS{W{iUC>NG1lmW^+v6MDqN0N&E zn5(xOALY$XrNZNZdzfEwaiDen=>SXp`Y`NR$$Iz(h#YC_s$n&7wT+tMv4wj@Ka@!R zNc9)BSQe_bp?E$N#-H7lbiunm+n+i$461XX@7Gnlg>Kf}`zO@RVw>kmu12dD%f4yE z@B|tS`jYZpQwCEYO1wT?5F7qwoMpd0b#hzPxtGxY_?d)G^aBqfi>XqK)QCM;{NM|R z+b#e4P!0|htAyU~l!T)OUvqd{6^QljYuvfbz`8>O8wni zBHSt|jf#Z@VHV>iR)(ji>tjQLcI9sxOa7u4ql$X0L~T0#-y5P(3zS*)Wop`vh0M z78gGJDwO3rG3wja1T$Urc$TrN9kp+RX+@_OMYs5B>$eG z@#n!Zr47~PlMZkra)5v9orKN&s4)n5{b>9po0o%$4av~`-Lv7_s?K@gm-pQA-PN{r zZ)~r>+j5(Yi7%$s&q!M|CZw*FBHyZR$8Tmr%+0LNW29(VHj}dnfpN>7+ok|HKC1Kj z%W>gAAm5Ra*U{x)?+gJ;moQVGW3dM-R1Fx(lo6i+4H`qRDtl+9T;SlsP9 z2Or7>=<*F)xRDXG+u4fQ{X4^f6a@78Z#a5sVNPsLGM{8Y?n8u7^KRrIU6-eE_0aP) ze?1P`^iaR%&?WR%jbMmepay#DIJ0XeBus{hZ*`#3{c&wBhC6;qCi-%52@-ZUbN*%z zyQs0fW4oVCH2T&}dtgb~#i{-70YGD%;0fT!#{6CS=bQ8_j%OdMtsz}& zk6w_mD9M#ykNbyWAlm8~EdsYczG-R>dvnzXn`-$Ut1a8
    z*&=0Z}>X@5A>gnZ}otL=6hAJ|pdF^ndiFZ*<;TmOo)G~~Mb zqt#c2^Bg5kw%L?rn3-28>`bw(soQ;Vp2=72yvtTktQXCy)AveHKljnQ=gT@Dnn|eH z-sV3|(o(1*S$sez4CQf+zYv^J5+&qYf6@I*M44ru^__9Fph=951JEE*WP?iv+y>HK z#cGGnmwmw9qKaDc|F$>T7;>6DoBP)y{}<32%d#dL3)FdAy8?MoWI z&$UmQ-0Z8TOf!DNojHwg^$ZpMzy>5;`K!ev0&b^4=WIVx$`p0C<&*Pz}_O zcdy6c6z-u1H|T7}13=xB&Exlu0gkwnt}#+dm5I#7`*SLRRG!R##g0&!Xjp^fr2o(S zGg@@=y=5tN?-!HvmuFMxOhoB!-G^P|z05YBd{`yClAP*Uf@BpG7;~ujE8isbP({f4 zA1dQ3ee@owxOlzlT;hn4d9$EtTVNC2_JWB8E6z2NO9}7bOcNL1r^*e!R>`KSr)^V^ z-0*#w;1}RJRM(XL-F3pZuAch+z0p|^g5g`GMHt6S{3!GM`d^rPc{xw_`amjD_sfj$ zw{L6lviUvw_;=TvtjX0H@fbkGKd03w37R};Z#_4!EISC_Rw`6p1R5b025<#1V}V4Z z3ok~d_Ok!}fMH{gYc}HqegIlLaV8Pz_G9VpWS&%Rut}Qa@j!zYv=9AUw9>aKnK|@e zqe8mLEjfZ{>2u--cB)XtUhP?^_}rJX`p#nsn_mE9w1t0wp;o7V9Wx3kjrc*#;&hq% za9Gm3{icAG(g0>w;fqplnZLzd!pfF;p*lLZiboFJX*S8@0Iqb@GT^&oP7^gb(1__t zRoi@5!uithnHz&QXAxzxmm`-yJ6M|7@~4Sp-|~#AdllM-tNie5h;N}pMQv)z(;?Hb zSRv34Iu+ve2DgU1ayXdG2RxagblDq>D0dDBkcC;$Ejd%x=`6kGlW*xWv54%ZbHF1! z@9J{dDDPRGGsfO7A5H7?y+u>IhE67;VvnF4x+)A824r26CNlKPC0pUiXz~uxO*>hA z;tOQVX2V`N<_7Z#jhL&Oc$SWonu%H;%uR3S8*FZ96Pis3;R^Ya*2g(?ueRM!ODU&h zo5Q8%(^`UTWTI6;Z;K?(k-co(FBf3I;zA6X%`s@7p9{zPPQP?3&vOON`d4FD`&{ys zc~mCCJdIfRvs9Tg198%#p)Qz+(EKID&_D2$F!Fbl7=jQ1$xOzOwXK>=s+e>T3mdvR zGMH9ty`9%l5`iKIF4{3`o@o`d8F8aK`Z?|?C* zYYqXy09ekl7$RFSbu- zZ)hw!z}%}|Xzv)6Wl?Mn-Z6cR#Su-^1}6dnG<&~5jtIwG49JGqrXz@r^_#-z;N<0l~ z7ibOHZ?#a(U{=Hv*bhQdBu`Y>^5#Wx&gj?s)RkSGJFv+qY}N+ZQs9*;yt#riQ|x%~ zw?{{W>OtWI>(NXC%D6?Pd=bIBHTvU7$@BiQ?Zxb58aJ#Ds{6F+V?JHCQ)b|4nVYWv zL`$hmLbQ16qv8{HqQsxO}4%d=a|UxTzdszlMZ+V5JY$_K`J#v?R9z zn8*AhwBnAVysP7IC(3Mu>7i7o#z}$ItCDBO`B&o+f(L6Bw9LEP<~PMB)sV{puU6JD z@{QDy8Q1IVu;dvatQ%{3aJ3k+Q@x~@3End=djAV@<3h=~>c78JKJtd91Q4ueu-ZVM zF6iK!Ar{;jgY@IQjko$W&_EjFnxwYGbaPX@oB2t+C}`qTV<2eas(n{<{VMZ;dCW~} z$W3vKyKcHnj)l`@0=lVvLNi1Ql3$;sFd zB_DA4EB)oX8Nssg`d|xLw~oCrTV-+<$MO6b*K+Tx8P%au*``=Yl?CgZ4_q_hN8o2~ z<~1ESx~LU^h)!m&&kVeX&mTa85wuRPd^!5&KJ?T}e_Bo_F(=TBptPa0ePA1s9)>QdoY@Jb3l2wm3uRRKC0Vgpl_8j%&~PDAUq$*$>nRdifRfPV_QWw zW~SX0^7QmH>DNyN&@xOoB;>X2e9@nc{-=#NC|zst4-J*@JNoA#YtwgZjcD-{U@?BH zz4?or>|gTK6dE<<+TI$_q2RwAaf8j)J?|( zU+f_s-pg!=2|C}W2LSX_`7L-8xe+amz_?0*PoKzW{+{m2@HFh|tkueEBETkbz~7JKw8_se1b0o%!={#& z8qseZt%XF7_e`O2pt}y#Ne=NOM~g8t-2L66$cwz7-E;Bipxw;%?2iKS;$W#MnNM@9 zMIKx}gwkPt|LIluZm}Fm^`K@ZX-uGFs`W+vJf+xDY#}wpO(FO)5V;9 z_g;%%^jV5un<3BD;Q&^0PfTP2UhEY<80E8}<0?9Py;SGC>$l$AiL@I@;BUJecpRtFX(gam@=adVwE&7^G|Pj_f_zm@yQt`Z|7r!ohiDt zrdPo=ON}9D!)`Njb6%7ZYDBah2dA<_ezmS#pL&}=5GP+F;AQiZ6 z5=-K$>FbMjbnFw^saf*i_QGw=0$F=gi{Bx15P#4aa2_Hm(f{$|UDeQ0ArwlVHBJOT zLK8f)!zo;rN9~yf=vkfzV4#r}bO%iD0nILd)rYOUZ9JaFl0>p-fhyhCQ7`74yMogCWync)ah1Y9dVB=&@3`HjZVH0!(dT#tD_zC4L zwQRd|u3{;@*>VvIsHvW>&zTjT!Dm=dhF@OCFBQg+M15|7=y<7|GFzHOtcD6O@-Mw1Y$3+ z69=$?O$Xebsf~pl*ak`@T@*6^o7jR-DSeYXPaTgn4v=l zEBV~84QNJWB(ANjI^R6%MBYKToSdSX-K&PtTO?F&1zM>Gx?cv}%Het4O!0)w-lSPf z6;GJmUOuQuLptNnktitcfz}Ju9a~1Wz1Z=Kur^sqCC)D8?O@bW(ZQ+8M0)iCcV1*I z%%a^vB4gv=`$%dOB66e~`@eVUm93e35LP4nc!s%6gOQoBEuq^Jo6ucKvON>Jd(|C( z-X@+ES7oGL>qwtJ@ZxWNm<>`SWcm-^18YIRhCUqJq`@Kcbk>V>1y~^{2K2%E*q?5Y z+`22o@|0Fok{XF5dAFWm{-j^`8c7V$b7DVSyLmB4mJipjF{DTn7$)iR*3F^Ek0e=- zye1XV%TYf{`0#k*P2<007a&E1#?DvoPd`h*tWoHi({BCj-VUt7oZBgzyi(f{^vyhm z5{>qidc877LP1b_(L?f=+^ffM(rSs?iA1_CmJ-mfAj>~UW7XBfvfQgy`L z$0Fk)OTreq!(#OYjf&2XfB39|nJDVxXtYF?R^cgnU0>eXm$bslV}dnJR<-e%TGOTd zM|Q26>u#EF5j4wvhTF-TlO~ z=Pymn)IJUz*Ti(rL3GQ9a+N>V+-z)nl|=I#m@$TK{`cCvI=FkXdg3w$D@kOf2!aOK z4uV4&Z0toe8OFicLbBOm59I~dfzmWQaFuvJ``$t2WxwJWAv&@YWW#b-mEY}P6WW_> z?(f25b5N*0qH<0oAHU@J^+^4Aw|@zfU?p%M-YDArfXjt*g3|_O)-G!bZ#1_3wZuwW z(u;N_St>=BbGm>($Dr$S+ouIPk9r|IEq=@w~x80#j5Ym^u!@5fhr!P4W<*Y=#2 zI1SZzp#xqX^Ede_`O;7t|LA0L+;Ow6Zgia9XPLxCBAr*}29Er&c&lXP6 zE{3pDWo2H10(2Jb@l;-k(5G&6uMQGL>#v!>BTL@jdt=ZOoE7l8<>W` zLu&2aI!`JRh)21Zv8|O;-%w|B>4wZ*$&gpP`k3z^*KOi2>Julf^K| zaSfrV*tSdf3u;K;K#@<=Baod};fm@qU@YLMT_kY$rwRyiq^fR`DebRUsuvH?aB(O$NBJ_1!m$_3}@SC{W zlL4R()lqysZ@1^^c5r`EeNFA@&kA#NR`VvBt%(5svK&6Gnf@}6_B7(Zr>#eyA{ce;rrbfoel-L znua`lRa_q;1HU!50OxP)xTo#!b_x7H*arSs39Kyb9(dlPg<$Zb204^BU(fi}zL{?V z<^uDxw&#dSpXb2A^MV`MLb3Xc-3ViG8HSkQ{7B(M*_kEmYu5X3@4)1Q%jX4adgseT z&BMz^NUw*Lx#d^7ECuZh$KAG zL9O6)hx?E9Z1jdGCkhAg${4YuuToojZ_y&at=~!^8Rd(cWgPjTC$R1I=EQuFUr%zI z$Jr-LY<^t&0%Fz)l#X8?GWCO7oWVBILr?5_8n!xq5UuLBbP$L9l4DsL2VcGte>a!B zlS*&iIX@%tuow&5JiPQ_Y73EY>o!1hYKF|6x_13(7#s0xw3V!)J)G;ld%8`0Ep%xM2mo5w@xn) z$!DVl++1|e@Nl#B1m>(+@L1}GP6=EHPihA~c+Vmei}}7pz-3SN@)sb`F>{i9)rOGU z>YNFk2j%0#npKH@=3{=QKIQa>!Z$RU4ZtyVztiA zIU+tJRXq$O;g5orfB`(X8Ftup?lnhu^6pHGu1I}Ppcp8)%ECmyVyRU($4uaRwAIx+ z1eziC$AmqPIhT$we?T=uFQV!AoUi`&Gk}JK zmz!bVanV$rm5)!|R&+9|zE_Bn%a=zWcHl<|!$AL%gq^zmg28DF@v8h9!+9@y=J9{D zjojVerJGh3g80?9XV_zU%8l)r^z(yjGA0Wjy}s^&89BIbx^LS~M#NT(dod!ja-=7i zw!;w+yV_)NIfFS5Q*m8X&sm>){OnJSd`b(%G>A&|i@>lBLeQNA4u}#9T?;yBmHuT0 zHze13J!sCACBRGJ>yatNjJ4Wb#-xEsWF;C>W69f#0ill zxwtlPvsbx4j|r#FugL&O+u5LZM8DNi`6<1QH{)`vZ)%R~L$L*{0P#u-9t9GGhlE_+ z5%t!CRu8xp9UM%?u0L%gx`1a)w&wUBA0Yfax5u55-Gkc5!n=cQ9!q|c>;iR?Sn(*B z`(hOkq^kVUBmt{vr=V>@vfHQ~J#$N_2iA(k9wI8TX*U3TKKm?nhWar?Q}+lNGtT*> z&`dLRoF11`u$2it;`AB{bZt=1@3SesXn*lG4^Z#Q)}|fg;I%0#FCbB%F%}qC&G{2) znby2Sa%Vn|AH7))nmE5KpfN8%93O9pUm?6cY)R9<-7k}nE=1|NpIz#ce#GgcS_YHPp1&oj{iJH|)e zl$%?-b#}>2>g^mlaH*7qU(U|tp-5Jl3y%w@mRA z7TeplZ)Egk)NKW=pfB(nXU{qhZN9!6$7OVRWbseqmPKv)kpYOJ*IQm|7USW^7%IiB zEzr|W0=|S7sycxe+_tb&4>B5qF5X8S8P0f5p*`&_6j>(ysBh$_9*iPqgPR~{fO?j3 z$>;?y$|y}yoqEH4{Ejh#J}|uCdl(@ZIUzFz_{$gFM$#Lj=%Z#a4vlMg&Dhm+vW@uY z3Zttr$Eb)7Ofag8g+=-qjV%Rma7X+MG;y@Mck(B5*I7q_Q9r{7eWo31F;{hI;|Ul9G|Qtp*LY8;G7|ju$~XVy zshv7i!zND0Z#iB6d7cb##(^;dj+WK6g?W)zR_g>94S5P}*dZnDY24#u^`ZPr!LGf6 zqZTE|LwrWdqV>tE)DL;jC<{cqzcF0x0Q_8Kyh%F<-cP~v(cf|&tL=PoO;-MifUQeH0OcQORSJ-VBgxn3Ew4vkxd zo8A>bb+7Mv@44oU@L9zRrF>~>AxQEQ#$*jS7{=c<%KBf|IhS`GWsFya)>Gxz<0Myp zgG)vgXN)$*mPh5&nT@$6X7$%BxBQ<6~NH_nem%A#%*JcZMwee@Fp0(>iVki zrucuC>sJ+y4PVFMIDD7kbcFSlrQ!Pbzc(yIFsMV)X^a!B{OeU#J-M2+ihs#PDN?IY zGg(dqp(f?}{Aw~TckukI6|xaF>s``L!iEXjq-q;PlXiP#jeC0MPrOnXq#O(oVGDys zPzT4W2|Pk`;_;NSf~DZedyr6ME4wCLe@UtyC1^x|qgbB_6Mj17Vt^=k%A+fjejC4b zYdbYwQUtbIEg23$9PAF`nH7JO;}k5)V{9sKuLxR{EF~~t;sa-Gl~#2K&8M!!cR%%s*@F_?6i7WrvkM!U%%cy?535F#nr3BDM-+U79z zBsefY5^lj?jAG*RPQfe@wi(}WquLpxMKN>!eCk616d{Je!YcOLpWYevw;HbFa2&og zWKdEvI4_Q(gtyj9LURTJ1tXGSAOw_4r3hpMbhW?~|k;k>`s+=C!0Ab})-s*3dw3!lu*mMt?|z6Kk5 zK~i`#jQ8Gvge1^1N3sjPVgL#mrhH(>H#fX41z{Avc?3%Gc z{^02T>Z@yY_>h0hoG=rq%f$IUM`kk^=JxH|(~aAA!yk@K=g)HjtrTA~))_9P!)VNz zMHV?0S&0$V%%gMX&rkpEfB1)f+ZpSPygwEGWe^d$dpI9kYM>RcUjU|3FD zJ;Mz@*K&OKw(oDH% z|IPQ)-~Il#b!c!J3N@z!yX@w0>1T=0QBOy^ zEF-6v8Bp2*r<^8sKHqzeP>w2cw;2z&6OSYCaoQJBsI%%rX$KI}7tDm<`~&(^+XC$K zoWqdQ>(oiJ&pFLsbYNYbFlqZ{bBNE0$8pV3iI#11Nh8sF)OIiz~IyqcX2jyTH{w+secaUuC5W<({C(g*g=KClUzl&v-G0AX8=)kuC#Bmo4TTZ zzy=Q_6B*FwIc?6&JdSvLm44!#I+${&r>A8}ucp6u>9wR++=4T_wRvfrNS{!rUA8graTw5}I8dGAGun#T6GMNN&j{WZ zoc9sR=UiJdKmk3fyQ-Un>Rkl}>)|wbG4m?#E$Q~Wv1Sc?uGEpgV-NcP4jv4iAbml4 z`Yy+p{Iv(TXy^K92eE}7vh}KdB;L@4k9WyfgE@RVB+psSvDz74(bMJ0IZJK^`08-3 z4ZYX^g2kCG3+XSj&+ts&P;ogGrPcBWmgAe?ZQ{Hu9F*o>oR;vuus5w&LAv8O&c}8B zyE#DhhDPXwj{r?-srTLGF>~q8NUN`mcN*sFwhvK;EhU#OUcqZQ^L*TQHd2<>lDGcc z_U7E<5oLzFmpqo+m8BriCwZ2>Eopr`f8|r0#lD?O-|9Vh4ubf5+*p@P!Pf zT}lI_EHv$VynkRe`7JQaxU~$;JgqP_S=5javrlD+kCxyV1 z`%MqeY-l=p-k(?TtnvNN%cEQ=^U}x3ft+5oY2^*PyH2mlP7gZ^xX#GA&USHnM_9`D zYB>+#bAZpSPCg_)pJRJF2&Y5G*C8CjM+8d6=}Q-;Yu|r2orz*VSv1SRhtS8>h)PDA zVL;|o86(#y{FD-(V;|M=@ufgSD5wmERPPkEFD{U{VwE+d3VpVAM9I=wilLRZEi=gaJ?B-3C|YR8<|)#q}BPt+lnqrD9O{vZDBbm8))=~4Rr{fGC9!}|K&E;-f>lFNTa+W3k+ z3u@4)(SzfQk#gksbko=eG&A}oLZSKtzD|&b!~O6 z`-&KGeY8vEj1jFVVfaJ%h4g}Sd27y*2me4k3Jl}Gg$oyJq_Mn_KD)8LKG|^k5IzZf zyrmA!_?n^3e9v(K*J(O0!~EM1+T8nq{xmZAh2iDl&F~hH_9pwf;8Xd^jZu=Hg+Hg$ za{WqT{k|{2zyKC!IljTL^3_*Y$FhD$jqD#z1$=0AZMAV2km#B9hQzY#OwE?&A+IRojN zPAX4Xl+TQWyLaw%mV~;&C!aidUW4=f(2vod1Bm>jj_u`S@2V?TF4UlE-z5&1%5%xz zj05p}Z^%BrC5+yeE<`^5>Z?3E(%E|MG2nh5nHe9xdvCqYp6$?NjFf&9x*LEn_%yz* z&H1jWE3{jdms&az97bRS=InYD9LADTLYIC@eJL9!5`u6{GF+jD{UA9Xe8aB)bhAtL zEoEq#=JdPIQR>h4C3h-YlZ`nR$%&UPU#zUSp6`e@sjlT?FEZsE`6uKV!}IZDmgGKB z`k|*~4dG{I+gfn)-MoAEUiWv?e!W`*e}Y-w%Cu{252lRf+RmWKY!FX5bR*6#*W`We z#NZg;XR@d-Bxfnd5ZZJ4jPj0|X6k`Fv9$&7XXE{3!+5XU2FzLA!MD>aHY$dG$T_Mn zXtP`Qce*DYhYk9ppZ3TZz=5bQb0Bg~OVbJ&>O*_7hbS6bM)Jzl%XPj~k4YK26ym0K zsJt8qL#Lu2puaw-E<1}TN3^x~+M+Ay8)HexV=XH~Ci>Z@Out&>C=OyXN9{GN{Vw+f z^@lE&HCM0tHQkU9)!8`77ayUQw0-7?|8QD%)?Db%*`s}bYlU9YHj6;p zQYHcp{C$_iRZq#iv_(UX7wOPfJhQ);cFy@mSA!Rw)a?B3qn5r`eUHwS^z5a@d2WCa zdTD=Sg@Lh5AimK-SR7b6s!ua2In||aCK}lh-s%&WxyR9~UO4_MTP7{n`lEaXeZtq& zCz(ycPlPCF+#j$Wkgs>1|v z=k_!ri`F+2DSzHcNR%eicu7ki(+}``<V(4+4vX_(Zvd}5 z|4?vHns3TydG@;JZ-Tw=yqeCQw4Bb>yTEuY|K|IuY!^cNR$+f)`M+E_9Y_DGpUtqG zF7bBJXd55>%1yUkS$~5a3eC6I>$njuJ71z zc5?s?y6DTp`Q>_K-{%Q~ZUOlvv}_5|&@OA2@wiC!r0flt z9l{}eB;e#)Wf1x9y9k=AJimMKt3h|@XBf|mO$vfCp z05r>6dHG*zI4TVi}k!9H~=iubAM7{zbv{&ef+t?BmlJJX}BL$B8%ydP+~lxOXF z^vAS83iF=PW@&zD^Zw@Z2;)%$h5;yjW-(@Hs~lJ&dCyXv+Vz(wk4;y<`)2z7_rINv zrtgpa2|1Y`k3Gi1S56$8_l`)=ukpV#vvZ1KFoYI{iuB{~6o$3IYlgDN=(KwJY-fBu zfAVbFyt^^|>0kd)qqcp$(ut-km#VL}x^tJ(I_l*?LgJ5W~PBd{p>oj<5e^c6_CE3~-{!jH{PNZD{_z4%)`v z2lAS(@=HPXZ-v2IMC#|zaU6ERbwmD*;=ViPe@>^}RFmA0HSn2nXT+6@Zdk)$-mg(F zef9hAzMWRjoGwqn=PYGRPFPzr!;10YejQJ~&z4Z*`1q%P`q$~F>pz80j9EgbS1hq= zN#`M3a1@yt_I+fzOO_`LZ`j%zhWBgNu1?>4{ncc^lD)PVsX2Nqb$ns%e0b8OI;?*B z>8J8cjwQz8FOr5m!|=Orzx}4OwKzh|tk~GxO8Jh|h;CK|<3FBcAW;VZ9Va8c2%mk_ zG#Q1-W*i?3yti)Ot>aEvYHU8Ynsc)W%yv08ojrT5{FEGImi&D)?-R%)c&3>&*KgdY zv3(4bc-%cH%*fg7%$~vj@Y0o2Cpuf~{Dsx&^2PI!(N=b6%?+dQ)PV$+67>BsgG*UL zyz*BAvg|)(V8K|%@L3&uc zWJ2X(JU(}BE$^J19`2Y)W}mKOX?JV+mK~kWg+|)U4}VHKOZsbx%Q^Vd^_$7t_mCV- z+U0cet(<2;CGW)<0e`dVd^6$4vGZUD%^31W8GO0h5%+Y%#c|-dSw}T+Co|Xd1MS(q zzOL>4bSnMBY_!$0(OdGpzkT~&9gm!6(w3j48_jT%k6C|4vU~qz%B&yhV`o<_|M^Ah zmm%FAWk>Qo*H;Zrv8<(;Y1-P>_U0^CkC`fUJm!5fuy6o6guc%KMR(ZTT(1L(quD*} z3jxhe!Yj0;_4SR?6umjG@e2Kg4yInoMChyEq$=y+Qs>&B{DOM$I9>;xnTSJgI#Q>v zc2FATclO-b=}gL&R+qM5UpvN44nio+OHn7U?yW=Lcs^#;n2~0s2~IYVs{^GT$86Kl zuhH8qxQCB8J;#1<)f+y47^-uIwuL4LjPrVLfGiTLseht0kWN57Kc4_zIFCBdj z4$Cs}rBmqJnX8rIo~16*U)x^3%=wtLP+AT3Im&(BqWvY4jfLfm7Tn9b`ie zX!TJiba?rN&_kJ9qdC$an`G|KCvErDHP!pfS9b3ucrUNd@B3zX4~(?Qq8w73 zRNAdJT4#3q%NT?(-c6Wa_MeVh+dl|OEJHs4jxu<=C-S};H zzH1{*vGpswMtfTN2%adZ5$2fgJI5bKvU7R~_)(tezxp`-vqaLaYr~OfuSYsfCC72d zbLWAmrSt9O-Z%<%0M4+)7rAHo2N$rEf85W1aT>4zx6Q5vDrmm2a z+eS1JqPMoUrp*L`urK!WAY5l$a5;ADWEJ5f5snEEaCRh*QQCaWJIcjq#7ag+SQ@$Z zG=j`<_`%m`SH>Yr9NI@rnFvP2i7u;>vUUUK2;G!gqeU(KS7nd$jx&jJn)~vh98m0( z#S(=tl3xY2yz87Ji_$ri7^SB`KdEub$U4d+{LDHNJVV==KsnDtcXF^i$cYt3v6U)) zmTj{f4F_TAK?rJ{G0uE3E&B)!<#;G-6?&qCH4bGbik$r`jMO{92y}96Ud;J;>(;I5 z#~*G?8@KLjCWmkc9}M)}8cEV7+a7bQ0zbFk(e__V=hp0nax(p8%-$kT=u34LY1i6i z*v-nhv(uGtu7%HCXj>o4tsd(Lw~ppbdE94s zAb%afVqV6UIj=@32^d^E?G8DDerd6WeL zXyJ5J$G30a4Q)ds&ar$i;aEvO`S#nCe{d&XN>^e07^pcAIh4Te=ydu)`$c0HoGOF1 zYvzaka`f1||47=1`jm${CKsq9-&_v1I!Du%EFURNvbTKnDa+fD4b1ZKF2|C3vM(6p zI;YsVl#5I;oJ)_=-l9X~i>qGjoyU>J`O?{eN#9@Dx&M;gS~Tvt|F_#M$&{hhtQ`pnK)}pFH5rAW4tW*Dby1ef?Y8)nCmd z(?`i7`nI+$C>Jmj^W@wfbw>D=TO}R$s*9u!I)Eto3DV(Q=#q_(=JTIj1UjoEiY z?odbYF;mqtl6xI+>d^c2JoUmUth|-w6f|vV@Fz1q$1Edh8oY;|oL<_D`^!os=c}VIN_C7z)y3l`EcNvNvdodCvec$(10UGo5Y*Xnz{NVx$r@QHo+)N-_vi+ zu2g-uEiIk$7MEng!Mzyar8RI%+M$!~f}bEF{0IF}G>|xOAg_wQ=xEi6wV6a2?LBg6 z>PbI9fA1*ULT9r$z?(PW=<2dRq$NB#PuC>8&KCBVr zs@h3IuMWa__m-2F20xUbEP@9yG28#(3sUqqx7i`AWeT+W@jpc{^(n)j6UVdcTq57 z*7Amfza)=2$R@82*o)J?upbV(_pxC=j;{-E0|&kLp~7DZ{3YS~DPVuS9uyW>uJznQ z$JZeo!bgG=r%z5_{r7w{h7yuFzdYVJuZ* zwp9(t`A8E)h9EyL&8Qs7hoUU);RLe*Goc~4N3dRINm#m~>$>NfB3naFM+Xk0jaQ6x ze8TCK>#^L-sS5jJFR>_YD<^A&V&E9K4rRjo0L{!I_qby|+I`S>~GH{JNhp6ct zN>=wdLXXls!U=6AF~}!ypunoLm6;wXZk{enNjwQ15?7fCLirK&;MRIfTJDNZNn;S{ z=G&pKK$#tDysN(#5t4SM+qZ5{w|`onp57mIeF%r}!9k~+gZ5s9C2fD#IFRd(kbN+g zBOQD}{Jg8rQBID2F`c_|ak})?S5fHAWEjQ*MxCvV&GH01NjjDWn?}X6N=7W=$r}G5s&;-nn&ay7ALb)7=}lr;Xcprib?*w%?pTcfKR;&#s>9 z5>@33d7lz;G(5_+{s(>e!VzmYk{d>$E7Tat`@B3BFNGX-cQU+)A%&KNe9fn?Kw5SFYe8=Sed3ki-n)n0Q|Ix2B81tYEEN(nO_Cpc+dNr&qtmNkF&8lJf`2^eCq{H7)}j+pTi4JbIu8|8a}~^ z)R{kzA}@sxFm8AGH3sFxH9&@}(&ZF`qFD&num4nIA|6pWAm4K{p$zKr4&yGvCVs&< zVmUg-5=Nhk7sDs7T&e@^?%ms+Wx;vCF<{oiv7=;&;TT|$txRDizw#$PxZ`J>?`D8h zE{gnTuL$?` zlgFGD_lu)<$VHB3VJt>yz>@@yVBOwrjmb& zjJB1(PMLYJ(&ZK}TwI&J{_4tf>EeaTsrF*CG+o=(!$;HIdmGcn#&(VRV-KuZ_RR5I z>iYbJwK0n?_u$g}^HUb(MMG`Cl7U-Wmi611?%cUo12(#GM*8lNBMo}8=M?#!F?{(h zFZ5uX_TF~VQGaCl8VZAu!5R?rYh45f&yJl49dcA(_Sibx{ix2?Xzp82F4tD!fS#3+ zb6=hu6KFzV;Nb9GR3`GRZ~9K&r3;KbFo)wzJ2@Y^qCY31Wf~M+8f7?_tA)M<_Kdr+aC^|%BD`WFKLRyd8i$6?xL%- zJy52x45>ac2Gn&0j}(%F=*$Xw9jk*Jf76~;A~!AlLOY}{z{v=nwvXT-F1=Dh`nBw| z3w)0=(ICUcA*YY4rw$-UI_hI-XJ&EPA5EI2Px_5Eri_Ch8{lYfMEYIyI_)NzX-8&q zmM*DS<-Tp+=m{F_8h$E%xR=;>2KavR(xtP*vkg3hkQKfE;Vh}GcXME&7n9g zcmRDypTqab()42S>Cff)hPlCUzEO=%}B|hhD9GoW*7w<3ZYwG7a8>hYp(U4Q~sti@V(4e|#OhOP&jO zXa9T4z4r-u`+$1`=9V=s7MPze?L&-LpqJ8d__MbMjE8g3reKciVSZnHwel`Zr$;fXhD!PTyL}QyC@w*LMkTAcxiI6`tRvv-6$lwgM8ylY;kxR{s0fwB8i< z!v5=D1NP^?KODj@hreZd?k)SNLN}f~v^GZjO z&B8_!>ruK!@YZ1#!G>}|AU4VsEZp<*X1+SqsAGV1^mt3%;jLa15Pkr~*J3Yq^GCW@*C| zVbC^ZdKTrSPOO=(^0cH6+$aZSq7mlBG1_oZ7X^ra3R>hPr9nF zN(BKZ&(Mg$1h=8Mv>d(kM&P4U&ojUX=UT7@4q)JiV-rSzH@7|xDJ{orq z;SfF=v>gwl9|2z5-46_N$5z50R#&I4mSApCpcW?k_yZULKZo(tkPl zC^d)htHLLDd}%K~2Wf^M1SG@h^-CemcC__3gf#APT<*>9z7C4pINb%W_kF*2#d}X; z#bZ9c3`_cb^y+arPo74=GpY`wW%_u6Z!EdSci#*ijxL76!IF+l8=D)`AOHBL$|elx zjFJq7Tj5=I@7=2bx!>s^fS+*?khhGkw>Q-{-+tR~x7kf(E>17YF++=?k>S|>IOLTJ z7cSJXM%Lq4v5cLWVbV0?%;3>Mjq(*r&6?=C+WntInYXP~7c&!1Pm zvz2+tvz#6FcjLs=j>x@cb1_=2=iY+{kBcWGI9#R0AZSl0vw}FUv;*}CZw^aNGE4BO z=i9gMO!w}scNt4dK{8;Ym%3dBj;VvvGwpK>hB`Ck%d`P)b~tL%F3iZt5g~k+Mn4&$ z-!vg*q92`71a-+;HyGU0SU*R*eCAQNb(b!z80 zoSvam>W7SAPd$BrPEr~L2jz9HKS)#Bbp(eN%B1}>WLhqgq1UYRWLElcBro#3IyO58 zz3>L_!Nnj#^|Q>Dp)0u2L3~MR4R<>s^ z#u9U8=BNv-iVT+OOkcHUY5GH+Ya8^$*=vvC@*!G<~hc5eN-lrqekFDWtJOuT9N&YAtHKGmyPyZX`oq(dr_WMW z`IEU}fcI>stv;-yc$5G>14_MdI>Vsvn_-FLxIgTL{nvZpp!n|!OB!#R&gMH%fjPZbo{u>D^VtucFOI44&dYau-1q(gP4ZRn%5s`_NBX|Q`p4)a>_VM+T7?zbNcT0xSZ$xhWUHu=eQ^2-+V649M3y5Zt`us zp8>ezzHc~$4+jU)SNLm%gUY%;d<-~rd>z6ed@M+xK6mBH^xJ>? z_g%(>@IdwQfB@}7?~;J(w3|#vF)Q))dN1TFEr%VDtfs*>@iKPL@@*#`?aI2u5vmx{hqr(tPq9EnNPQWH` z5D+Lj6hxy)eZ{K)DrL?YRJM19!;2%x0AeCOp@1?7ZzZA7G~Xx^rN^vjbZWT*C$AGH zR;D#e_C%3786lsL@kHJ)Y>+*a2uPzr{*$~(olAbzKc8VCZ7+1ieTy<%nNHs5_V0Sd~v1Q+{q?_~zNHq!t52HA1oRUX= z@YOOX(siJrcj}BWeQP}m^Uhey{SXe}bAn@0y4S8;nl62PZ92PV?}k&|qpnM)q>tOz zru`&sUjNhnIm2s&Vh9LNVdUuEB1y0OF>RlN**;#33moL9P9)9n1*7PEmb9`EwW2htsc~Jew|E3@(>1*C;1GB_D4nPYE9j3gvxpVaY%mxopVeE2}{ z!IDcNzAsLbJy)*22NgDIn9NrAWVI9tqBO~Y-^rOF; ziEclfF-V3Z2CvcQiB@KSFs7S{Vi`g_!g6$$1(cqpy(}rkILav@E#GGbNi*RY^)Fw( zQb+&2d-tXrH*ZcHG2~@h#@a@M$YzDMDskx)7M{JtHa^PAOAFMq|BZD5!uv?4n(Hl3rk!x!#IKD!C-E-3qvq@OgYWYVGx%W z*{Sks=vw(U^@R>*baBl2mT(@NK6SbVdPe_+pGz+-qefv4sX?RdF_N@MkhkUw3A z)1yw^$N(IHaFjfhI8J@5(G5-Rr9E-nDwF=!GDQBZ^QG;43|8Zyu+*@8)sbZ~Ek|nh z_}1qAq_xq0%Q)Hon?4S2lD~=@ItAICgLXKGrQ_QT|074p7@==yp-wt$EA7NUJI-+J z^>JhkiKwGxkRN$pd*VdlpwOo*U8)Z3^=6q&j$H2<+~z)Af`jZzCf)RVd_=vGzvy~&GJQoFXrzvZlg2(_>POvK;bP3}xP19i9sL-CK4D-a zz0Dv)4r;Po+sd)gUe!B1IkMqKmcn<|M`zWB4(*=_Xg6TUwgV*WIIdf+grL_v zD`Uc`_zoV6Pf1ff%1b?!hommhSz5}c?c)cnv$Q>RP5<={C!h?(_gopv6Wqho@lkb{ zxcavC3{COj(fFZ-d^s?;x5v_@`bf)>=lS3Bm&cbdo{!@};g`aPNaJ1Mee(Rd^8VcO z1zs2DZQp+zP}hD^TWlCh+IX}Fx{m&(9TnOfoO9ZQOC|KZ-dkWvC*N%Cr*WjI&mOCD z+4p$?J$vMxHx@jkw;cQ2{{eH0Y#Ix`Lzx){s@b`QLCPihw;UBJhVr~9JtvOKJBmjQ6e)MoJessgXH}3REJ-f~ zNCpnEqiPo9JtGxp#!9DgZO z;@B?%4XPX_edSajqfcv8P_Go4DBSAb2yl+NbF1g7#ApvS<~)m{67RXzQCxWU!OXC zx<*xw^(yG$N&3F!X2w1SW5!kcRCt?yeKdV>XM214)4%@fbnn*f>CyJX$ue1Z$m54k z%C`(KxNz}e4OaRVe!wUK;h2`#_!^<~7j_Ib$=h2Y^48I}Mkav8u&Eznv!t5X4-n)11 zP8%ERHCmW4a(30eH~5BG6OjiZujuQH>uc%boakg7qw2{uzTspG#^HPG>vgP<&Afx} z;6Y@%?kgDn!uWkFeCt;7y}$jS4lc8h3{o-^jjBd5F}X`~!=J|+$IE{=k0TLK)1+`L0-DzYnOG% zaE7K`xOe5!rRn_n^ELbr$JW?~NMHEZfBi$3RIHIdw9&ScS!u0&cb~IZe|U~g z9Lh)99xT^6TC+MF?`<`1=$s!NK)W+DN8RBa($TKZuC6q{A-}vRkKpK2K7$ieDb3rA z%(m|{r%O9Dk#=>N(8f95)4l7~H>$_L?HcEJcoTd)8;&%x*@^PN!5f0NI!#{MaNBF{ z>T~EQE@v+%%d&SM{K}Wp$LO#6mVK$=N}keJ?5#(Z(k}5HbmUN!;iAU@|D}iKyE0?0 zwMV?**s)nR3|1oddy!`y*c2SmTpy4x94z}-nj|`YqiuL)Dc|DY)9*OfpVl!}RAzvY z8}rR(r|){dxsTg9Z~v@5=o_USjscgz_k%;vv$jvV`TS1x{)7(hNdDyq=$hv;aDUW; z8D^u5FWjfk<{2=+0Pp0$496Mohb97gscL+Z<4YS?51@IxEX92MI56`5xbU`liuX2g z-xP0owl};Ee(w3Zz(~un7vtJ#g0_H<>n}OYy|k*dN#8C_TvzO=_R+uL4C*h(p1Yra zeiD^F-h*!x=6B`S6mm{ybF$>)Fd~guy^(Y6d$}&obNb6~#Gl`pVYwRR9%(pwu(Wf$ z3+^3oVIWNhI{5a&DZvqPIY*<>m*;ZnKY3I~bKdDJ<;VHvSN=&K46>y~GThDXRTMus zw0xflEOdX@@S)(KwD#xqzTrc{LFs?W@Fw`V=bsBiDmrw09l{}e3^)-5^XhNEpT12v z7Dcg33ig8;lJoV1z8^2|QY z9@;243S^W-!mJM~0mMg`(IYIXc`P4kVsK|4Md+4J1@sCyMxxD9O?Vn5*yupUYDQ}D z7KfUA!ufiS;D863+0}g&k|(7^&Xj})4+mc2xXaNc{p8viXJ%j#7M3;BY4Q}JQ!A&Z zFC*;tMFM)#r0_h;B~TvE2>g^QOBud+{xky0PznhB^6*0x@j#6NGyTwP7GL#zvAc2zN zuAbGoyw$C=;BOYoP7O>^i1`x_;SfF(Fx%_uci&7`u3eif8FXUhM2&v>OC7?G9(Jas zzOlPhPLyuW3yc-TLvT=~0yP z>G|l>loUt2@zm*+>B^PM9Z_z8fxUCaXuPB8&kP~y*Xf(x#JzkYeKPOjVPQm)!70)g z!7xpEgpmznB1MNn=$Mc^7`C~}rRmz&W_GPi zTla@Eiou+-P9A^w!wtwq&IlEDZXL@H;#A`wlq?AD5PIQI~EDUSv3OnD3GDdXC0uWSKnYWHBh? z=bU>Ro7*+GbCSaUap-dQ?s{p4CJg`mW~7~QBx(m7MwMGb5#KNl1Z5%zasZL*I9E6= zIZm_%4kzt&aimFGx=R>sgd=RsOl+Mcs7Ex{*2lL<`$uoaw~=T2z%HQY@##X^j~QPb z*med={uXP1G>nq z+qdiV(s$&8HkHFekH=`1INGNA50aJhTW$u*;H~~SUdRUe2;GJAr2GAK&|l<*yibl< zW(0C@33`IMu3pl*8-0ianQo>Ymp(_%N1x6-3uyoL#ai$Fahub_$8;CE(UCeQ%v6*< zx_O^$Vd=%nLn)JY%)B(vhDwzx4KBw^`>{V-`d0d(zQB=Br-+u)dZur2zS?tcWAlFV zvE<^#3m2Q#Pm#0Kjq+$<@J2s+R_PQR^EbD_VMK1(>9x7mx9pp0#vk3(phIyus^~zS zEs^@GUK>31nX8ebym!C*vOQ?q#utatosKEbWSaBgc%I6e_1Efc#b=H)o0?q<@)}NZ z&aUCO<@9o`zCD+OI;!4XiX@fLdN`-XY)tK?`daC75X|}akGz>M<1G(-5xqRs&zJnv ziLxq-2FU@p3=pMP4hQ>K&Qp8FKeS=IT6*OniR-+&W%8?D96GrVC4GW3m#n?;#o_eQ z9uq(K*niLf2hGq*G0HjU2^^R6cLQm>Oy~8m#CzNL9~#~^&%N>X;(Jh7;7!lo2HxkL z{jfLhq4(rw>v(>aU;9hiQSB7kYJ^$+;H6V5q33D4X@mNQc3FPPZZY%M#!UeFViFqX zeP5rJ=J@vYd()ZkU)+>0Z=yzt2} zpj&y;cXHExc_p>G)}BV7p%5_QSaz)M%-?7qcS;wa z92?C{7)Zt~ck>N{;)F7Cx_babIkt44<;#@eNO1HH!HE)HB{X4VG7BaYqr^wMNGUl6 zkEG4sT>&Jx4uvb!$a$BBc=jat4Ch{jwFqL16HBPmkdl;hqvmV`-zCa|AKEGBqQor* z1lNoklzzBd#s-Z+av1TtZ^6-y9Hi7!HYiDq|A6BVafV_&lyw`=FUnehV3d5}hYVdl zNVy(An;vdI433AMuS57eK>t`-Jv)8-oA0OdmoB7FMqz1Rh;q)*lJoS`@PTlc7ejex z{5o;+R26UiT3gQxBs3|cwQ21zpIfT zeWXSKydv=#?mFT=eUWj~lCTu}8U+)-dF0)&1)Qe+4?otIhoXcmorPc1{rk366i`Y+ z=}@Gk8%B$SQqm0~F+#e9(IMR>-68_gQX^&L7~PB>H3nlejEDR8eg22Nc73k*bson# zySdXoM*fJmM*~-eeyfI=OJKsD4Ty!hp2x09C8D5D=cT; zwWVSnpfHW#rld2ed^WFD3x3l)c!_*AXpTRi4qv8r4N^UGjOJF!Jx4fx%58@RruQE<6k_-tf%!pL`4 zl{dmsfED}|mk99$662G@myUXc$8XS0%cwx9{#tN!)MfYMLyL5uCXdxICL=I?J7-G7 z;mQ`_8sY2asqu71|F)8DkZ zoep_iP8b1SFN2%Km%;U#Ek0Bj*xS0AV4C!sVNLM?*ycTbDU`kb;Y6@E&hiAhd}_z+ zlf|zj@|A@{;a=a+Ygcr0itQU_vJ!0zAm#8LfRu3r%RzD+>$u zxm|QA3k9XnwV`7O`#?+2CBF@i)47E6873S<4_^jcz7`#(rB^b$FK=C#7%%Y+Z1ro_~<2O$i9s%6-Tn5gTSBDCV;xTw`ofwF;Wii94Ov9I>QXIpk)SRwe`#~TwiFw;( zfhe-stD!~MM$i5{$93=1tA2)GmVuK^F?8aIJf^J_G}+y$ehc2Vv6L{5DTN=p`$TbD z4thCfe)j)jr;p+>mD!@sr3_QZ0%kKIOupur?A?9N!0Fo;dUnhp?D6eAD030ST`28IL|_kZGZHV0XB~tFq%a}rs-N1< zVBDo~RfqyO&e%J@sYsB-)1A=;hX!_8?D%u5>z_9?DmlAxii%KP=OdBPCu`KV^Uv|JCOkbB`ug z$bBvJcn<&ka)7Kyv^ln~!+7n~PI@F&;?esT+4v07t%@&+gQY`GYBzKr6wz*7ODOhg zsdF60lG{jn)Ni-rX{=htJ@t*$Qe4FOB0lgO|f&fj-S35Fyl$aH^JFT3Dl z?H-Ti7z2c``l#ej_;NkE{G`MDsf2D!n>ZvOZkFzAHzPgwxFvO6;Z8!9u5CujuFqp( zAI}fHt9Bd|Vmd(tQd*SGr(7{X))DPrZCtuZE3sS{P66f~O2Q-&{I#n%k*Qc!)Y z(VSC~m%kvy(H{D^>MQq|=G}8wAp4BsNuf+JF5r1Aj2>%=DRLtYk3Z3*=B~wfEG*2G zF*4j!R&Fq${(TC-x%1iy(Bb8^(AudR8U)UO76;EJhQMtXbNUI>Dg27{PK5pM6uoJSIjWdBWV`{#znn~P$oa(AoRY_!hq&z)rSeLF9H*EX z?eEusv%sxhRsL5AGB*|ei01+PH`Zccn`JL2IlPFb+PwCMXW%1;$mTE>fbVMBIeEXu zz%v;01eq_Fcfy z(Fb6;fg+KNfWwfgV`vOve76dZ$zL(kO_M>E%X7DDge1Kz5WH341@<!R`E7U+We3n8AORndS;+GvO|k=O@qe+++d_=uIvD;3iu zJ3aN>gU^p}z3b9FHZ2FcoWU(GO%A#RV;ilw>m83*{wcTNbAyT2b<+XwUaF{V9%t19 zRY>6Y4fR4a;v)rxwK+Lk5&fT;>$1A_=mHIXu`E!zWf*?W33h37zxFyuY3bA9`vgQA z`bO9HH9wV}Yn3wH|E}EoZ+LLgHh$(Tw$=4SonA&o5)*<4S*n|T0ZiIj8}M;-C?qw? zF%wVO7;i{3_WbrSv_6V(U(Com5g!Tr1y63r7e&rX$$X*~hK#R7eg&*gaDWM=lN3f( zKhor6#N|`^hu$}z^5;qkrVlXFHk*-+iTa8C=$CTT^|I_2fb90B0>xB`Bn4?XbwX9w zm0qedz9XTo5Uf8D1B;mt9H%qC8TND1jc!jBf_hR*e@hfvHKS)kVz!YIlL<0r`A!kr zS3v=|(*XL=NNVMD)3EalCFal)N3Xl826vsk2N@-ic?HAuct(ta3GOdo-mo~cq9vOL zu2Y*{M+|}^&|HZWuSPAJB5!Q7b1Z;PAapU!F+>J{Q}T!lpNk4pdf;-hWvpI~B`#`hsDq z62i<{b_cb;&3E&Me2>=`oZ31a`t2^1==-}!{?h#9S@|6;e$G~Xg zbUvT1EFmz-5!6+-gSM(*?SSFWoU<<9jO?9v)JB!!ck`>|oVV;<_X-wYTN=*LaKr4^ zL??9N=)+YAtkIuiw}5|XT=QxHU}lQYdPJkcn3mDct~C)HBGhfmsNUbL8H<)|XKi?H zEmnb6=SgkZ{lGUXKbw82HPmCb+R~shn{MqimOwSb-7H48D4$N>{@~fd0*rgB@EI6nO?5O{7JSB@qxoNnlP!zjCRS+yQ>y*^AZx)*Wy;z>Y z3v~*n-B@t$Q!%*uhLVW2gkA-n8?>8q>!WrET4n>1@_B)i0}fIeIcG`!Y)1-kyu#}? z_n@sd*z}_jSirz;<4%yQ(T3`e!wq+<&J6X=Zr(p7Nx-`&xL}<0liRh?Kg~RWJoh($ zc6ew{WJu^lK=zS%x7@|kNWN9IhB=M;d$0Wetuf}*;O`TzYl}5yC@dCLMxbAl$Y3Ks z{^@;W!G}vmKXyqG&bN$)ig-PuKplE5&57T~>UQ^z)FNp$x@d}jL6Z(3P)BqnkdWa; zCi!nWxNvKVd3ch)X96Rmit3#6v*(!*GaaSt>IAX1jFVs4Wr$E>l1I%6;@w@K=uH3A zZc?ZFpO)Sl6XM0iNuCF_)qOBva=Y($5PN88MEoX04i(|v4ZyxHTT@YUJ-0UlmVd%q zTtKC(Y)Chp^yV(Ll36XqS81h8^=yA(Vc}rH_HjNfhs%vpD1b?=?ps`MhS!F{GL}sg`O#&}D@WnJ(yFP-COG;t59xH`BbSTtf6OT`rIXV+JB5 zGA4AgR-FAV@$|$GZ>oniBc*xYLCDz>p1@Tm@7WkNAZRUoxmOrXqBQeQC8Jg5t^D0< z&KYqE-}K@yRQ1L6)XqYYwD@jI1+j0% z)F$;YkMK&r+9V5nci6`NX@o1gPt<{^W6;$0i(xMhKjja%AIXf|4oa*IkcBE^Z+m=J z4R0NQIDh^FI47J@@nAyYuX|9BirLxX3r23F#lNK9;PcY0p20~gH#he|rj=nYB<+Hs z-@81CbS-faI9()Z&W3}SE~j&3fBezz$7lcS`*b61*0_kXEw~t=297HorSY(K^|FDn z^e+EYvFH4j&Ic*Gep%pqW}tQT``XR*>st*!O~#xO!U&tcyUtxhBu5)16b*7L%rg6t zbVj1iOS^S`XT3#%wv4@*zXFw-G-!*93zm;J(vwUar3`-PwDY_Y`=N(&5M|%L4!~qK zDP~Yx>z3^ickfzxh>Xd%hXL(+>Ew3(>@xJK*@-5>RPV&Qw?d(NmIo>#3ue|=Q!>sDX3+5P%+ewa*&>xI?uk{!WiKefHwfU#U2!8)+Z9}na#r%zU zX@rR$8C@JBsLd#_=s%(ZJ4?%|UmD?t1t;@HeDxA;N9@D1fv7IODYPBwy-zzmxuZ2y1$T*#a+ZArXp}Ck&V5V* z+g~pU+zG5d5xwsxA(N`~>u)l5Q;(O138C3YT(2b`)-aQoaWu;mWXLksyrP>}$(76h z!B1^>7+gBWeZFS9dv#1t1L`4wi;8W%MEwh{l&GXmQNMnf6!%N>zr#ipJnL(dl{oY z0;4*JrCARUO+XQx3oF?abmaX_2H8e$jA3I+bz4 z@+OE(ntK@dm>HoAv{fK|mH92N#_KVfcfX`)(^W)jS1ZEigH%paQ)CZzH6RtuUajl& zBR)w~6OgQ%%etbGcR8bfVS3h{)alP2k&b=!hDy!m7WC*yq*slCGMd^V;+?ETSWJR% zTHNDj4BbV=qNG7*T@TXyksHmQwHJVZn^xzxIgGL=#&){UTBufb}7L^xv(9{<&&=P0kOfsaSr%x38`F z*sm{H%^=?ggDM$!aD)kSKbn8+M7rry+_V>?9L^V-^+wAV$H&(Q2t73RFs%}%cWaTm zXCyM}3C)ZV-fwP?VxHh#?g|oiruU0y1q^;3R{nSN1ezx`n{;=$9}~+guR`7PA}{!E zFGt?6XK+FL1j6(X*wIFM72i&Yqo{t%Yp!a)b-XSxw@!I>Y>^{ktVb4kv~onbad9PUoiu zO@AekE>E~yrt4U-*DZ5hCytBN@R&-PBk1M70+UK((enNg{wS{*MHg)n!r@0amDHa$ zvjHOLgZYzkQxP{Qj8&|bG-kU*VBcxA!RRWkc+Rbp_!J&l>`1aFaAZu4_)^&4wDmsg2@C0LxilIu6HvYQ-TA-4Z?Y%?Hd%PbsL=7~XWUXg&zN`#Hdh_4t zr|04r(nwwT_v3lss=Z658M{Hpy7zwNLd7?99=L7WKFt`H*?Ejfv#bilsTMP8)E+Qg zcWIYF%=#&nPXb3(0rP)Xnmt&6Ww$7&@(!y+>&n*?kMitbirL@y?siaS?FJ&*d z`BcTr%~oIWX}}%~gxUBi*!By=Q+S%~vlqosdY2`|%lPewG;bguHpOwrHuStON<>ye zQ_pUxv-5?KWR-e&yiMX>wkLjhmDfy1t9s%#OeLYIqgm>)B#tui%gAhN9r4D3k{pZx zl8>q}@8HFEXQE}!(|ks7rP@zMoR`NB{pI}}=5;E~U1@G{;MKhmBU#`oE=Y2G-MYfi z{Jc>i2_2>6B5!g@laNmZXpw;g$LGkMNEAnjdWbUd4mS9vL{i0w`JnS9>}R}b!=A&l zJm_@A!IJo*pQWVJ4W=clN#4Zayk+{gysAPV&vKZEt~}& zsR`MMz#cA6lA^w$r<$1^Wn3GU=RqAiPvZ~CPQ7~_Y7>)kfOtaQ?Vz(IIhxRqCHx(H3Wgf zfAVqtcI)ouBSZcNzSQ75WI#0n&rw*&u4v$0o82__`HLZqksjWy=nIs*>IGeN+zJ2H zS2G5#cM%CrK%A%)l19=JI^p3u;(g1kDHv}T^m_EfY;B*W7KehXK85Kkx`#`TfH zuHXHcXsI`^^ze5C|Ft9gt5ipI-e~1R4{Bm!o>T6Q^0Ab_fEXrQMj_92rG^{#OtDK+CT0?Ow+{4Q^*6n46uXs0!|!-?#I1Vm<`Sxbpj3occxnB#6@} zOgLoMJw2>zpXx2&KMO0WXVKUK8JXBGZYPla$}{8%(xsXu4S^nQGI%`82U^H}C9FsIR3 zaZuneLdH6f^GXe~6 zC`8_MY}%jh51kC9feWXZ3NX_GCAjs?*kHx?g_pKHyY9BK-(le@y}&rl=i#5x_Gf(Fh{}5*hx9xc(IJyZ4onjn!Wn z-#s7ew<`EQy2H%{8ItI!5gnbiVDaU4&o+UgU>(9U${v(@zEKpN_*qWX8W=Ng`IRT% zD(Ks%$ZnkY-}6T!_*Eu0^oi5yhKFg9N5HgfflB?$EICM*4B=c-a0=V&7|uY<5wYc= zm#u9XU3)V^?h_s7LXh*!!a@tcaO#EGsIPT`u4mJf=daRPG9<5((Dq#2`%H9F%02~h zJT^Nx<*!X5m-;&)wre7odWy@sZ8qqo(YbNjs_7@oO*iD2@8sbI7-eX!?%GK=jCFH5 z%gz8U^skp}#dgIEG%obu14CB~UYab5`=Sjt=TdUTZJLr$M)ZxFJE?fL%_tdsZgFV* zIrfxRbRSbGC*wQRN?cfyaA;{>d5_}$ydEzls^F~m#IOnAE@`-wNHVFn=#eiR zr(e-!e48Q}y!NDuWVj;72B%*=H2tpnIk2AF@w-`pQ!-p_f)s_|4 zXumsVT{bMCTmC}d_tQiuxl~+n=p->X&GcRV9=ESdM}EiHqe~TD3$MQiW$;i`Qb0Uo9F|w_QtKjx zz+Xk;H;5h73J(bjIOz>+I4(u{1n%hO>@3{Qefx6s05wP+>mT#jpG*6SJd9P?*d+_;-{PyFUgY8MglnqRg`r#VF!Z2Z=<$D^ zy0Iw|iHUl!jzDP#Q%ed;snORQKbW?(=~2Yq$m+biUls z?2!TD{0 zzb04roxx5EXJWc~s2>V$JOVkhv!h@mbJPfl`k(($O@6B}0grdq{&5FGe9<-+JkiHq90wsJ3gNDfDgmy@9F;<$8VvbwX@Wh#+&2)X$(yp z>bVx(#jwRaiR1vN!<&-~w>Wpl-b*@Bwh059YFmw=wZ-Ywg=)p?U#{)Gp%zD+($(K& z^t(%;__k+qV12tbD_yiWgrU_TW&xVH+%wM4yG1E(+~IlG09)w-`2Nn3o|iKNchFHR zY}#+SjiqOWF9cs*pkpi@_35Oucl9yf4{x(Er%3?H$+L#Y)6*(DcL%m(kr)z53BR$g zy_@A`;^5!@wQhUwht7-Y$=e#r+#;YupQAK=Tv#jIt&?6F#f#W{%8~Q7`LN>LmKxu& z154VNlof#rUzhBf_qg=Ow(7Fcxetl=xY&4&{kp+Ws=xb&UtS>cGrCPFS0qD(Bx#Q~ zO=5@QBZwGI@&}Jch zZ|cE^1Sg3PB}0MYl&O(7tj*)zr4JAppKdZ}qyDb8uPTozGPWChdv~quVzAl2m&M(C z6A-V~TPX;6DPeVJ)<9AdE*vpg=XmYUSh(7DY$@ui^SA+OUf*Y@TaV1Ig&5NS?& zNMlBZhgn3ZMfCLrdl={+ z;W)p$j7rm<uaHW<=dti3+tA6T6p9s;8sh@Vj(9I+Mb2L0rlP zMit2d(TA$rw(_;8f$pj9=X3oN40||n`D_};5I3o(QNYyYNlMF2Op%Vu7qWrai{Cg* z)`pLz`xHapLM!AOG+ScV%^3>)pFc}sy<+L45Vn2?nUdYHi%QF_%3Y#O{SV;LDUixH zlak66s}~3_^w|F5q^{^8c(vnf!~vcS&vL<@cD-4#CZO(0m!UnX@g7j^?aSi z9kTOocCddl^2qFHklwuN%jhe%ij_-6EFEIl)a7nkg4g1_DMiZFjQm!+hm&gieO9XX zIo7`p(rZ-%>y5l**-xb0TuC}!g%O)vv+&uplqd3I)t#*p4=|qCO=%0dpg#0RI@}P+~so%r|^OlWr zU*kICA!-i_&lks1@kJ7E@bqLIxObho88ltU_k3% z`9YO5p6S3Q+Qr;$q~ikWtM~E%DUo%><;|2EfAM<7;?E-#LDE+ruPyUV0b+$J@U%7m zCKEpq%c&C<^|9*}_G0R$t8jEnLVSp{4vi4KZMScUtwzt9Dixf`di*?%8a_eNNEu%P zV19g27OV0jlRcm`)-m)Q^dYb!U>S5t1~+qCsCq#ffs>A{C<)aVxO4o>abEMJ)9b1x zG$E^|-6%u+kcg4ytX!t&hOdAd3cRF6heNI!y^0gAU)pLfD0jxi<$FvJXGoi7z2W8g zFkF6X7C1udqn~STw|~2R9bw-)G3bk>tZ72#=rn)ygNQ2jfJv>IfJhRbsv!O8rgT}j zz@h^ts|C)6t?qT`@30ta!BAd8Yc4xjne^dV=7%jx&Ozaaowzqfy8*<1V91P!Cuezg zrM=iX(A$e8+mChsU*7zA^?B=6Hmc0|zo#hV`X#`geG43<=uc_@qK{;{Z2u^$grms8 z2Y8ZSP@t(CE42CPmnBDZ^mzpOh@H_P8mD^>zh5c$n298|%+Gr3){?Y=;{!c^Hi=(a z2D@1LSfRb|}1YV}EtT?~X;zUV8p0xd4qa=rX zY(TJ*=Upp1Yi#^|^4GC*Mk8O+U!X%-X7K|f7+cO*9(Y-EH`Wla0mTS`qPr_^Ud!Ni z)9l;e{FCeY?k;qD*z+%jzQehq+Uaj#|G_vpsBDb;8EeERX)1;C zYm;{lOdlDx+@T&@SX>RcP}4$QUaf#@95=Q znceLAarwYB@QV73Yt@)wd#gl-&$;1-NGz)UZDxrD z2pDg_DhB#E_#VzrPA;^#r)dsQTRp`+UZeZs!`M!^T7QNTAPABlxkZnznigxW4Bw%x z`q?mFY!?hfgQDr|vbt*fXf4I(D-^4qm$hsLvp5b5-lBi|i&%dG4%rL>1XwL;uP&Ro z1YZn=PQDs_Z5X?phJ!+>o}u;*s#Dkgos?8L!6cp%&^@>D*&Q=WZKBrLa~JDq3cd3J zJM?~dX0Dm`BreA9IA?Ns>-Ke`rhGy>-vR`m+wwIAk(K`*VR^pn3$Xg)DHt2wYha4_ zvZsn(7ojL-B78Gss_t#(ay;NGikggckR7AP@+frI-UGRj;Mi4rs zpKSmhZ;gI;>f{i_9k;k$Q9PxIr;X?N^UbLWseNhB6$h>dgR{QXHLPWN&Nk7uW}W(6 zPW)R3H#SmdUCAAPBCg}__<4=llDe+1V1B>b>`$Yp35s5uoQR z`88V}CJQXc*39^3fRT-`XeCBOUo0-BS1?|KE4~BjlB*>fl&%rEs$jZROm_N{Br*(+ z1@+WrX8aF#;uqHRl8uAEde%#&ceL-@sjgoSh_*D~CH2#O?6{#l2Rvswb$Afe)VMQK z41c=oZbuoD$5zvHIze~WCyJS789h#k`nxdo2q$0sO9A3!i>yXyU^INiM<=6Cqh%_J zIz~;@@yW6|STOl5N%-B;9VJ^i1~M|U_CBTGpzh>DJ`#W*g1b^?;`tzqHD*%f+t9C3 z7xc$U^{~EK;-x_By7Jx%)*&HewBW_!`^9eK2kill7gW9n;TlPBNNMrL{>fyu*W$NO zx&BL@F-g^HSbmr7pfu@18mfL{6_0=m4qtY*o}dNsIdl3go^&Z)`$c6VPV8Kt1**s# zbC36*K9N-UnZoHfS6dHQq@2^mTyAD$JOQb_o1htp^~kQOyg!EDwD5fv-#^|$;;ha7 zMwkmC&!32azTY#3^5y4%xtQy0v?TjVTf`IMZ)g0y2;ASo|4T@b5JHL%ZkF#Z{u=?; zi@OFCIK-rcK|M-Iul*;zK&wx;=?ua&iyv{|hRwzc&l+1KJFvh-N( z#go|BU?|LgZmy)hPJ0U6&YZ`UK0t3z@h7Xdde*%m7N+z|22*Q|M|(hhTH(lbAWf?4jP6Pc$QgM z`VKH6m)iW?9j+zn`>8eC^9$os4~;LTLom1K)T&nxI(Epyb955W(yd-opC_u;^W6j) z3L)BQJEf}*dWPpk17r9@8@`OL982_?bgvS~1XC9!@p)noR5~gIXEoljz00_u0E|UG z9~^wCaJ80Vce0{~rtMGsZ#Fz}EY}Qz=9y=!=b2TEE5kQ`%cMBmhFHA6p5=w+nIWZv zD7^d;9#{9V6gCN?SyjbbO!xMg$8|)OSzykL^U{yJH$32pk#yCJll+Gfj*_9>t4j+D z9@v|32I^Ett(pY=%U_Q~LfWYUsOpk6uO-bY83o>QLuhD1A{FHW52XB3=aeC(j z)9p;)e?@PP?pGC!*_sSSx*mz%|DzB)@6PY!h`?mqWuo?8;Ece)vyl$Toy+~t=N52= z^3^zA5Y3LL`1i)&*Rb2tBay*Es}m4&J5TA-@bE8Sbx}ybBFdqabAwx2A>h~X)X7nT zMJk;lbuek<0W;>qmGFit(6Zzql{o5JL!E5E`QKaDoP2W$QPUQ;mIyEObF5v~PUBH& z6LdP#R@8|J?cqo5Mc;W-4-IR`{`U4u@a+ROc z!4DA#PpVaS&*z@F1ilb0Ag}K$UpuN4@reFdV#!+El0N!=WTa)8d+XWB$?4&YwhVoGobI)eA?3ROu(;J{XiX$Ze{A9N;<$28@ssoR zI)^Sj+$Y@2ZhL;B3y`G<6U^-~$i?IVs85qOhBUzSJ<+^7>_^hQ9shw!_G95UB6mp) z9#m|UW$*D`na5bNCbaGnKJV|zX**N(fM|!|Z{(>;H&b+j5%{ zB60$T>=nsO`ycRo)V{B1s&smS7B@7bZ*i_rR}V^In>d>w&U=D@x(P6IR`rr)I3V;n z%N^Pv3Ax|Z-OI!{MDd;%zg424@t7Z;8l*ITKbu8gQ(PrQggw&%=$2=IzeH(3?V&~d zq5dN?!TGJbU0v;w8JThV*pxG0$%j?Y9K+quO1i%_eu~yp9@E6j5+_bxDO~}sdSArb zG&rOzJnT^EWavkXi@~&vVXQ6+r#0$RDRL=0Hmv5xfArCU1!&Fn)fYo@5$kVk4sCoQ zXw6uN>Fg7?yQU)=sRcegOa3+G62oh7g$s`0*~;R`M#Ow&34r-LJ$cgJwS%{-Us#2e z$l1TBHgqcH-Ayg#6=@kC+Xl~@qXvN=UfiZ1P1tra#iw@p)yN*ISnMX4?(zHAsL?qUQEiv)HIM+OMCpy+*u*aIC7nhi~sg`d4adxh0uN*d+5$OmiC=J{25A600?m)=k zweh>x<)GA@#RD^h;CKN@%z5vMTL;fgRgauCJP_raCH>is*_nI=@Bh2*si^p%<{bjJ z*!w!f-J7)GZ>~@D9T0c~P5>6n%E#5d4^YK?-D`d#aR5HN>)|VzmDJ#^I}* zGy#*Ro5JzIijiiSEixU?Du+QuLGe{}aPY(4pDh-BKZDXd*y|NvklAzj4)|E%egHa2 zQe6vvPXO4c#?7;(29@NtLu|XkV6E};LLbEYv1GoSb|2-X7J60fI9N9p@}4RR#@~*p z=X`e~TOyS=N}V@ph-YuH0V$6OaHNO&7yceJ{$WYYlcLUJx?HzPcTX<*gUm4+=z=fI^Okz-DZdjP}3PI%n|2`;VkSmoW{yY`b{g&MUu) z_shc;|7+H|ymtuqBiZ4aR==J+MLkRnY{!f5&Gf49OW|Uk?ESI`Toa(+zX|Jk5gxrp z&P&KB^r)#AIEf&XRIXdgwbbz>A|D(+Fp~0QSKqBwb2wV~0{_By6PwjG>uiE@tBVW3 zM?GR3J3j5axs0uuITe$7?v-DPg;UfV383k0F6Jp^q`4xd?p2;?SXtT8{INSvjx95+ zhp>R`q#N^U_CcEi=6Y|hW%F3UDgsZqDd^SfD9$_nKen#^)E<_GA_C8|`pJyJ=Qi3d zHfw?DI)a(sL;Dz1Ds$~Tg>L$^!i|LkQpQFAuXvH~``g?RWM?;j8$hPyc(*a9G zT|ZP$Y0Tu-aK?{L$w)4tO}sjs6@~5k$Yg5KBWgcFDfZ4@XA^jvxATGl{HG;Tk?OFb zneNn(1gRvt^ZYHNLK*21FLB7L?8G=KT_s7>fH?#Bp|F+UPX6cEbVaKsx>9{WvIcNI z=2d6?hP#INnqv@Y7CHT~Gdg!`Q*8do)2+UAzo|Jbf$OVm3Tl|jr0=0o_bcx1QO^d?HFmo+Cq8X5nK6aQnnQV!Kg>Atgwphl*9TaOyCB1Ra6%?f zTp=}syF2s}9b0@Mm-~;TA)F=`kAxu7)_8}r?XJJ^dML(b=b31G*CaS!q_r=Y*_Nzj zJRq@Yt|?oQT`-(cM|cUA5gU*+r&ra6&HJoUEP55j(S6e&hVClfotQfAJ)|$9|fi^Yi;s zij&*(+}k6`+bOq~y}SQz1*QMy+@o$il_V`{F>zunK6z0g1DRUP@=r8|w+v?`dVr~H zjQ)Zlu|1|XOqV*eY9@sMeR;_(j}I$h&X3$58xOHF4dzn$MZ5oP63(AWKwE_DD^>*Ke<~92VUl;?({C}A|&L`Kj;xM);m5NP-QptU; z6QvCHb3IhxRBm6}G)lkw*_G;-`ypbDg`qpo@|hI-BXliP+ESKm#5^9YUU0)Nl2!Xp zPN$df>V3hN-Hz3(~#+_U5OdUkfB>FVX^PsdUs!YGl+Unn(ta`=Vtsw}8}r9&Y$cE5kSDwmTOS z?CE$?@!z^d|0PApSqdLO#j?V`h>!y5H}uX438cf@&Dm(=-6xKD46iU*X~eJ)W<-`Q z$&okiXDAa+mYBuBk`0%$BiQ42Qq=L4X|D%*&S8p~;O*i?0N)A`Vs-tyPP!{YW{T}i z7!5Xu7f#%u^mtU``Fx{%wIU5phA9phqm2iy%@Ln?P*q8{EQ;gmh+M*)>YFz@!dpE# zFUz2lHk%F_jOwK{42`7$l*}8+!OZn<^?~Csg&h)K9uP8$pGY?AT6tBF!qE&GoSOae zi5_!NR4)R8Kw|$~x7-P#D*SGJb_gtMng&Rdd@+&+2od+wUmR{OB)H!Jx(v~%V zTdmvgm5y;(^2-Mz zff4iU{8ZcV-fKP06|m6f*5B)SpfoJ`@&D0u77k5@?b`-XLP|iTOQe+Ukpj{&LQz_z zB}T&-Flmt(9n#WL(mlGnrAChKW-$2nzQ6bTC+_EZuIoIHqo8U}%-m(zRuY$x4>Wc4`DK6>%dZ(Y0X=CGSbNHf#<={9NLY~)=RBiN=@gGHv-8Pt&I zdCv+L`O5U}ChK(78l}i!h|;3Z=8o=-1?~tIOrNJ-_4T{ns;~9iM9J9Dy6HRI-p`;9 zZ#azawBcTn9zwfLJs?uL_u*)*=FMZZRr&l2w(FWnD2316DFEu~#{!R@5w8O|kc@>L zXPqWB_BdfZCPX5uc?F^gW9W@ZJfNEX|(U~>BU9O zAQ8#oUow3No)yzFhxgwM zme7DlR=|xtSsb8t5T^F(w#`flQ!{^qaMsV^lm>Fj6!^*tK;^ zgW~*?AO+ROb2~*vU&Du*#edy|TU+|S<$0>Mc7xANs}x5{GaRCDEBXG$5lWg$c(V28 zBrNseTa!})U&s9eeYokDOz%Ivo^!iGD0VE-u(qNPQ+H1D)VO&YV3J;#O1AjO%#2<* zPR6+YmtJ5{X31rr^38dJJ~E=+Dt$<^q+k>>EN0s2b6p`T6sQ+*k;v1vV0Gh?`0@BX zF$)3i%(-%Hd!br_b;~k>#98&`io~u*iMi=COo4Dkax`myfw^+NL zPWkSKrGK3fB~9JOgGE-+fi6kiqy|LNGER(&EpyqkhKJ5txy|!GZo%J8xLy4MGs=2z z9YP~>jB}I-r}F^=qFbdrxD8L;9m7~g<8`Hc`mwi??_5OPXf@TM@?330akHFI&fZHc zkOKFB!^GMu`>Z>IO`kKWSCN0&3%&`y#e}VH7CcXj$N5jI8)I-ScKgDl$6E5`stykN z7JwNA8jT>!AJZf>XT-wEL7hd7!vrLV$;qPXCCisHd4!bnxFten`m!X{4#f^EV1axZ zrg|}pL(q{rFc5#8lO}7<>G)rHxTZiNm0}%@l5Tlg-&@W&h&xt3kGMSN&fX_Ctj4HI zdC!&im9LzhTL zO}sjtFY0&F4&Ny>My03$4g5A3F6ftD3Hgw<%lROE>dh6RD?Sv7+iXi`J$rJL5W_%u5 zD<=~NvC=AbvI|wlz*MD`>HI8(PGGn0eNJ(dC#34Zv3Dr1CmOCzxwCK|NhDbjmQZyLYhE>F5fa|3iQ$`gK5Sv&fXkw#nSp_)C@Lo{IAnDB zF=Tmx7W#1U2(O!d1$A(0*Yph%8+G4CRy+#B9)_)`YGP&-ucB!SbE#dMcgoad|e~ z)G?X2Q!PJR1glKMBVRpB3TZ{XnYIj1rD6Z(!C@qNEU)Jx-Z$c2J$;iN_t!-etvdr9 zCYSo{ix0r{aNq54E%=gbg!LeKtxRUG0OrAuhi60a)2Xx}n)ib{wZzuG8;cfEgyUupE%-s%f^5IJ69-1Es z*^BdieB@A)lr-IzJ35N?(=Ma>x!7xZy!FeMiuGF>U5?Fom@Ej5XxZt_^hKaPC)IB|vNhZXR*>gmRnY01kv#obw zTQRu5L>En_Gn-i@rJP_QL>U+r)UtceKW{G*aKxSBVTUgD7Pmr8$`_B&Q`OmfX$yvK z%269XTZ54?ds-5rAXeJ1?rFI4Q39@PF66yR8_%m26`P1h2ij{Wsl)ROsfFw76RBxZ zv=wl5^3A&Btg7sLT!Po4+HOQFQeQPrxdB}>JjeWo^eTMDqvg|Sw>!OH)`QDmcq#?9 z2rLW9Lecc>YoEPoYGaBW5y+7-zIJ~)pqX*wyr~UAWj@^ zL+aU&z(n}hevgA-qa~2H--c%t;hJb@vB>xf&WVB*qTY)Y&q;>dep8v5OTdescU`Nw zMOAF)dL|daM{V7)1y+F*Mb!YII8m*F?b4+;u=DY5U$hG2d%W}Luv@QBx5^fDJ!@p5 z&2RnVH0Y5D;uU!XBvi?(xs2Jtgddk zT)5O6@XvonJ(BCc-d1x|kP$!Ea+g5qT}!9}&DzU!_1Uw89tdt7=J`Ny(j;yLk!?q~ zN6G7#(dLt2f^LjqN2tBECUe5fIs=e|yYox4=>Ed_NEx#V+aT_;GjR3h4ls?HCoRxR zce#<$pfR3+xEAA>PP3q{@58E&6&$`6?QJFr5ae+2cIt$*tlZzW$sVqA zz(>S{&BU7J;b&!6XBN`;;3e)cs;2P?lAvll5dxpzvnH8)rY3ThWo^+_il$v4--2Ux zZ!K%OkWV1TTw=vfB`g|-XVi%%YZ4J2+}O4wXzvkF-BLeDdfH%X()hCt6DnX``G}S4 zYFU`;F9h|i5=4xb*CN`?-K@6Q`cW)*yf@I(p%p}UJL$V59EtqD?}Goz#{9tf#Sv7( z_W=`+FQAsk6wr1iOFE~=Vpq%uslQgI-NrwCR0?!UnhJZQAnTO*#jrr*xlRw>PiBRc z@lL#SS!Vu@!o7+R$vp0K$s^sRh2-mQ-_2c(kI@2tYo30;KrA>%H*`7*MR}DBOWjAC=1}O z+R<)o!_I9jk;YX$AE$PqA8ap!OWW`<~NO=JZ)M_Im~`AsN=(@Z5uY(3^9;jM!2 zYqKG$#=v1)g(Wk{I!3(CDD48{HC8Z1HACJ|(EZ2q8ns<{ zI8qfi92WI6GbCw#o-)&Qum=ly52}=au6GJ{HZkRB z8T3hLNaObM%#M!4nmX9mc;wO4N;)2*z@MG&cY(|C_XDs9crmH*oa00z! zbpOu(6;xL438co-Ar7#ruCDsdc@Te;C6KB>=Vh4NdX>a zcQH3JNF#JYAFg2!W@Nuep9+iL9yFD6-t^r0`2K7VZD#axT{+$2~iJJjp! z_l^ccu%4b|dzfFf|h;x}M5?UA7vq;;LAhbRU-(|o#tn#}WEiKhd z6tUo%0uA5Sx3%fv*b&|S@l4zLXUSzW1Q>_+vVq9L)S)+6O< zwsa$00`IL`jG8|qoY1JqAj24iz8|=PEjBbnv&U9cq7sqXiHnL~sYW=f+%(;BDXbN& z*I!rj#PZ(g`UzXi)CNQWhYot?+;t3vyv4r>kr@W7*X!4MK0<} zX33#fYj+0xgrI%V?(fjU#W_jFK$@A6g@SMU#^zZ6_##-3=!lK@47Wz4G}Q;GHzhv$ zX^Oyxl0iD_qmjMjYs?xr^WBz)!IrE3XXLbpk2}u;^cLwlDC0O0?!N{QsM5z8P z)zooeAT|T(FFJqNH*xxj)M~ze5aI4V zlq+3riRlrRYn*x_sV8Ize`*q>GAW?0T$^QK zAo#~dBr=Y&h?HBFSpO5 zQdAvAm6V$FuI5XnXY_v##M+^7m7-EY=R3A}mFDZjZ@C?s)u4GTRJnoWSuxUbp4luZ z#wJU0oU!-YO6Hq1jiN^zIUr(dCZ(rJnJ>5*>ijY`TPC=D!-m#{*ODyHiInYcHSQ-u zB+~N+!=**WoVSe}K(?N&>Spm0K<_fCY38`Sp5zBG@7!}S#$FdlZ>LhHny&RmVV?0D z(JnDY0IEjqMrP%U24E;2nYM2tV+&1$2U%Y|RmJf(K!d2Z_tFNPjY!u~U)4?1l(R^3 zPuT@K6@6=m>z7uR)s`|yipxTML{S0;q{f<%4I+9Uo3P2QN5d62Pk+Rs;t^yH*Ll8J z49K?)p_kJRu8&VA;d#mIk)Z{x>YgE8XDws!4OmoKI-MPyb6WfC{ld=ofZVXn?KeE= zs+vDT?RcXp;U`bqtU+EB`>-a_{m{U}7UF%NC)A7aGlJgDOSrUU7DRE`A$x^*3|T*f zdNv@S55_CVTL5q``e#=82S?>VXA_TAKbGHNUN;E`BcQOc>Ja&BWiLyxtQR5Jb{}nX z94XSg!H?HUhu7BSzJ~lJnRM6YM9}uu_m>akIsYgkiQ(3aXAYlxA?=dx5&>B_X8z9+ zyrIMIR}1LcE-26b7Cb4tYTn-4ceHi-Kcy3gvP{$UMa_=r!!hY3l8%#>j*X6b!|+iN zaf`e1fbNsIGztdJKnb#A&YOaqspLq7XY5lm{c-iZuK?F=GCoew`Rr|lXi^E5A|(~! z0a3XfSIw+mvOgO1j5}H*85_k9(PkoYqB%my8P7}|%Mj`!%-x#oV#S{=7VS~@2?emw?EwB)&7#uMNRFnu-(rqLmTznY4*7V# zN6`_<5ph13Ws!jiB;%>c)mYL15F24U1AnlbMBW~Nx8*Bz8B)K196+^nS3dtGlc zwKKKXa)PL0!fK`Q#j zalhMy;F0nV*XLqouu62tiP*%F!Ah-l~c5Q_0ZMy9h&`w^aAN1nB(B->B&t;&U$cU(c1bxyOT$Q$)!DKZRm)7WE2Xzib7d${3 z{niz4*Ip`3Z(1q!uO*56>K%-*VXRU!rD^!3H}N?95qrR`;-qP_R|ScPVlxILOCv$D z8hLy|XZmo@X!@4@!9E=QSwnox?;IPYHA!7i{v?Il$vGHSGK3* z4))0;4*7k^5Kfep(9_?$OkYT+_E_x*?su_9Y~k;b&&04g0VD}VnTw4Y((YI~Gf06O z%3trQKhWQdGBH;YnAoZ)?{L8GTCdj>=&x{JIHmD@J@~gEe8Y!`>mK{<^Q;A5?g#y6 zuixvh*ts?Ndic4^Amb%zbR;2Zu3|TEr>Pjix9sfF_hmeZzHq8CVxa}1^37^n{muf= zVlx1f@PZlVJ8t<){S@QtEqNO9uxde5Pme#A1h1^$zxisxR29j}HZ8{fTO^y#X*dU4 zvkS<8Fw|2!Hjd^tn8HdfBxDd48tvVjKI8Y!ppzzw>HG&%v@q9vOMqx`t-BgcZyGy_ zZFe-+qTiC+*dP0&Sw7a`2}~2;P+mV)k++E7Cu$$lGC(wWo!q%$>K=%s+M?895{9XaY5gQ}VtRmZ&A~zX zwmc_JlN9uR!hn#$uhmsdE`qe`6M-tB~`+I6<{6Nzvib3p#F2M>ewFT918S zHxUY5nXNQK(hOA2Q5|d3HnZ?H8|);V5j;)(;(MrAcw9v1;&*xEY+?;2skoy$stf4W z_iaIfaIjIhtyO#lW1vxOA&UHWf;v%3>x4FkFHR=yj zFSKJBdoOkpCLNNlCK$wMW@qa#0S9ARg4BiG9K-8aHZs3CnknmOje_>44QL zkcjv}`E9*)O&JbE1HCvmA1Y(ZifV+}@>>H=#`MVxnzeLfg4_<@ zWS%o}X^0T@TdNVbU%bORJv8hvU77+gD?dYrBYLjuW5pYRTndrbfIRzTV6&eZl3B&5 ztP41q*v;;r90J^FxAK|}F;1;63nQOGiOlS+J(vIO!o)~S~uELT6UUX(Y;R`^BS2GZ5?E; zt07~xTt~P;A;nkEvO-|*p5*7E_Z8yn@YfTcnsu4I7I+$WY8d({KIG{+xIE;0p;f~V zrx<~^rqBrL%MdT4iY=RR)=AvSbcyp^J)4g)81qB(?oUfYWEUHlhS^AxvjQ@S_- zrMaRw#pVoZ#W&zh2E44#&&^du%p)qbUq2Sy8~f#?gq>tnF7Gv{s>OyC{4=|BAksUj zPSWLj!Cm8P3!73R;|Ytc@oHx~E`K-7z7Fsmsl}~iF;#j0M`m6KjVMi>Tv`w>rl?{bld90+Zcm!Io92xjn5?*pXj8|H)=?K3|WrnQghH6;%7A znSNNQgki9z!EXI1k!GwGAtCfn9j*ZV}C`shJcfZ=*7wf>_k}7E`k)d`nN! z<=Fhq0UBfvudMZTMiIUnLOtH6;g-0-Ou$l#YD6E9#WiM$%8LO>3l|=JDFLyv#27nt zEPhi?X8PSZH`4kASf>HKFOMo8Q{%A0EnX6b0#@w#s)FyvWA3t3sErq{hA$0xPq^hn zKPQ|}CA1zYDNsbeG*N!cTQC~LG?^{BuUE;u-@%8^bVx;oCSbqo>WLEb)sF( zF5}F`buuk{(}$JAQ_(`N4>-r&c3JN!-8uAzE5QPEos>R#O)2w$cGw&>x2n?YMjbb_ zI%`Zv`n!pF9?{WSkCbiRl1qI_JTRQuek`2J{sRz8WBcKf5HUFPEbDI9R8oxld;YF! zWBAbLbY^TXpkEs2?$&OCT7uNDk%85aq%xR${a~TGwpQ!NjfcRS>>3#Z6!EnBm zGtqBY^930bN$8XPYI#A>|sxZAzK*~>nax?O0c%%$?GVYhvnwEon8IqP*2Itx0 zA47%+We(zUgr6rzy&gS;BviJ2Z1O?5?K_ujpkAR2Yy%Fbu|rrFY#^v=ZyhVI@^py> zO9cQy2$75x1Y7an3~=J?K#9UDCCujUPfH*GHiR|nCw3{0#ar+6h*$Fcd>V70$t81@ zkVDAhlvewIMe~%SOl-xx+#`XG5`Z;H8Fv_-FS2LG#oiZ}qpT^NSpDSr?_ItfZ_|X$~_a=5I(QgI5r{#_;?d%aJ(HLzzBWM*5u~ z&ffvof`)>v^Yq6W>8@(DV$Qo>d-S}8EYG`z)Ja3L<7EM(6-na1>6kS@L&p$&Skt{K@BNYwd4cENz}4G2;<1Za^&1(d(sI z5_TI0HwjMA`yvqs|+Iz;WQF@rac*q^XA(H#Ai7jx9NiRmO`vneSb_OGu4+dqNH&!YV=k z<&W&%efFQkTjWokmvUGTJvGb8LsnVCvUR+*h2wjbbq3^)Sh0Q+$iJY`B43#m-=$Ds zV8P-HdwjoY6W$SX6)7kDTURlNyZ&19vq8mx`=PEXby)n)=NC!lAH6tSUg>_Dev6EM z#aw>Ej31>Pz{#yt6SJ62^?PTW*FGZilDzv@XE83ZJ7XTG6R!N<^R)WP#z5H49Ws1! ze*WgPAuysIdKs2I)O1mqe?e=iU>bPYofAJ{ zU}yQ$+UUhJ+UpNK(e&h5+8YUCf(HP}k#s4;-fUUD4e@5d?(Lh;tKW&FtP)~U<4H*n z6>cIo;j4bWt~tF~36dcb%hcqvy>eZ-MZ+_44~iE!nn z(?E&}a#cMfUk*sM99Xe$-Ws+cbwEo0{&_1_64|$7&0jbLCmPx>g;u)s4Gq)bs9l4r zt_ij#-kBM+IEtLr!J~AU{!~PXyth!Yf8F9Cp}KXt8c%0uGtsi}6-cz48CE;g9-fU} z&0)7qO*DoIZOm3{kEo2WMyY7>x`~?OJ6gRkX>ciuGCLR_>f)hKt{*U)fw_h5`{Zf@ zqs%V+ju0)E>9sdwSUjikj7!0b2mkcd!B$Lba=a%1opPfFvC^^(6-mLMZ7L!BKqBJJ zaJq8hEd<&pbcZv~=a}yusnkVSljqUL!%x=p&E7T+!92U}E6;s7XLp+f_gp~En~iL@ zFw5DThu8Es-lWDg4&HI_;v?6UC?xKMjQ56GX!WI^By#JuD`w{P9S4pL6Sd+=TtSv~ zMg?n2U8`=+b$6;|9HtgKUjEbDNL7M~ou6*fjg>&3O5!wLxil0Ii$=H#N^O60 z8sL*;+5{6w6zuM)8>wZ%Ij2h|`I~*Z@q*MOTPE$g?+A zho8)YCIdEz&MX%Q7v)6x@reAeTN;9-7)8ahLIc%p;E@*sz77>=wrla1r(WBC0`WdL zs#D$R&h@e7IDJ4f9C-+)+*S!nk(-F9JFq=9BrNN zcJ0y$7Am9ee(^Z%&KjPzd_S8Fo^2oPhAg3h*n|w3PcvZ&N5wZ{Q2oR4KPJ*pmAJdX zP7zA9cB*|U<3U3duS0{wPYt`FS2M60klE|lzjRj{QaaN3iCcs=yo1gURisY{P5N_Y zTcv$U8XvTdlR}Pe16<&C{|NDi=~J9(53ErWvNd(P&UX z_-vV5E#;GTyo^)1{&t=}J__}@&!tt4joH0)>Z#Zxj$b*=oV@Ud=jffi!k+6>K1w=z z|AVh1`maH+I{B+(is$%CK_8=D;}Y+sQa}NlZ-xx!dAI1vC@sT|+y3f?QnG(|Oe)y_ z>yRrBIv4XJzM`42d$JJu^k2|ve2LoXd;coW*~`s;^}p8ML`He3OKZe^Ihd9EjB6Ev zN+5mmx|<6p-%L3b3k2n7dB(X;r}Ca&O*up8kMZr)pJ4*PRGbtX<(UbU06|MWYWqHoA-*e@A;yhM1|508P!;xf0?cslkA7}m) zRqK0;^9J;)vrx=z>Uw5%dqcH4Vy3=|YdZ_9L2^hrEbkDenTQW6J%+G2+B2b9r8z1*q(a>q8CByGgsUvrdj2YHDe1j6;hi4}Ku+3{!FZ8bWVNBc`c3f5ya&<&X zNO!(J&8Kvy%rx54ONw2dXdQ&e?0j@v?!RX?0zvZlB0uHg$#i0?=7DR&^{Py9t z&m~#lmJL4TO>_qEoog!VxZ6aEYR?%A-0l^{=a=?WaR$Ca8n=;B=LotY^Da-n zgT>uy4-BS{K`ka2x^XinXceA*a6v!l<6P*@HpC}4pBlVaAtn)$O=0?z>uN*a=Cqsd zs|y?)E#vcze@tLws~o(lZJssLT&F(JQy+CjJ>GIuVMAEimAP`Z~I^*!Qzn_};9V6-EBiK4FjNbk!@ zc%wIu5T(WCiRel!lYn^CoW6uRJQO)*FwT38a1<~h;<5xTTK8`1tL4uT3v4Y~@C+>A z#ph6^-K^z+_}lE$Td|=PUjZ@dmP%j5^pu!D=#b1Q{c@IqCf$j_%I0ERk3vrODvNOz zmmaGYDQ22?yG;2+wD`AxI&EwiVQOmJq=$0y&Z0&?R-RmWe(RYo1rfOcPI}N=k;dKY zB+bwCuVj~uO1v9ZPZNLDj{vwR8gz_aA=LRUJkGaIb`0EDHF@3t+>3}_q%@@q&mexe zP)94xj=zjAE!HSWI}}L2d{|oyV)+>%B4E{D7%KkFb+l8qK(@H{Vk$-m@WU%1gx`Zh za?K4_eNx(loxWEHrBZN!8G?flh@BG9@`E`1k0DVD>9BYlk9g9x*AJgG&o3sZq&dVT zVUFn!c8wlW$sECF7pYUNIS{9*+CDbYiJm8?A&}D#%V|FjSip?%!$@x$wd!ISO{wc& zmZ6S^f?_%PXZEz3sYDgg7;Cih8_P!Ma%>jqAmcon!ZQyu$6|buK-6~nP3D&Shu{r2 zWkFf4a+Q}0PoY99y+iL05HVGHnbVQ4wZS%`rTkwieEYd=#lcT1j%$(hSBoYikaG|i z0e#}8?cpB6Flc^L*E%Sel5Iv0cBOqIv{$>)EP<;DF24pprvfTT`_0>oLg?oz+<`DZ zk>kjC0%%2V<=ADi{ zz8$LZUkD_vJ2>n~`bU1*iLi#?e2yY){<(hJhN!#;+mNu#I#(RsGzHiB*F|16v|&c= zqoM8f4yL==R>aAD{%AyNMc};>n-EHc=PXPJS0qV zT)}9SD9hJm;+%qqk*qfy3i2rt$?0|-99HsF$~4+~Vlh+%%A@po$ydWzd$2EQ)@f|< zyX@_q1_$rWS@0>JT+D^XDC)AEORI@%$8G@okQTc{r5l`@UC}!>@t@U_ozwaQC+w$k zw0~bS=Mb@!x8W|TaVARUVEK_LM89); zkc~GJ3ze3p2s&e;!@ds}PZ`@+iC<0UK~ou^KJrsrW;JVlNFiW0ppJ)bitZ^Zv3`spse)$qfV4+wAcoinpcWIW?nc(uT4lmG4Ly1hn|^ zrG7EI$7bE27UlugyCo_Q-!(5E#@J_q)ala4HNvRcNBB`OE3zO7gazsgp&RZW(%=h06g+ zaFQ0BS+ljmI4Eh0?w22ST7eIH52#kn2js&&uW&v0cX!{EO8yxECO!s%kZCbGxYKP^ zJf=znAKrRSIZ* zja)Nd6ZhU#`v)cVCe;KzZ2}$09O5ir+3?PViE%_kS4d z0}tL$uco^Vedj;h9q;S|g+cDF`*&PWm%-sl;yK+qW0!;y?x+uucMCVQG9=5ZLM$vP z3YAqYf|vs}<1Q7JMF@sy>esC39kR?*@j{vqr0Cupy8kYt&2;x)ktF}1Fjx=3u1st_ z8{HZI@mIpfK-lSuu2ru4CA5R;y_;L*`AXg(rJa#=q3DXgdJaRMyw!bNJJr#iS2EZL zM%YT|XC5;6IluT6c1Aa?Z=3lpvC)kHNO!9k>uV?f*<>gp+YDbMLce8DaL6yX{9=h$t(ddUF6KW( zMRu!@ULkXLTwwclxuAJ0uZcUs_JQ}{-%#E~WaJ7hSmuJ+0a9ozz+&ev?3{5aVeziF zVxs_EeB}zZ!c9#HHQ#Ax-yuyCQ(;QUEK&Duj;hgcxb2@5*B0|8#$SK;F_V@ym00n< zQ-5Jn8ml)&sM=bbNU2;uYQDaf&E06+mss1e`tHf<3>(>O|&wtxP_Od3ThW* zAt(fyAmkNGaEQ}*Z$GWgnz4%NtV^s_ysGZ_KB%VZjN^#@t<2gAYiF`T{;-!RL`Mms z#Ljp5$j6B8gkFp;ECcyZ7Tiu2&u%ly+~LH7v>LEYkrhOoJQ?#4(=>>}mgW0vRCmCZ z_^__B%ier)<9ZbG>9Hw#!q3<}-uzEPx!(cz1ru`0bQ-VFS@OE0l%#OcGYSMdBLn%H z5OzCvIkzlcLYvo@IY^~Q(Z}p4^Pd^1r-RJb?XnHHzC9Pk%va&-e3x&-$F3CfyDi5! z9=z#n0Utx%y*caDr4l|xH3G5^2AjP!Jlhbs+Q5v9xvW!ZK_+KHJohpsHLGe zQEkHJLx+rFlSbfx^PxNsg+3kH{3)-E?t$x(PyiI~`z>DR38MH|q#D&A2J*|W&S+JT zW_*eJpJmlt6s745l2NQ-fA`zvrA=U3G>nfzX|-~L{Y7ySFc6W zFBRnO#_w_wp3}QqO#vg9ndz$wK~p^uvkFq+T#fkY!mD3ZF!pGq|1XIYV47-G{7A=$ z;N0fnc$|vWwEU4G-i%0?Feq_LUJS z8Z#$&lF<}=L`5O|=xf9h1i4h!t>VcGrIRGzqaO5_bB%CbL$owaw%!ji4)T(iQA!_1 zl*1k$y=r^-)fSDLBpM7OxOH`HxkA*3%(`5#QH|0<;q$kOgNZAK#yILcNpoW6Z9`N~ zGD8yx#89JU8L2~ymJ@d~m$^at#a1z}bi`E56c6vE1`kVByT%+Kk?7y*F}sAv=)Vmd=p7M>MiLRtO&FIr z9hsi+%6nRprZpNWTzxS?KW8nktIz4-Uaty5_2oAtk$htQbm%dxkPVr{bh^NlV?)h% zl@-)-w7YE0a~D}E0;->h2211D_?=R;f0bkX85yNh_`H_u`+;Xz%7tl*24F<}UYjL> zmW7eTB=a`Rus6Z!JrNE|Pi6FgRtke3!6`+n*yxrTL=N;lBT;PR!)&gpPJD<1i;f_GjMm^%V+7qjad*Z>a(#f>A&BU8ICR-~!*NwVcLY>%u13aD+L z{$fM}NMx*PVwGf@ zdY+ZYX-Vs4_>0dgzm>XVwk3H|kti0>n&{_s>NS`;BXxDeY?n>Bh*S>UsGcX_tcONC2b!sT${!N>+zws$4NiVOuj#?q~pzo9+x?3 z(R3^e+!@`NDix!*ZZmoR{{!uGciz8q+xpP7Gco(AAg%!D{*uBUzC6#TI=BL0-{1S; zNXpvQH`ZGZe=tJ-x>I+`hnivjCB=R{UC_y3Dv(5Uk`{8SN_$zmBa9{iO6 z7;x*X2?xu&S1nP!_?B$@i}xpK^9N^l_>^qAXVojBh&y3}vRld5JfW{GM@lGvvIo}^ zp$LECDOhkQZu?7rtPJoIB+yih0xd2jV^qxIZa(xKTR1y@?3(FmBPHo}(20VRcAB6G z(?qx-NC;pjnVsUB>O>SVlkNAW&fV8-bknTM^N zhx^e7TNLb}^+62X`*6)zZ~;j@qviFNy_~PHbN@1{r58xYGI@46z0`sUvYOrYMDEcW zgLEO?-IUZTLobW}zVsGb(~aoxYCl-0Yuthfk!ByyZe8nKo$VAn7MuDjlG)1RV{emj zBMQa!bav{JnfFA|UXc*p%toIjQL=CqteZC4kwoylYFcj^RUY;aY;}IW152Zi5_LqR z``w+)xNVgo&u1j6toDNiiL$L~onAS2eb$@vQ^alK8;Bb`_YAQVq@ybBcSzK*_z^@P zE$bmcdGEcmmPfM&4UB1nFwfbsk{}6 zl{b#dhBsbLS9?1;%p<^JOI1^AIcC>of-<%)ze+$QlvfjP!s2@SoUJO;0g(Kv?|lk% zp=)k46gOOzw9P9mD=-tR^!^TZU_@R4K;>{Hos6)7h zy(-^czTAoufe7ummZi%;%N(ZR)$^f}Zx}bWZu2vS)?QI8Jg8y(Q=<~+7$`zXhJ?g6 zWgh;0qVd9Fqp7!@%tW#4D+dKFn1zqfPOL+AljUNoYUoQ4J1WBWst1v| zJED{AWa5T%wEaNmvf=6dvUyyErjuV2MjN4u>UgnVpCsK`QF!2z56VS%$S);x&ex`$#~X^{-b?xYHjT*pI7}t=OY&g0caH0z z6a$UnWt5@TbQh<$rZtGPWTnLW=GJ=JXujl1ji6%$G8ldxZyOvFi5&S!89Zg18g;qv zvq&svc(`M0TU^vqIRXn zaC_sBJ9Lauhmo!Mx&_t&XTiORTewAZG|n5MD063ug3x?{!{OP$WtHAIveuK$oJsA& zcN6p~r0_q!u=TNENXGY88#|Ya63u;piCxx3oQ2C&hSX6l0euz?BC#Hodzrhu5{wIS z_K8`R_$+*&VQplCb^BW?lkhZ|AId`HjTW$(^J7a#-h}oY>9!Yip_k6|*ipAOkh1ng z+RZ&Fv~1f-H&gNXJumlBhR@rFja^~nHL}__Wj6HtlT6d7S><(C{7jZ+LdQ&3z`emr z(!^DkxWOU!6)C+bW*B6|(&H)7Y(^bLV1k3Y$5BMD! zIi~>-Q2ZM|25aPfe@?u1L~n+U(w{Cq`{>6UQm~xd{UumYmqon$B0hVHa_BDN2w4G@QPauWt%}~m8P}P!P z#Mf8B2^_v67JlE}e|fY{qVy@<3CO6VC}POT_mD#uE6?!cNXb~hoC@})ev8`r6EWLc z?K_O8R@(GM<(XeP==s9a6-9Om1WcX1nbL<*TA7-`0QR6TI3Ls9KRM1NEM)2Swc17c z`4N8yUrB``lUkb=4>!HVYf&WptL~b1V~bLS(4*KK*zdQ#gG}0v-0mE_SE21{H&Gu_ z5S7kiPb5dh7B%(#PQ&#Hf*ud^JYur8P5P@|*v@^z8JMlJjk2HrNq*;ayZYSt3X}0U z`z~Z0RSs%>fI|$o53ir&#M~PNI?waNdpTJArq1C8ENx>N()79ItNyc~Ma)!P4o$wl z$b0~!lAt$9J22?Axl$J`@^0%HB2Ie9fB4$UR`2OD`dp)j6aC9PwX;}FWvOYl{RtGc z19Y!mT~G{oD-%kIO1_YYWyqPN&ZC}oM8Gl0M|X&%L{O`E@26JmDA(%`V|Ug@CU`rI zjPxt#1EUvoE}V)Zv?mwYWJzb}zml}pXojY^`pz$c*B|hhk&E^YBiOf!Xg4&;p{G4YWy4r7H<^qg@LkLjQFQ09ph+7Z5O z!9TO((RYfCtJyJmZ{7~q-u~Gs*aYwp9G(AM4zUGFVCsX2zyt)8wa95dq ze%vsqm5FEJA|M({G@nJ$f~^@)ZJ?A5J0fCFxta>{LsC znHC9{k?v~{+yyK|9RC%(J`6e8=W0mi1Hx`d@W-@F2AeNhqZ zKMHcp(`@Glce z)NM}Pi0rFB={aecPSjip+!06Teo07rJbx9((?E>qWEPo6Y|G}!y6Qyv z(G0yfu4eiRbDnr%6YMn|Sv}jc`lZvZX}F)d)o=9u+93Mca2}6=n`z%^yZEer4<~I~ zo8_uoB_x5w-C@jgu1{(51d&(aRw6qb00@L^#u zeZj9uV`(2cz7F9K-T`#SKkJgYarW}1={JA(`)T#US{+54PG3a%AfQt62*(sG%1)%t zeuEi3C@wCf8PT;0DPgnAbtE1Eph{d6*($LQtr4Gha^JfT9_6}1t0nd*cFRb#k!oiS z9F2m;z;VWA>_$H3{wxGYpWEeAjUtTl#ktnehqMyVf*+ZV1~-b-*?CzUK)5Ar zC#Ndh&lxnLFiH!)mQmou8Oq?XDh}}DII>qjonG**@E)ZzN|vQl&Y!<9oj7$Obc%u+ z90~VlQ-(Uia!#>kOd6wuhC|3+V%-=ST{s^}<0-2pJBE>Alsh#roJmQ?5-sqeyc77x zEV7aI$rGoh<56S@_wdD!#p5)TKE;DE#slRtijhkCC|>R*!Sl| zjgDq#neoa{ZK)@(Gce)Xj8{9B<*RrdBPl}|94vcyZ+#tG z`&)<4+VRy-<{b9J{`<>y>wC{NSdQ-kd(-&2_ZOvOZ^*y->6_tWHo;xoQljNoS!%&I z0X}34kNW%_Afi*>YrvD5&Pb)X&9ad1xjx%jtLd}k2(#41BI}V$Dw_ng?uT{!Sa~8t zBIorOe8iB9w8O&02c!Ux64C7{e7&t(7=rYgA-*d*uogK^eMfOYH zV<|9vbUx0+r~%tw!eC)XIyk|MF%BWiy^W>j%pQ5xSy*Haa@FHH4#Km7t0e+AH-kg+ z4iS^F3(G7g!E42uWib#R1t4YxsV$U8%ha^9-V z9r)WL3Z7=Z;EP*ZJKb|erHQY8q_#LHjvo7>aw58Nym2%gJ@#cCbLvld;Hyp-r`gEf zan8Fm8~2yC2Oq};kl25}{t3IE3GE?IeA^tG)<~!Fr0+`Q!{Cujgi&uv|HYuiNI$UT zKZkK^$h6~K@8q7kp5OBAwYtD4XX0p(O@FirgE7dVoIu*^$eS#W=FwZy7PP->*RC{9 zW!^dDVZKq*bSmGf1^11O?djI7yPaibHra_2!||0;waq-(8MCJ70m{s9ZeOaa(VaME z$k&@28_mZzQ2oJc%oJQnTi=;(-@22!-)^uMnZBc~NVkIwPZ-2DXy6-b;EDc%KH3GH zOnU`G-{FKBGq%R}*UZ52{T{P5IRg_p@6%(X%NYeX-)eHX_H1cQpxxBz8XW4}4v%y$LnaT^ELDs`o-Aml)ez6Ca>r1_jQb>-^kiKXrdfwNB)Fhkwq5U@4_L03d*0m-OPW1T*!zBAc|RdJ zCvM^ew;sKa5Hh!Y8N9miR`K<(I)2i>6lcublF9&s7B$5s{oYemIVP2nj(e%Q9(z9e z^teFF;OAt%C4utBv>mi%O?CBpLrYDpXQswA$&O4Pt%V@<3q>SAsoUlgcGYP)79U6H+}W} zx6|o!=cX@a#e-tglSs~#ZOaJ~NC}ujf#eVy1_03rvtLGuplDE>mirVg%i%og(uQM} z7RAJJgx&YcM$i$$3AmIY#uUKm^+lAeju1Y3wuY5sQ6w2PFqaDM6sq}MOJs0(Nte-= z-oq)y@Z0Yy{30w!)EQq-9wv&qBlfg@&y(2OMaI;U+#=Xty!QqUr zL-@>qQm+r3JGQ93Z~v{|kH2yF zi*S7Hhvoj>XS?@&sP@3CS8ory>Gf(pPud5CPYnm*bWm90_SpY{`T7;eEqC+QxPA** zzWckdn_myjSKz!LuMF8~I9l}EI!k=ZEAqXVPB7S?S?N+`oy~RTbZ2&)TRk^jx^%JM zeujMgpCSIcZ@-CLwOYrLS)pVGX^}a|9t__G3+zOus>3953}*tvYxxOwT9z7wb0kYR znt@I(0^~W*@fQv$djgSfwzsz{Gm-P$H`7bG4P4^5=OEx1+uF9Y+Jo{mGRfMx)uzEn zb^rdu8rRKKG1GThMsCPXk2|y9vW^BpbVY#hzsjeTZH{!%68Vu)cgT{1@C?6o0Cp+H z)1|%T-Z(zg0mlbN0KQsh+9-Z$idU{g9;=+1dkpvXQycNz(Lxx3)m>gx$Fr;@`%&k; z>b(IZO2%#X5PIAN6=UPM$D;kHhz9=xxSX+QHmU&O{f{#(Xo$?aHVxm@z2tI#W1%IOnBT=#3um#53p_9PQFu9NP`) zmuBF>nI6TtZZ4pioMzl<-<^5B+a@i|svbvvXhL^g_5jn~lnG9q0afG@Am+3;dNv_uy!Sd7dF+X^FaAOAx4$+I<<50*ahYPZos1<&qr*p6LyyJP zwVW+!wyO*6k8_`N?P34T&--i`b?cbY7yagYfO3nV0&>n8gVU z`@$&Ko-pp_d_4PWf~Abh`9ZM6dEc<4aR?t5J{8ShN*#xA2#4@qV3ya_Z@!t18lhK3 zU@RlkB_bj?T1qcnd@$KOA5N>sRX~P_n~oR(cdV;DjGc90C7w?tBY{~$6b%YG#rA0h zSR*&b$DFWCDS8?q^$EvS-X-Bu!d6aMM(0cwT{9Dg5@z2i&Y2;w`WSa@`&@kaMUh^#mLvD1 z-PO46T%3exgvM9gWDX!kexp&YkP80`z&t!L{>iosIA`{g(slVfb&J zPRrgG$Bv(xEORvWDLGfiK7M`w!Ory4^`EAH{^x(0{`kWW(~m#>)Z-67{5ajdeW!*- z1}^;^AF~AO@Bi-i)Bp58|4-9bUtJq~^AJ7?^xJ(vXmeH#IT!XfZP$r8zVq`tjoZ89 zH)MeE`&D2!&!2~Z*$D3gduj8w;a%QaU|}Qt7xRGmf;bC3mpJ>wL9nE=H~d+>2f7%*c=LxyL|jTw|Ao_7akGnR~_`H>OEh-pbU4tdS}Ugz&9IWqW|O=2eQ>Y1~} z9Z36Wa4J3oro2NoUE!#hWz@0s;pxbuV-V80b7#ZbRwMTwAI4BJUh*`PUX7R$wm7|t zNMK+F?`DxOH&x5#ggBX{A49E00ioC8m1Lu+K=)WM@i&l?^*h^&-rv!>vD z?8M2)Ur(mncke`Q+w4ppfox`0k=ZJh*CRtV@05k{c{q<|#P)-H`_snAw?y3`n+aoJ z!%M+TI*akUC3Zch+xpMD%6@d7$&)Be-LdcOzB{KihsK>@@BQIS80}yIIFd2jZgMTn zmO14`4?063?~^_0FJFCqt+Tz!GjLgX!?ow{KXfcEeF6D$f47SnO!L&hFjY>Z~x%OAcJKpvc#pUh0;NJRB!zGFCoN5RO^K`R;|A4DHfe;HyS|7Y_{1bH(iVqtuqkQ_T@oOkq zY}EZYU#|BDu>X4RJFg4-VQ(5s5U&Fq@}mW!hyLS;w{W~#DpGiu^T*nP2y?#>QmvCx zKMRcqC-A%!@0I^WXFgf_tfO|J&n)-G{qf#H(=HjB{_{$JOM-!!_%HdAGgY6}U-WZZ z7^pw(Qr#`(UFusKrkCQ4V?`CYb8tS-^Wj*nbG2;^o@hA2UOd5my1oxcZ*Q8*_1=5n zpgfj1`{RBt@Vc`6ny@#|H-*1`&{p2BO};xUdA(1b>f+Vl_h*n>quLI5_7@2I+v1zr z<=(izB>XkPLFN1<;X}fQPVZfSktm%eIc^xrSHC;zWMv#PbbeX1Vk8&Qb74I za*A+hlo;iJazmKqG~ooIfKW0icN8p26XosX$tWDT#}V?(C@q`LCN2lavIK?EdPDJw zKpF+d_jFmV5Ddlp$aFl)+uDVT(}nZrYpkGf`8FC6_$W9r@Q~^`tc>vGkh8Q+mp+hw z(xG6Q{d8jGbeFIh>+O%_YnG3>b>biF-0zIB=kSGV1oRg<64oik(yDM8)F=v^Oq2=3 z$QUWm#^o@wtV}CWXeqEAIhhBPH%4P?>r>`9+d7Ih`I}j`xv?JQaI=P?WK@y5^C}hv81fw~6bu??z>t^kV$JrQyRUx4G89~W(WywfOz);-0$9Q7oYUz+T zH4Y?y^r4_yzGdgWeZ5j|iN{FJNoL=&8h3)9x=j{MPv{aZNuOdqmbQqZoax9?1==hixEzMVA8c5%>K;`Q#GJJaT7_*MAqxpS-2+W8CRM~rxQ6k`Q` ziPtl5F;wCk(%KHM{qe^iI}_t?7(V%oF9t3jR5EHXpFYLa%9QJ+--8&#SybFx@^IMfGBr>k+B+2)A^v&bbsgsf8 zj@j$yL}zl~fudHH%eh%qj%HGs-2oUH$%<06d?EQzf3JMid?G7yE+lU<0-n&^^Q`m> zf2i?1N6*J2&&D|*|BNzN?rI938B4@5qLVkwt|wa&z|1aTBn4zHa-*3r$G)7)6ETG2 zpa%BDC-X?1%(T9-85wLV_%itpyzNCq4kAwur`DK70!KKw*JY<$mfRyl2ghCKQxcaR z82L;!&_5+V<_4qh<3~@!FQ0Tk5MY=$C}AZs`Ge5Yeq_=^Tkm;?>^U3)M@oarraG}a zWh*lwkXXyfe75{|6ls3G2a5ZA?9VY_DcAD61D^6zf9N{~im9>jleDc-@&>+TD@RgZ%&SQ4Qt>pRKK(>uf$9>gKIm(=7urx>R9s zd+{vw8C@Z?6gm?m@2Cro+822)5AEZ0WM%Eja%t-uThr#&cK5j@Bcr$Fd&%E5*f)Q( z7@wxio#-<&PvB49Eu>Hn^X;Tdn3=^u@B6zroj7CVtIe4exV@e4V-PcY#q3Kn)TGya z>hhe^jZCgi$o&Qf=5cY;#z*@d&b~o;1MN7A=JuLvxTv!)LrZ)>J$1#04q!_kfOqRI zeWm@M<9j$8ILLkT;V+*$1MOR!w4|dsKS_JlzMnpsoli*{e?V9Ir5xa~ET^i@wIlS< z2lOxXZnh@pe4WNYYRtGCPO_cwBTfqB@u__gTvOVV6$`n7O-7dUi$9l{~J1?Z*+cGU=uSAO&T^v!R7GaZf6QG-Ag`ynV- ziH-8Y=|bupg6U9hIfEQ2C>=$Ww2Y?Zd?A1q8qbI>`{Hm&8MPJV-MuI)oGAomX;MIC zN{}Y}lCDpkq3jvWdvX{T2(CRwxSnz8a)(KiLS>nY#}SyTygXBa2)n_@9u|}+j<2<~ z^HJDNbruq5SC>%;UY4_YY-t=u4o2HNAM2MVttd?k1;h3#B#%*{!-x}XnqP`LojA1; zrEX=i`7Uw2qv=w{Q^Da>6j(;0B+TbnFzS+U&X8o;utgcGf|{~Y=8|~+o=s2cU>dYn zN1Xw8?8_>3l!fEDwloSlFr;w8eHo?nN$AnpbIHG(zL$n$Pd3T}g;e^-a$h}5kD_T= zvP~l?gO@s~b5lD>-6*@ltCL)&tQ49k+`$X(S`ekGb#-JI!6-=H)!O}J||y` zdkBZ{`9RtvL(bO5*0g?az5CHUtkdhSr?E0}Sw_gfgYMs$zHf$>(dp~!_a+<3U%h&D zy7twzVJt{U_a6N6>Eq7iV35_v%?3NacCiK}%M;;E3>NsarA@snkFi{=(czD#>(_tk z@=xXUf1B_bEOqE>wwz(nL#SVjS`FiILF;e4UL6d-q=)S0xhL$0CI5r)*n9mxc>GzO zzeac8gZPryo?9>B&u+|+`>%U+AjrcD%9h`7b`H>=IZwzWjMryRpPDXRJm3DzD80<& z@_`qZTtEgiVqd>K6*=nc>X{~A*)Y67yamBJW|EG)87K$LMptr8pluCadDlI%P36r< z6vNR(e(?Tq?&PvE2>A?;VdOk{>iBg2!iC~=@7}!*qB84;yhY|C_n7%V_JDmbZ6|n_ zgGriro!Kfo_wDJ*Ku`X8ROiFiwn0B;zKmj#XNI$37=cGwJxnPYX&93Ge8wGbg|mC& zjinif(?U7MOfq{kk#CcJ;u)NUb_OsRU?lD^0Ed4@wu7U5-BU+{yp_s&f1$Vhi`NYJ zZ;w46&pck@EY-C49pIYGIL`Y&A(8zhjJlh7c@rG(^jA79@4n1$9MNddX@3|7^_j+m z>%h=a#uAuh>M!$s;qX#d+GQO|x&JWr%`s}}P5Zmm@sS@r0d34=272Iv%Iub^Z5SgF=$G8JL`}W=N^mI>(Y1eDx=W`pw`XJv2fOco~#JuGg+R8%9}^ zR|mj_e(0EJfgJN|e@*(;;gY}ohpm)>P6qzykML2x#%ui12c@H2mKZ#FaxA;f@g$Bt zl+eupyHlq)>Npi?2l+`eaSfhB8|Uz)H*nkuGF49Ls2h1ddKmpIeVZCEYh`_hXexX3zS({&iBGA?KNo@ zCux`7d->i{2P59{&H{VS!SZ}>cq@2KyxsR5ijp+7g@uO&7F=^!`mEp557`Fr0N2AQ z=KXmmK=7?6DT<+BXlJil{K3$~}UB%a$UH&6@j3s}JFijmcedQYU z%n-A+x!D;VJKOh5AML<<;*HU=mY-0Ed6xV;n$B#&qlr_OpQT=omqzmU-cXh(9(#-= zhj0j=A(*YY7+drsZT7DT^gp};55`Z;inVe5pMLmZx^?5H@GwhA;T_NNeK=7bRY&;N zM$Ylod2mDEKBMu@PK|%)#h~EYY|+iF^_+*NB_DY*`dz+!dAfM%!gPYs><~T~;LUpj zfm+ym?_D4){=o2|;dQwE8hP%e#V-jT5?&<1cM0ScVL2a$V}ZODK9KMInCsJ37_!LL_Ez^5 z!mrI@Q(m~)*A#wIfAsK49VKS(m}R9r_#0sOH`8W)W4lXJ*ANaj0*ulmJ?YfZ5IkD0 zSo+l%tqI+b> zF5Q;*)KfA_zC*Se27Kjx(y%Q1)sV8(NjR_=^^o^>>my0QyZ6|UHI2w^t{I_s>+UrH zAcgcDNBmg^mVa|?&U*~zLuS{WT7RiWp~=bLVNd!m^O48UC)APq%`d;Un*{Y`7My3C zPRd~qG_5*@Sc!aMS#TL~P^W?^>!y5xrzqwdGPV1je> zlK-f~&>*3M=h{Z_40xxm=}D<$H2mUA{e!b|v{UgEPWkW?gZwN@dH+5gW+%ZOV-J(x zvDVwk$THq@ynOk>^zFA-rr-VM>*?B+ORdk*Cq~+(Uhvr)mU{~1)qg&Q5(}!Fy@1ISru4koS~l@QH-bDLL)t*Z1(ACI9)jd!4v@ z>ExDtz``enen0bzd}BHrGWB9+<#P1QKu-DTd(YE0q{4x0#e%UPputz8UDYO$IAN1% zug@y4ZfHwls%#g{5qJ!$ELRyd`{Y@Hyl5G2rtk_uMuc2JEeucL}eD zmwAYG(7VE$!Sg+#homX&!~d@V_R{3-=yM2vi|}*p;%%Pq4RrKFID|uZ1L!0Ner_VP zo>{vvojZT7OY?Qfy!;4)pv%=%z>U&E35uXeKJ?rOyE?m)u+55xk`@IeN{4g8vu|BT z&{0|{^io!z*I~jz<6TBo>$7*?2ZrV-c3t8iacpKw5i(*?8box$uJ`0Gz>N^xB{ZV6 zQktqTRnWCu$8ahw1fbMVnBYQbI~f7_XilCc56(CaFU}jY*5D>@xH0_rQLJ-l*_EYf zCT+n%7^m4b$_e48WC%M2#T`jRiHx~2Ah>A2dB*3N_o^N zh1g6jGvMysy&FY;qjmHobz!+jGwy8a&8P*JM^B8ROFdbh^6{vDcztnX%nCspiZKO- zUPBoI?yC>&q7M$?5Dwv!fWCQd?Ocs~9l;w8YY;$}dY$3Mt(#qv5U({0?Dp;3;Zyf( zNbU^X@GoE~$UArMl+XB%Fuq!T2>-<=7{`1c7ULyDpc%FtZ-?-C0j_*d0CRP}0&f$? zhfckJNLcdwOM-|I1MfE=Us`@xQoRau-eiPPTLUS5{N}CO(|`M?f1UpL!;jPU{Rfe^ z7@3FBepg;`p1{b+uwMgq`h5rFkX`g~sgf=7^X(@Wx^HRg8bA|)A)HaOM``7JStjkm zg|+G0)vMFmxpR?IhU1H|ynBzGS*c^rtP%;?U+MbwTg9EDh`}Bh@YDTlGK4dln&m@|so(3!I8zw_X;$CP7bW>s}p zcU2E4q6ZQNQhcN7O$108{{-<-qRdE203|cQ@PGzre3HQcfiMDs5vB*4@kI}OgiI6x z%0xl}r0%Zj%I>PlF(Tak&V#$_`+e&k_ZuD_Q)Wz=u|JO!_uO;#*?aBboV(Wf_F9`d z@-iQi#NpS_!&W+tUy^$dtX>MEr>>4>uKI=!re`koyK&<%Zr;4%`s_*n{^)xj#M|$_ zW$!cy7uFhM@)9BT{IYfd;mCKwE=u>BXM_XD5?<_5K-EW-#eddV{Sx1M?z{C{kX<~5 ztXJ}>#OQ308-4-p&m^uYqT@QaOl|bDb-R_$U6F-cMY-ti=%6Mk$=~^A-YC(eVLxTe zR-=upJUPsmbCd$5qoz#2n5ge)hlXE>H(X}F+jnFKerNC^!V8R-=JX}u^sJXEU&cJ% zQ}^#5nFz%T#QH6It;P#c81CK0gK*})szRvY9Rz_zyD~13l?iiPOMgI=Rh}kH@H;w2 zpI%yr-qM(EN&n6spzgG}baiBr4Cw1s$oGl_AdSgY*%j3!IL2M|Kw+QuR4?$=3r`wRH$qs_ zNm`&5P+r)m*d)m3FqD!JyNk7=A@&(VJ?-P!N?)+{phHV)BN_$QrEGbRUqwZXUHwhF ztkY`TuC}Mab@@FHJd`i(>bBK~+TPD)HXY-;i6T9xD=#hjAxVAi$IIu;Iv7E|p5vrZ zdJ>b$eZIQat9E0&)5i=im*Fv}F{$W!u*VVt;z7DRto?pHa>ad{T3Apaot2b)# z_J{As+wZ?;uP?Mtn@v*Iq$`>PLviE2gBV$!VuWLOV6;dOWLtJv|$}Stih8GB1+q=<`5=%UIzYxG+Rf0JL zlCFnz;$_Q3N-X&R@}?|gM;S(b!u@S+Z^yy@fy0|%I5Ptnj|L1PJeLS_s7%nr(;&2= zr8+y`oNdcPh>g#;JWHWTVcS}q|{?*@M46z(A&Hq$QLkam=p5H zVG&gaE~Xqkk|oP&Ol6cZW7CHIXp}QX_5D=+#)|>^mf4#avy@%It#F+U-ze@dXcui zUB&Z~<6Ie$j{Ne~8aw(w{~1oR`cfTx8lVS}ewEz=sLoX?d4BYDzw^?cX96B6JQMtqRC*fv1=m_?%z1uR3Rm&WipaSyU~TWBti5+A|C*1RQeRINVd+w*0(8Ry=g@ z5ZaRNm_(oIr2MESZA3ag?cK#BBFRb`TAH$G1IV^^x9ykr=u*1Kb>jsuA>$w_h6{m4Md@BnpHV-bZ+{B&os#Gch%YCY{k;h|Ne-C2yT_5PdCcN0#XH#2P zey*iXt8@9%y2?BA<-3cezpG7Ou@P3y{y^!ZCog+uk^gGrM3%>=Gt5s;=^OW{JwMb( zM45m*#2W;g0Ugy7sRX~o*JbF+wnwy|eN3G;-It_6zMjS%`s@i|1=X&M-Kwu4KAoS& zA38B(n(>CGUPF0pZS_5NDH}V8@Pl}dK*AXA5Ijy6addLx-`DC_l~dG-dxN$`H)p~e z;_N9QyR5Y_7CkLy8yZQZd*b30l%wwwv0v-wHM@Hu4|lR zhwe>}UzH_!xc{lk*ppF+;*f-@Z5zqSH6};&iCjs>RqdS~h#bQ+9739jl1z}fd+)xU zC25PX0j{Br)B$^iefo#+k<_!=2!+_|QunqA-}^_$mI?9{nXpG0BG`SEUE${^^->v( zrzA-593w>PhIE*1+bv_YGxs3`y~+d3}B{@QjO zJl5AfD|qZbVq3>`=O4FSy(SOjM|FeJf0Eb-sw9>8xxSaK<-XL$c)cL~NOzG5*R17n zalO8fmX7hgoyV&-t>AI!vGid3QJ!&;C;yS>YEOCaJmGo3_(ty}ugcq#XXLrpudRhf zv40Qfcb>b1&*XO^i=u$sTu1Mdf0ps2Ez@4^S6EMT-T7z5b@@GN`#Si#*FOm_I{)W^ z*ImZ1Dj(N9Y5Qu(>%M+Imsrp1b=|&ccpfr;6YKpV@I1%CdS2_>btuGFLBTcPc3D@= zQ;mEOjdmm6{oaRh>&~61qcG|s(#dS_%MFZblNP%9FaR-vZ1~7XsSI0gOkN;tu<1Jn z4C_Rp5c>s)@>${?B;$t#!WXlt*W*Ilw4%$VatO8H7b8+y^X1Dzc{O5tZ`UtgyE3LQ z0!=h24F(W0VE{4XaJuq*f+%8*FAPNFMsG%uZOX{q-P`dDKMYm~8P))BNWl%tPmeLL zKPCgv#1zDij#HP5S(mCmWkcpw3bV;3?eij;*@G-Z-B1}Ap^#p@#K5@4AjAk;*uYJX ziMh$9fsAH|J6_VL{Z`q)rUl0fblovP57=|ds zL#xvz98uSGpe>Xfi{AC+a})yU878oFEpo7~k_mWahnEKHFOA01`Ou$8B;Y;6HH^6=bEJdtvQ>ZRO-Xvy zlpmq7TF#G`?T`k9Up+WHi2hcO8d!hf9Gz`Y*s=vxh!icuw zMg7ucF(C-=6~cF)uzr~2CZr>irFijv|9GJ1>)2~b9UVzG96>5hOwRDh3tNZ@@^L@W zwk|sB?w87y92fF%-ltdldCo#t`}*WsbUuHgFLH+Ss~6DdcGL-I*T?hQ8l3*Y4Irh* zgFe%SuyXG6L>oxCE4W4m>F6`$f~3rTYij(k{uARh$tK1lFTFk1wDB?={Z}Q}ofli9ewj}Rv|aW$ z4v$gD=BfG+ zLYZeE&1(XLytGyKM0G#A9!QZL@kp$v1=ar5>#wF;$D@uv4pn~Dwd8sLn3CSb5$<7i0q6xpOIn~S**=5r?F=H!g@gj{8v70A!3OrLo= zl{{7bUpM){x@@mfzN>OvZk%(9)%Nv4zOO4@XW1Tw zrAs2eei3+;?Z7WuA-)OE zjc6+mX6u@K;w1})>U_0mxaxAQ`tp4)V-1-r0~uME!Hc17(o4#78n8)FQ8u;Nu#v^f zk&ensMZAttCL@j)CXjZtOXXdL2OMp*U>}21ZR0x8&N_|~@AlI*%zWfU5k?=zDTY4h zA-FIoXcJz*=MgU$KmFv>_~}o7TD{MB)9}iPFaHj&wy%Px={D!j z?}R_A{d{qGbxU0Cy(m})gi%=!mH!OIKa}(d*Iqr19R6I}+)j_#jEkKWs_$;#{3LJZ zzuKy@IG=~I4Ju+P)2npp27FI_F3BP8RlHj8tj80H`_;4Or7tjfhL_yri!MTbB%q9Z z!B3$%0mz;{(i?TF5uD;pM-*+w}=?G{8H3 zBE6C#1fFSJi+*OkLmMwzsRyCE@fJaEs>m+t#mjaGK8N9x{)8M50aZ9x$hSgpvh|MAH#dMLUo>3AkWkPu=EqK~@ptVBN}%=M?Ae(w65oG`gy zqPnOptTRHkK{BA5=gVP`Wv%otMh^Yw6RVfQIX=`kIF{COjCp_fuDN8I-lk^YSHpjvMlK->GlNB|}gW zH6g?CX8I&*kic^Dr%z;u452+4pOls3JmTPB-(w0A%!|LDl~05)0n4WULQw@SuC%l4f5fxE&J{%nKE_L1F$=#Zt@ zk2~8teqIs6GQ(Qtc;MN@j)_dQ595a8mB$mZyPa0)*%I7~NWrnHeexvNRM%Cg((+mD zSE!Dyrw8l#vQ>GqJ?T8#bpxipKI)MB4wAPc7qd2&ID>h|J%p7V@ilok=SK+~vTA-kPltnhwMSwC1NrT~PBUXx{R7Ib|TWYby z=z;ViZagy&=O#^f5de9^{!)fq##CP^vSiJJManef5rkK7XUF6X9%%?($woevVou&D zwRmh{WH~QM3SrZP03rlOzZd=fR?ZkyCZ2Jrba!V@(f3ZZBPSxh8t}n;}RpWt9qM!lQ9V?r3P|av9<-CXIzID zhi9Bh9t>GXv@JZvI$hV#MuZF)jE)R-L_Ji#&SA9FRd?Eo|1e}cjwDC3)^uN|0hGo* zuO?_eUI2}b2}hLUsi2_X<-*Sq-?-O6_iVe{iT#7Uc>Arl;>L{|ehKySKl^!ndGBrv zj!#VfSEyc09NajFww@b2mswK-4=`Rr@nV;v{Cw>7^sL&5Km5Z#jDPtr{^g@(_;%y< z@c4QOu(81BYD-+#=MScMQQ+qniBhU7SU>axQ64(|i1Zv@->RL;fXe?b4ja|yRrvTL zPCm&XyC_ee)}2;r25@U|O#9rA{N|sYrQU(=#0znB3OqO_W7hRqDvuN;38s8;330&h zJTJ4+KL}I3x4RcN4iCL{YO__3TQ?6(dO=Dt(FX5PCJwQN79V-Kv6J)~Xrcx_yr7xPu(sk_P^-e^A z44IcQ;%x)*HyKa;a-BL8#QoH8oPKWK*d48J+=S?|Gf@5sq6-8Uq=bkji zIMMh+UxuK9B;h4`Pi1l*;tQgdFpIq4XZ^Ur3G49AEi3C=?QCyr%;SlKcbdkW#{8N3 z9pcNRmWiGu6e))>@d-t0{)IwggxAtNg08>(^X8<~CfVUH=5@=_;%rTR&c*%CCYaC+MG#lHS+kwX}r4aqOJE zN*1=&Gu6+b)qPCryue$ImmD)rN89@v)l(ay(0AMu7w;5wkdpbwHH;OHIbBPc$VC5} z_*(U0PP|z7dCD^wf|~n~b*3HlME4$jOIjux;02c6mnu_vWS{FV8-f2Gz}0rV+J@k| zwtks-)#X15*U9xd$oe|97qYBxZxXK7{ZU($w&2Mq?euc+I<)hpW>HX3@bqYGMn}d_ ztKYSegF#?L5KCK1AhWcZRvcwOSh2Sikp`p`Nfb?tNGq&5hk}Vm5c(rZZ4yzFID@cJ zmUwqzGoZX$X=U~*3a`pTdCr#wsqCT-DC+ zs!-xNhRj}ATV+K}UI0R#-4x9$GKdTZzEZ9*O(nCdFcn|sq}6Dfi^g^5Y$Pv)OF0FbQqGh z`c8E%C@6USu&L)JB-P=;Vcfa>mYy+-`10+QyOI&UIRp2M`iE^w!+OLDEZCn=ml(zhyWEbD~bcnIxB<|lo(KgWUIxm(x zCZ`S$_w4zCenWn3dqXw-yN-^8hddi$3~wGD#Nmwtzr?RMnb4HpGUyBtUia?b_ls+e z^?O^=JM^rOK6dZ^aeVgqm+{FbpT^xU@A(BfZN`iJ(O~H3%u@OhdIvAwdBM*MYY4B@ zCkfRkJwwm2d_jxOlUs(dKDEaR`X2ds(vddw8^Ua(Yk6&3>8pg7W6dz+B;4K34il(q z&WF%8XwN16x){c(hy}%3j zRHD>O)4ZV2P?$st$uNr%R$y1Ijp?09JXv6KD9ghR+-n=x|MR;cL zJ3<;rA-uKj+`ePd#w6k*+Z&P!Iq^DzfI|Pb#|ZkU0MTW;Mb{jkoW$L`8Df`qr3}V9 z-XK(rHixu?2%)d>yke|FN{+@%k|Q)A9wv}pGmm@7w7tC@k8^Ac>(HuGMrC57-Za2Px{3=xHei7`-66+Z){u9SLCBg&}Mj1 zK}a=Z^YNR`HQXPNc-TY8e(7pio+oW&%WeI-^|aR=ySfjmvago^RluceX}7Vho*jNJA< zy`|KJ>I$!&MOr|8u;X)*LE7`Q6}ltde|TNd4?N%L*Car>m$(mj)@Tf?4AOfts_bKv zk@UH3bcD=$A_w;bpU!@jA#*@F1!_dD8Z6$8~l7DqF#u1GK5)@l{apjA(UQ zar-;(#ar*cXQOV8foOwPkinEQ6(LqIR(PnQ=%VzdVPzvtildcVowv~;BMC(iMHS+U zuzgmGG16qv*pQT>dX8}>g_qf{HXvl^R}XH=Krv=ED53gVl5LZhC@mI2?|LR5;?$*J zQyy~UY)C1|+E{ajFdiu4ocD_v8DNA<+}qoWtt}QOulWVUcsyK%Hk53V6|XCY@{x?x zo5j>!AIV65er$bJR9oS;Zd-~KE$;3VQrz8(y9Xy&pm^{Wr&w?(#odcLv}kZAIK_&j zxcg=A^K{2KbBy(nJgux`%*=m&Hufj&9SJ*k_Vx}F|Bu8wlau$9GGKz7OnAme=EhvhvqY^EEZ!rlLmEmEk~X0;{)kF zVmo>8=-J^@?lNNRpUGix$Zn7kXU0VPpGq2A$hxfogpyMObK-1W-74Lfak?b|FFmvI z&rUy1&|}1D0rlhLM5x4ly+mxzB)6N9u#I(2>m&7LNYfrJRS?s7ry>ufnwrn9v> zKJjO}8!8`@Hyic`fl(a@$Z1D5pnF4Cykk#R{f`Y7fP$7DEi)Vy-SIA$`jq=e+B%cC zN0ykz!<*#wfD06$u(En4ldEjcBYqx^h1S2{~TeFr-%p~L{mnRe92 zu(W5DT+Q(%7W~#qW7FhJ$1z_H7I5Jh@oeem6l_#3Xd8v4&R}`NUI|pMHI-v?Y^y&BSuQ~DaVM91YF~a+ROGZbz`Lt4j9DfBs;dtj->h>4ON};}u7wq8D znjtOfLwP2%A#LW_d<5cMYoB=T2Z07RASGTof9jKJ)PoEW^~L^M;?J;%%ZN7_e&ULE zsQhNhX}4OTl2oECA7*yKzZ7HN9I+<=mP?1@`7JS}@GkGBuN&hrDFj??#FB8o#&ia* zw7N4puXovyBOA-S>$-Fd1fiuU1$|uX0fvO4%%;0SehY(J_Z2ZO_%ON@-?p4-gS)4 zQ542>wEHlUSk7cxWtyDd(v0#o&OYV1`WE*xDY;^I&2SCbeFOP6ad-3GrUw+*-fsM) z0?0^Sz2*Rqgb$^?f5A+#r{K0vO2O_HCx&h_uNGoS(|fkkH17u7E&si#{(Yc zXLe((5N{lCmOl;`#0MyFvaP&lEsf4*Pp0~%Pn+_ zoUdFM+n;{YqG1Z{^@8#{DaI?8G@sPXCALswq1GApOz;ihU3Ux-9U(8t+S`%Kp9+f( zDAnB^d6|IqyXzCWmL_(8U)s+L#F?rNp1#wc5yL7+R5(g`1_YX=93%O}%mk*Es^Xd^ z?x_!^FhtdKWVCKY5|)n<{s^KO^C9{m@^##k4VD zxc$z(7kQUh3v02YW5Ls4DkQdXH9N=rLcp_FEX^`F&9?ra+Tw(CVlE;|rC$@ErvsNj zT$P^)!%lQhgop1{9eZnn73NMe1;c@FKau`Y;Uan^$D=oSwtgnG-?&kyc6YtEpBz2;z2Gu#i6Uih&^5<55yDtoXg-ZvUA z!uyc}0~>l$TA=Gn&RUiw3F;5ISlE=6yzr7iLgNh4cWY@2^ePK9qJ{lGP% zaVz)(S2t;N7F+^R-0XMb^WApo+SHZBFcx=YyrjRL4E=DU|L9-c(e=PnVf@NWHk#4g};k7puy zn8jc{X!=UlKcE(GIHFR=Au#A|w!sQMo~UjXCyl)aMu|$r7<@O?uqbX|#N)_2NyL}v zb6lMkJaIh#d=I(ft%8JAFb4cg8vik7@g7RjQFw6|m=$-4=Ya&Y&u^A=qNJqkUj=kG zh)0TtaLWK8{<#u(QMuE6hsg8+Sa^&D$hk?y&IbFDg(J9*{_2*)cN}+)dOc@JO}>We zvE^w^dwxt74U6uIHhhc%ZP>n}ProhxDNhU&*OruLdg#vKa5F4(4B;$|uCd}WloRKf zU*lj~`hnEJJkj?G%-H>5-sDtrxX6Ulz49UzU1uXpy3~6W8|6A8|El7U;ytJD|D=HU zzm>)7XKIz^JlgFFQ!8!L4v%&C>%nJ&D9&4G#*i|f8njcsIh*ZRkcU_$m#E)GoocIM z)<3llXY%K|Pzr0`@!|j8Q@@L_TAp^lzVf0>_4f9L`|eInxvq2vF$7$g_tIbMn|zyL@ev5Z>5*5?7kP zt2ytA@ciT3?AVeZiq9i6sTl)Xw{!v7NJ4Sv?aR&_VuP$R;KHk-&I&8t?}IzHrByv! zYU?z?~o&DZ9GdDX)yL8+7SB6hrCMq8_ z9y8l;M11ABo1!Qrb6QkA;<~=THieI*B$_>`&$DX5`Hq~VDqn2ZAPKIkPiD9 za|5~}W)bDF^UXCOHGYqtkoP{p#3{!kzYr|<0M6(GXk{tc!|FDH}4wvH)2M;f| zH}|;P8ZalCBaqEEQL&HlpJ9`5a(O-0yZa^IZ*^UO%Y(^r5WuB}!pDFv|K<}LfC8;E zxGpL@vN?qsZ5UM=DdZi}&_HnYX$2B%e6)SI=jo_I3^nkL9d#Wl9t(&CuZ;;yIEI!$ zmq4AsG)aNG%hx!REJ2e28E!$`aEce~-+A>WTYIbaj9CSRuK2wJ(wkmYc^q1u^vl6f zxp6~Hvr&&#n4{^~t~NeDNkE4I)UF(rPpa08^`0Mc)*{39+2r!OQs8_=Pvp^swa!)s z$|?O8*D?>5Znw48ebz86Th&lqdAQx037}LJuq1g{;Q#0*b9+noSP`Snrubs(DXo;q zybn!sa|mTd$Okztqaf9@WfTp{XF+Ix{TtY@BdH(K;Wmewvuww}d52Huhr4!2mmLJ0+T;J4wx=$=I)-dzQ;1eYke!638e}TK< zuU1Mr6g%8^IVLLq`rMXK2T@4eFHUr<$rFknutCIEx&lPj0(L1Q-fv#_(vFj5p6-|A z47@m&K8rq?J@-n)=R94M+&yLFSfER|x?PX`W@qfWd7P)eduQK&9C!6_U%wRe&IFiK z+GVy%HBc}i%Fbq(qxV-~<7-6@cSU&>Rr7xLs0+CL>~aVqO_z3_4Apt6Hxd8UJbO4P zbi>gNU42WC%|ym=R~xQqKYvMH!+VPdcc~~UnXOXCdjmbjHFnw~#HH+rSxXyl?G7@3 z#L36N(UP8^T$MPJCApw|!NfCnHPk9Miaz_cZZXP1xIN^um0^8C*7=wn-6~F1ag6(6 z-pY7p;%c29aq80aTEt18tDB8wpyCB>w>tutv#uWMksSs1gIpxolw`{r$A!JPMzO?g zKr=W(fqGqBu!bZSbeElIF)?RUjGCkYoT)EWHM!@-*YK}f@Y+S7)6&!)*q-c8R|^au5liv z$hqT$CK?}X>-j;zq-~1Q0|TE<3uZdz%=@`K!l?1zk3LkD#t~v6yt5e`ol`I@5jOZ- zNaVjOLj~3AxGopxvlYAYppw%?P)@r)3|f`d6(@taQT9S%I%es*c^DC7azLhKnG?r! zU3!Znm2Vtly+vsSDwQztz9dCpPLIpP7TuF6J2Wn=9Te?;j{{LN)_(7^xmw?;j}xxw zu3oW1{PDZQG#&KyZSoH^bw&){R(@U$Olev|o%2jKUG@HArGH-etM*b=!A(LP6r^jI z00=tJ55#w)*fH2lvLbMd7YYE1VkJ{^>^hPtRER!0?X+XNQBT4D(L2fnIMZnbNJ~gM z=u$x!8OgErN48(9|NLS%voPw7t~9E9j46uEp`N<`h$`;xM?vLW0vd#OJ_(zQoy%=M z3g;&77&hxiA+|02^i0wQ=MFu8>G}YPTY-#gv;2@$Uo%P`K>ip|Hhbb*1-EE*b-b{C zWKD2z&6h0W`xn|JwS39CI=S(;JQr@(Oeld8XWmK4bo|$FI@ZjdcdQ5WpXjm``MD3U zDw=VPacyvwW?rbEg^FxAm>lA#r9IG)n_o9_q*)W56moN)*y`V_+e~_@_`bKba`YPn z+7o<9bfm*VCNI$bRtHK^Wh&dNTP(F=`phRJW)~<17scU-H?2-74o+J zVtATjlDNb(L?Qf@SX`-Lang0gmvw^;PD{R^L$z-*z9z+M1F`z3XTghh=)ECV+_q)P zm#LZzO8hdLK`b}=t=O66HqeJ&>gVm^ZvT5Qm=Os7`J%!ER_`++8G#i_Q9ByZT=p8> zXJMh z_N(zcVgmbreF`3xO~cOgpAkA^qRa+g>Vf-dn(@A3zufUE9p+bcdJgR`;SmH^Qa{ESiH$tlWc99oO_@BwVKM!@fZAxl-oBghdMucBAs+9Y@ z@lDZ6gXT3S)mv=mP#~?^RFXK`ECBn*O=Hw_^FC(Bxf47}x2@^}NwLX_$+Eb(_~4&Y zm5j;Rl?gzMsyIZWp-cG_h>JvRGaAqpWA=2G)WS>|Ia$-uFxJ?0RutG}UScw2Ns4@R znTB6*c9X>a=v})XM0?NKE%p%HA&lb@&fqN2y?y>zu371Mnm=k=(4W%o&pg4uwfx-dCpzs zq#}a;CK(pl#W#s`@&^jAScgM^H0{~4=g)5TOlw>9g0FCt?+g}h-#TSTAd$1PV6oS# zyDD##r-uE=6h zV39OX4YT95_0rm6-Jx8N>%?leccI_WLco`1b@7mv>r-=WGrJ$3vF{__asT}Zp!{aG zdsroZ%Z4`{4NB{bpM_tLUkClo1gC7V4E{XKoD2A~3v)OZlal^=Jl84br@#AHX$+q8 zM3h!<)GyU&>|m8YUUFAB&ev3p>)U6e=o&qnMdex%p6W+60b>pWOfI?7c^VeHd6BI*rQCI8YX&pK(;-Z{=j5o?fnq@$A`S7c+a@)>)ql z`n3Z&-gh-MHWeGV2CZf@Q>E?tW|)EeOizS|&Ke*jSRVI%0}jbi#pQ5Wy3Ne z6tQi*o=uz$0dBriC4XHo@L8qv2~fo5|O7Wxcm1 z*g@M{Jff@C4Skapy*r%V_c>+L$xWG?mRX(-hl;>%qy%fL?`^y_GfofRCj)$4ND27( z&}Yl;_t?m*SI-wpvQj!W>ZzxV9;jjqlPhJHr;qj#d+wD|1C5pck5-8Ump36>`z zn!oIc+$q8Ys|ZJY(QMtWU}|t3pj(*DBu&21B%_2ila7%g$X@IjI8m^e-!9eIZfSxN ztQw^h&lFli?wPrSzrM9LCnO-~Ae!tPIsaqsV&?tgI&=4M4tV&tS=3kXhnQvw^0(`9 zp3=|zWW^@@iTY`Zx}W-airR1BsbC{wGcy<-eA9+a5tIt1oU1*E0%iqGsoyY@VyGjV z#yx57^f#4-SUcVdJrj;dnzgmmEp51iE3iZ6?$<{S$#l5&AhwIy&>&sV`n+A#QXbj` zUJ|i$#W@BJ1~9pRFOU7Q8LhbkS-bUK?40s9d`jVGDO;=aFaTes+Voj^VowT<6N&apSTym;Cmy))+7lTC^LDJtV zh(2Kgz#z5rLli6}$1Z1!PA$@w(O5rdnFw<;5K>7tA?XAkk`#rB9@hV@8px<~7r%Jy zyuV%zy1(~xJs-%E*{}5?b{rFWXuTKfHP<@Ui}w7bx53ZY4(E^-&|m+a8*Gqh0+YXG z3KoXo+1zw67=LF=(%9jN7Z{g1_`3l2dAza|&`|LHYW)S8*V!^}+>-Wc6 zx3}tfy1Wm7_c}T+&TD2O{8g_%AgElxE{OY#aYxaEY}sA!NJ(i{zPdhfd@>MO^yBPfNG{ zlz%|@NMKPZR+#PQ8`Nk~6k|!OC3~o>gqG5|iDHLheOo{<};p9|s6$EN%s&M_&oE3VB!r;qY2 zCCO{uULsrVugFh(NK;%#s+CZKNrfs;`+KH2Nb{5TAqT?od9sTbq#d{hzz6^QN2OF5 zCX!qd?bRwE#YzXE>B|a$_v;UwOwm2zZZ39URhTsj*N_4Lq(#|VL*l*0i3}&err2-F1nj>BdBuuqdfqj z=YO*i@tZ89QUJ#DuYN*2Iw#Nx~3_i;cpi;J#=2f5#XqOJ7b(?mkC z59qZiYAw_Dkc>F&7?SObP)xwlQ1$~fT6oTi-)sPs6I8bQ$FycwE>gsgS73J}xqS-&}=Xpj`g-hfI@Cs-e%wl%Ac1W2bfscM%0@Qb!5NQ>ER!FM8T#S%A5l$2}iK zdEvhOTD<0sz5bEZmn=!+qN)&m+nFSF7V_Xp_)QznGIIk~As$di#i(H{&;LZ0o-Mr7 zndT=0yR1R;NSpEsoV+a_Gz=otTeC7dEOb1)<^L`yT5wF80``-?Ch|q5#GbM-RwMTe zI|=pJ?qa4qj0H!SKph&s_WlNVP?wL#?d7%A0*PfAz)r@pZhz$d@>{>LEU@uG7kKBB zz0)uwuAS|^_#rf?WXzzVW$ggQPc|_1h<}X}um{4UU(BjtGkZw;1Ci6xg*|o4#>KC& zL|1+44m@hJB7~hEGzC&rmehRadz|^BX)pAzqd{FsC@(>M?RBN~JaxdHXH8j294PBn z#|Y(_4VC(Qti0w;2`t_tgL=PqRjFAxRVg4#iFYW;`unz4j_n#NC@lH54r^X*r}Yvk z{?|;Q4_&+YI#56S8%m#yzNU?{9geI4^Ja^7+LxDkPkL0`LaSb(Z(Su=CKzV+ zFd~1djtqY=#I&%!jKXn%Yt5{f`~WSFET{y zzdRe}v`s=+3@0(0axHrfypfJ$)Ftj2p0-OQ+R;pPPJHpq%m^PmD$ORmPdv~3 z@out)){|GdIIBnK<5`}gyG5J2c7oyueG@Mo;mxR@FTaq@?(02Qjoi&4fTsGFdUVmb z)g34BH21^vOf{iB#Xa7(aN@O9FF4?zHo$1WZq!#_d;J<>@;aM5WMcs^HM12&uf(>` z#5veTWT2}R=6i-EoOLGEt%CDvKY5xkVLq?0s6N*?H`6E#13l_q26DZ8qFyi8=4nb<3gZFV9O`Kg!QpCIB}-ylUm3)mr9_13oy| z3>m)DdsXNTcmq$lEN_An!iUx< z2qOlvM7UANv`#-N>RAX_^Dc-euLrOf{IZ}~W zHEOb^8;ybE$n?&0MTju?k29gvR8N5FyZh zI|3grmezs7w52uqF2wjw%IWVB9?~sX@m9wh=wg+>jR!U}7m3{umAQ!jOlgc~j3^TW zB}j-LCyAN6k1vx7k;LP^`j-0h#Y9Ij7U284m^69+$D`w?qaZh3&2HzJAh`1blO5nX zYpX!2t%RC2exUKJ>ho%CO~~NRr4FO0Ts|oEVi?)~lJ;2C-8o)TPEaf|x=yctZ}Em> z!tMN8f?3!VEr2#?ZtC!))B+D*IH@xD6lBKP7a^Vs4pmzPZB>xS(x^4*48RWF+X*DSw(E@F3V0h%%R!x=f5= za9xn~_~DCZ0UJ%VmNIRl^3^|3gft83WOd;i#Z7w2l79KPuuz#9d3!cO-;CvX0nr9J z;VN9ctDi1%yR=`toKw(wee6Ewa9+Rgtmk7t^0eXW!CC%;uaZB=JKQI(K>X)$=0wE= zq$>|k=I+KQYobo;T6-uXEgm6S=QwD;hjC@9ezq&Jxa}j^K9jbWT3OZDIj0YV7BXj3 z$g_xCD4m_Y<=r-Ty$EYx>|3rN^=lWIwh>_hMohEQD$wZf6ZhC?S=MMXsbXeelYlmwE4J^F8Gfqsqv+Q*` zbXpF~#l~$^TCmkY_sicG?1m=~o>J7Wj6lYBtkXCa&5t{;ombjCdoOLV>2_88%hncX z7s8>cxMsSU<-XPQp2ZW3cBp70anp5cOTT}sHAM+0`vq`kfB%zRaWtC}IFN0*QW%^5 z7H<9NZ7jnSDRto(7rltA%}35Q+>}Ip{afK9)9p{w%0dWXL($Y)O?bfaVfz!bKxKX^ ziSaOl?{jC4_T5_{emshidjO)X>$&AnSm(AT=UR-j(rj?obEh)L@5x~Gy0yJ$&i5q1 zQ-!*)Q{^`mTzOvf&trrJ<)-_ghi>;lhW(Ay^GD8Qx@NYVgL_{;(_pKL)rv5QH#obe zwws66@)Io0GyYAh#@-2@{|mINuZdBmth8m}mVr*KR%*A30`X{UW%3e9ifv)3L_6!FUvh#5Jb0=+s{laN^h{UD#9am%1oM z#uqAn=;4@rcKNbaoi?ZlO2K_)tU?ZVVobzM)rWbe2HJoJ%mERjeGAu2La=xZDtb~k zNQ;z~#b_H~?zw|E_r)wPK7u5i=h7Ob)XZTBs`K^s&5uB>DUvyoj*go=YOYkS4|Cj0 z=~$eLWUy2QlleD=c|O%$R9P{b+mT+Z{}FCCBa4cl5nhg{2a-zMZb`&RJPoP85cM94 zIw{MEg^_FCpI(Ma$n2k4T|OfJp>3^p(w`9p2m-=)d{gh9W*J3QrHg!)9!3RBkq0}( zz?^2pY=b*uE4U9`GbWHg8Iw|h%JUOxsw_;>sqz;1;B@^$`RC6a$<>jsn%k2ZN<3YM z;oISE-mmW_uN}?^+fd0Th=C^sgD)dhQa)&bN7ko+IxoUtSXYlGM=UwxejB-zs$^1X zh&+JFY|Z%9NMoyyb8Cj8bq!@o^byROS-K4fWoT=HBNWCgE^V(oUT_AOqta>53cPHM zsdJ&>cw)|VX(#w5@yA@NLa@j7Aad||(vJ+Y`DifZ1#u8zxfdNyv!QqKtwUzLxkRtbm6WszY!q(g}6Ju|ZOuC3_CY1km$V+Y{=HrlL1xS9 z{+;mKO6!847A$@NL{lqDWkAuo>oRZ{)h)4YAw>B~R&G`OqU|abE%tKi zl)Ww|zDxS&s0dr%4^u?Ai=pCuSB3)#2sEXtQMlyNyJYlot8ufz@-4(YqQy5*jM8T^ zRW}>4TYaSelE*EPJ`vsLyVz<52H?!z8h#FFuN zgU@+??&i08!o6eU5&>H5Vw)3eW5Z%Gt75aqNxP_n6C+n+%vj*!2NLkQzOtU&`^tC=Nsu&Uo=F%IQlw2X5eD%q zKy{cFAbpxHq6Onzb$ar+b@zn?Ha&;4%UKJ_Q=cI6+gIOlVC4_6AXd^DMICWi$%8Eq zsqd(*2YJcYQ9crPs70i^Zz|9Cgl|x(P=JTXM`a@vGM*?gdc&Mb+FIIPvfeqz7*+`& z=60pyi~RLdBRnRfx?CXqBY^RvUIx~u1^gZ{X&oV*Z`)t~(YY*z{0xOnV7$7r2gE31 zy4^t|YCB)QB!J@FTCljU03a*QBp>(z53!Asaq()K+u|7JAhhHc9)}Amg!3dg4js3{ zi92CDq$;;ZnXyZ+JziEkg?jDPgongPqi$)JguSu)J&TFhb7_P6@NPx$I)j_%c*Va8 zt?>%{_~mROxT)Xj6-h_rokR>lXntY8o!RxFTq_jk*8WjZ_%%aFFHcR}=~*h&-gug8 zs+8iu0AA3}TSzV`dlD>)NZfhV1u|>-BbrLhl$Gw(ixD{g)-oU0H?EhlSh6cz0dpsF zVRE+|O~S7{ZJ5d0gG3rDAVRoUtst>6p~Q^kewrtM8PoHiYtKAYtBs`%OBnAx^2zLP z@<`#IUhttImZLSXx)S(f0eyER^Ta_Bho?#~L%gnaRHtz=s@v|a!%WVzDaDp!qM!K4 zSHj7Hp(J6OXY`7h%CO$nQL8zannI$Ate*JRvta6A?dx)W4?oud0mUW&xzCR0ZSeQl zE*{$a7^RRkgBN@0<6(Es%#d}AyUMBHkHdT(tjk`(cSAd6&M;sCaBnOIRgtR3!ZDFA zidrF0<9k)0{$pCwFSK)1+?lqrGZ~ZFAjNExdPjS_h>!lbg2^xKzKzFoZ44_mLT}I- zOP10LyKX9i)oiTkRUyGvZ0)f3KwxSwLkB}_OEDbbfGK5OHGn&)YcWvJ%SzWiAZioO zMBnV{DIrOwmu-(LbAgY)P7~m?wck!ZV^c1CQ-f=>|K#jWV+SLs;fTIw;N;91DV+8r1BzJ_dr_*EoQnifk zl`bh&%9Ex602JVt0{MZdA1_h;l%amvdO)7j-S+k19M5NU=Za|)(eQiDF~_$38)DjI z6-aEtynJ^B?ysM96iI*LSWDkX&gTeyPGumUkUD5%4S{HfGw{ToN}pG%VJgKaT>iG? zjmld>-0UgZ;OOrDV2!OEbs9CQcUA{vmqPYWhn)1t!!bx>xiRNnB2Gq7MO*b~xplF@ zGQdUoLgPl-fC}-;&1>O-%fbS{M{&@Wod4PR%bX)|FIwD-OiWDhf*P_;YB%Nn|Mkar zn>X{NlaR2=4++wN3n6(SQ2a4HaadQVl(BKQgSg{)tX@)&)`m( z5imTe+QUQ_53ic`hS7gRfeK+XVqMmk%%Na#l<1SYBFH&RQToS@9`L0>*gCF{ow8%UCG0i|lksE)z}Lm0sRvm=$2tR1fh||qBSMMwQ$h4UE_9dUu8&+ zL5W)mK9v;Xu9?GB2@qB(8lRdVZ3=}vT3x??A#F_sB}R*Hi^QMkZV|ma{Qp%aL@(dP zpR%9tr|bj@7M%y>tB67ce*oOa*cFN5-WQ|fml-j?{B)bjH6Q}!{k(^})N2u# z96FrwCFJc4%8r~NZw5R;Lrk$)hbgD2`P$MuNW!724gM!MkiO3nY6jM>!#@g@`>A`a zr*P}k=fNAb)&64VEvJ~^K8FP0Kw}29RdG*mse1ltd0Tj_)=9K9x^19b2Yp@)pQia? zJx}P&Uh}@>7+Wfe;%H{2CACdUA<4u+o2X~p6G=y(Ea6=uNb3KnubRLNA_7qk2l6Q| z7EvO*wU4iNJWFVTJ;=_Yt$uR%#YKGnYAqaJe=)FBxk!!{&(@JohLROP!I_Z|>)7d)c1D|=2WJoo z>+5k;9Xz?4p2?keN`K{myWAy3N%t3H{&iAE=)+7S#I067owZ1H-fqEzrOUw-HG(qq z=hqZXW686hwn(8^+2&BcP@9GblETb)_Ki#XhQ-P>X)Muv9Vd|QV>1;Th@UaYK%2zZ zo3&?X?uM`eOck=KC0m)pX=m^JnZpd26?F~U{5hR!)grf26tNj+6INL`ZXy}!KiVStZ$tLnf;`4dilD4XFxee4&Dh4w<5JZiFPn52QF zVi@hVk*Mu*B^H)Em8op!tvS6cfc|&o;+i2NtD}n+8vvp|27@#R*im}24TNzv-bPJ1 z@m|LEr_h$8MMZ!#@T8#HCcT#*98`TpbN-HGOmDId2x~%_d6HB=u&FGF!&oDZMMlE< zJ@ec~#sp3WhI(FQ@mpU$ck`4rjwdb04ExQLsX{%v@Oo?4DGy+(wR zyvUC0uI|JlPz#mp6(YN}BTPr3VNhwPLcuAE8p z_{l&fz|i;~uLE22%%N;OGJ2{7Hf5lO3v)!|Q5Mq}}>tmxr1TQ~x$DPCyG`FCHp zL6avBMYGSyER?nqZcxvrL?Vbc-yUr8_48MfC0YI=W`-@NY=k%1CPtAet=4crUkfDo1P2nMly1cHGm7M!-K( z6rrtSLcU)6X_-43#J821A^CdB)uU8+t8@=m3f%FUVhJaIl$KDJf6Wfo&n1l}&GcUW z#3W-O6DyvlsOa$ITlo?h4Pb1>PAc3p02{!zZN2_BV_YhHD&CnZrT@+@X^KXEE3b1j z^?>@|6ZtZ^vL_<}0|WV*Iq$1Ja;uQW{!%`wpd-hxUZKB~H_ul33VL}zp`6)#m=cHm znM{QGU$pZNpjc3rC3P;JJc*2*qhJ0X?OICetLA@LWhHO76)TWV=XjNn{>c?dboiaT zQa(d!Go?@&*(*I(74JI z^eupSnpWWQS38)y2l4JU@d3j$f;bs2@`8Co-5a*-c)3rJzxI8%gUUd|Dxc?^n)8=+ zyBm!Xy=M9dfO=!{BYlK9Q1jU#?gL-Z4*6aSOw?Y3(j$t9VQoCZOi%CL7GEXNIRV<) zx|&h|_>F;fY*QwEQWq$?{P2e!SebgC;?Y`NoRYzb{*MS)BOw3^&O=*AN%r%h$jdwh9Sr*Wk}c6Oi0)1fmY4^`Eh)Y!YW@d|C8M3z*pH%7KL z?PIz*+PV~Hbm2twl5FkB-ktLhDncYhvkX8Lw()d5Seu^Ko3hOS*%TRs5?Ult50dm* z!}6-#>?v-r-6zZ9v$s6xjiI83<>E_lpGb~ji_WUUEYsa7#Fb@58kGTTw9V)W&A7^& z&v?{Sz1`)t=|pu@jc~Rz79|Fp@GPQDTRdp@u0dhuuY3cUYU5V1QroGW^>p;zEc&wI z@M0obCDGxi8uFwgl2osC^?OamBe~_+`&#~NK zRb>IF-x&I3jc>DrP}!;IVQr7rBQ2kRaF0J}XEabEUW|{MG_qq}qe;P9(BHoN5*iAZ z&FpEXPVx(4OxoFH=%p8IATpxAd#qqU3pRJ*--v&r%X(WlHGI+{|Mw^&mH$6~kZ7s$ zJn#f=^nCS5w5N>#WD89nk=ic(k|=%6nZkF2-#HY^i*p7H2KUx!W%HJ*jcP{MK%TL$4_{c2c*%iZcumI{4_mjxd7avxpnYD=4d|~<;|3^XpOKi}7qn?NDXa;shp;EW)cmv4AO45Mr-?Tp&&{xdZ zFB`uDQ~{gGv-CuUC?lEB2>fnF53!KltpU_Fh{oPziBN3BH&zipN{(G+KXjo{YU>ER zWqOtS7MTve`0XJY)$id@2QIJU2;yY=d)22LjW|&YQ3<^%tTBkkP}(zQNFU$jqKfBe zzMrfs?VK>k}h*F+W!9&q zZ1KN0da-S>bCTs<21g85fSvpHzr}pfsTI(0qn9cbj@X%D2CCyS_C23_Hhzzy7A+GV z#?UG+?v}55Kc+XbKEyJVVA4FaW^)%(IPAaskyZ`qR+dGk+G>?ek+lPM;vZ~B*GIig z9QtDP%Mew^HPp`qBRYG9YYvMySvC&vqx#*JPM-gdkoK)mSejt~((#8ObRKsv=V^4D znsaTm8Xi9lj?4WvnvkW})3zwCjJKItYXANnrQa-RWTlO?cCMoghLB*#9qJO{ekxgF zAh|V=#vpJAg7HW8I)#k+n);Nh&cy|mvznS7PHPI`rjk3TFEv!%y?^>yp*~W0S04_S z^|S&v78De;-0!4u2@1K2^sr8GGL%Og%wrr}Uz4c@Z$Kjy@fi z9+GK^BP7#aP@-L%QO*VNR+zhXgoKU{8>H+i|7aWOHc~P*jQ?7E@c(SxZ2z4<(7zb{ zk}CO1Ol)y$#NmfChfq=zx}aJ6vkFK{2YP0R4M%zM>;!<3K6e$ix zio07WuEpIgSSjuh+@ZybJH?AT6b+C9h2SATD6S`czBw~z=6g^6By<1Eb?;^&DnK3Z@l+t}zQ_lpJsQKV)-~qwia8m zh5{o6=f@{hymh3;_l)5+jyY;Xs^h=Ri3GJJ4lxOoOl#DcJGy(uSo^h>T6DtST%a_g zH%h`<(wI@fi0(W0r^hw2idxSxkkz7=H{GOVD<6$_JB@*V>MUBbzyp?21Ud<_GmuNZ z)JV@o$-l%?1^dw>W0*|#vvO9Rij-#Ip+3-mhaH2yqk2BtObSJReGnmb`&ZSX%F z%4u2ge}4OmQi=_SA>8JjA<(u#S9@w3BM{F~f`A@hgF6d9>d$=4%XQ`3uwJqxd7gnd zrTTIWG4MwJ--`8$+(|orT}M+t=XxEM?jc^1@M{q3-W)0e=P3F4dQiz5cO)+h++8iXyE6NX}(3paZs4vQ4StwIhg_x501M^AeI{V}Q zcfO5$A|3deSoAf;lfFmM2@)LO8!H zGxJfZ-m9Z~d1EE68=k-4EF$jWAN!8b?sEr*=-?-lQA!P7jAH+)*Kkv2LwGADd9-jp zQ{&}pRCSr8*wuC`Lz^JgSMNP{rpoRGF;}9?Dd_GnynpBqdhsO09AcZ3MAmgr%bjnxjcBB(G~1dx4=5}BG2s_zL{e(zw#DE5-*pZdI;W&N zkqYajZ#XG_PM0b8kuA0;dae= z^@6vLKTXpLuRK&Ko_RhiS2H*F)4*TM7tv=3_0ZET!zguaI?l&5&8TvoH}RWRX^v{F zu8Jl8SaTd=StKbaTs+$mUeMGoK*cCt{}J&_U4%gN`_b$jEkAX&QK?VwyXdHJY1AAj zqbd4vUEs%qoUnk4TNlXPhyqf!{vj*Tjyam{H8c4hFqWV{`4WUZ>M-;6_4>Y7QEzv# z_{ztP^Sq~aPAf=S;F>yDYiq0bXRs`Q?(G;*U4HUJ0~}z;U>J-s2kAn>_a`q_0Cjd&qd#y90@$=tPowY?P4U!&RYql2P2ewV z929OTirmCilK4h-6gdxb&EL&;o~9w1&en@-et-Ypn9KhG0bb;Po(aeKc9Q{onP1nH zSIO;7nLBG|l_lK&i=Yvo9yN*k8Z#P8{Qa=^h5QsMq4_bO>U5R9i)Jv|Rk?I8Yk)wy zLeerB9d-V|U~;b-))GC2aZ>Sp#&Zf)+EE|@fokDIIKLAATXhvgN+XxOP#t4EhglcA zNUut_Cpgy>?>z{}pH?T`)%{~Hu=OrYy70xBzWU-vGXplP{b3EvL9Rh}$cZGj}Y_)cuoeC05z zQ9thxqdv(-EzYwkr}iGLnDWo7qEZwZx5(!oW!NtJJaTn1f|z~Cif2vvMau@11E}8j8=9uuQhQsMm!BcJn)Wj1a=D$FRZZu%lnlS$zh04}MmoJ6JH9zR z*k>tj-eLTR23eV0)Q|qDo*g9F|D$+%^@{L60>=vh$i;H6AHyXs-cbt*0Se+}srR@~ zBq^?}zW@2DEgnZH|EBf~fBq3qc&471SiSy83=~AKUJS!{ZRc8qlRqyH6j3alf5V7h zAkInz$e}?cGe1AVDfyddL@a8Oj;jLDPu^M#fsI@qBdH#6 zV1DHeIo-?D>umL59x|#CJ0Ri5IyQmyu019S1HtM=m^|s6Qvmbr14qk8i1Qa)?KVh) zb3icsmPmuQA62;|OXc$tnJ1;t{Z~#y0tH|>^;$12O3VC#=z!o>pL~95o>K?5Rmt=- zjT*!|89{$B&P5cV=HkRsLEV%h9MRwVu8a9TWp7w|=q1z!m2m&?cU9EgJ$J3MTC+1F zvKfzKxW-~SNG}L`ER6l106N)!2aoO6y4v1C>$@Hx=(7I9z6j;T80zdzJJ{Jm?QQgH zB5~UTgYYZ761f!p1Ds)hHIO=!RNC|KmnF&Fyy>YaP6bp z^y=EIwc@?U0km{Q%lfJ8N-|c)gMX~>%|73higl}ce4t&7YiYelHy^t-1j4^}dnv-v zSffWs;XMbu7S{ex_$B|HpJesFweQJg`yKPNMC zuaiQ6uL3f|TDr&?a(l<`<+*85)a=>;Ae zkutvO=_h;*&?l8rBf?w!nY#I`MCQxm9CgeU!33n%7ayF6Bw0(%fg`h0#-CW~N0yzV zZ;`33NnMjZOM)0k8*LlcF+}RnJ)XZ;wSW~*G*PwZnuy*ed)*Wmb3o=DDl5ITiUzab z*WrY@co&1=^2IA!O)O70{RO7gAwHGOAe9p4b4y=GwoBYgOV{8HD}y$O?~gH;-V;x_ zDVO2uej(225R+qCi?;el4Ss1BoBf~JtJ(L6&v#oBTwBOFl%!NBlG{AY6IHJz9MJV$ z3`i!;*>Fh_{;6rD9!x@cCe1DN$;T^EK7YDwm8s+K_XEm-oJc(y**7u-u_e{7$nfSt zNYeev9IV!nev!rkWPGT%D%kKU0^{4RqZZl{v88H$RS<$@5|M0b`9Hzn|1Jijz+rBK z=bla1!{gnhR!;60VZH+?GV%T?sbDG1d{_Jq&KUZo>d@t!>D`b$(!p>o*;+Paf;mZt zX#jQ*Hb~Zq%dQhN*fmB}hyGT^qt)jM(0xyvFE*fpamFgM#z9(5n!aJs`6?7=hJNC^ z#FtEhbt`atS=EaN|4j6>uq&SGui~xmV$E*nB{AzdPOrC9%Zhve|uv*mh zv(B#8G6K$v8*q_^+lO~;-+H!DqLQ0>0ZR!QK^Nm_DE$J{zfra`H47*Yy5)d!iH(~V zFT2F^tU{brJVr>I{UDG6Iwll}|7qZxp!B2E ztK=)K13G6#ys^!T0Ri5wKk{mnFU5cQO6qQ65?>03)rTmCGWG>vX`yj3VldQ+>5ep2 zlEe-5?=%XK(%2@DgeTEpx48LtWwMN$+LRyc$dT`jmO#TX!-=6HsHEo9H|j=`1=%I^ zPG8TM0s&gn8J+<$Qv3MI_(@EoO#P&nZEY3-j*uO~;Uq`>4J?o@zC5iJXqj$gPhHe>2E1Lx-j3$4)1ylL65LPipM(nAdQZu4wi!(Jn>#Osy;Q1rrCs^I&i?0rD37U`5)c~wYRRb*DJ9MAF7-pW|FMB{;ZwZA z-13H+|ADAE{F!68Ul6wtVZaTjeCRZxD@)CimumUrzE@8(v!)){3sSS+EPQ(eGP+ z)>Y%+ii#6I6rNU}l;RGhI)hEZeLH@B#9cWL5{}D0Y|q++%bBEht$uMcyx6<7v4EWu zudCKn$EObmRY||a;}%`CiED=xuZ1u=-H0;kcDIs0xM++(j@d+!3MBCYfBhX&l3E!T z=$!k!n^7F=8}JU$%nd&J-_Gx)3s{SIcg|_xhUn8k|Cj3_WpP!-dR1$|uytC4d=m<^ zLw!@ZeXFKa;XfPN(gf;~7M-$xh7y~baCLQKD4~bU{*#rgyZF%8+!!f1H*jF;x;qQ+h!jik{Nldo(ooSXM{3w)g~!Vv>3l&8A&m+NHM?cI5UdK*!`4|7fnlWLM!E5LDg70@z0t+xZC+7tZqz=Cez zCANnFQxpi5Qi9-|X13YakciP)06G^Pu9n42c(?^#da|jr(lGgd3iP3)nna->A7I7R! zJB*CVKG)rz7?BC*wV~Sp#!m_(kQ&_uFZ`nM0uvR{f)pUngn2(b_;cv90jzlMA744C z>NM;TTOo|0issJTy36#&fS*td4c@aTc7y9w-njs5`Z%|U1HYH#FYL7i$@S_ysp{UE zv?0qhb1{~)u=;P+taP~EdEU*qxUR#k;QRhPHq0CyYj&)=%RqlSl{2{N9mr*|Ll2~r z;KPiB0vanfPTIRcF&C5aAJcJ^mhEzY!oD=$9^{XXjs~ZX)tg1A!8kAQHQGPdm3x9r z#Zu!yYDz3`+V?L8({MEeyJnaM+_BXYEk!AqLdwtfQ^(no#3Qa9_$g*x1mDnFmE6iW zKO@g(EI%tz+Yi`LGy7nB`0DwJL+dAUHBFAwM$Z7rP-{imx)__AMG1V*W8d4_gDyKf zMRuZ!7dOjQr(W)}SI77d=y1&UHbrU*WUeK8LyG?c8Pe1QY*Su_hQ27Cbr_twT8|xo zv{98EPkLb!Yxp~DGNB@V4Hnz+bq7iYHPKuc&KKev7x%Gb#PJ2zY~4Ez7`50CGm^pr zHWLPOv{P5!fnSED@$jXLYQ|LSwVX-Li4T&~-JfEFzWXj{Fo5*}!*+AHkv1f?(7BfuXCns#QY%-%aAop={>1_$)k%7lK_jB)tZXUostA(ldD;^ zS*hS$NVv@y-&3W|+}magrro&U4JTn-nl|+k5i7S|<6G)<5O7H8rkVI#3Y*TcNml?* z9~bQEM!%j@vN~=#!u^0HT zijd9EHbIpiIS{Rl)+FDy$9qi+}(!%5ng;;8P3KO9!7Vz=1p+_+8{+u`qq^v zH^2$hc4vZ9REr=YwZJ~%P*fOI>{|bU%X-AhR9`@~Bb_s+!30O`S`c!P{^%Y0ytrmE zT4#LWRHGklUI+H^VcLf zUdh2GSn_MWFgE>Jvi$oW>}Fd3-=pO zYwpU(s1*}2Nmf=79X@-Ng`Dhhsg&`m(y#Kisj5^*f5xn4<%m=lj?tPZgs4Iz61;y$Jw0Cn5HSy1apFezNNV7$&?B(8e1HBD&6^f5L1HnD5b z-?Z6P&UDj5&hKC+!&^Z-n&s?t)q!c^jO=EXb0O&!1D7*ipOT2jq$Jw7UJs-7Lz{7G z!ac>~y56uZuzy zf5~dia`mF#Ao#lkrpQQ+F^C$U&6LkEd)-9I<&E0Qm?6JW!l<{}mq7JJZyG#?DB|sX z16i337&o=;!5B(%xGyOqIdPN>f|X19_YTEJAl-qXNxxs|ui?k+0UCi-=ZSh&ze8oP z4Gxbqaiyr$VDA2T;CB&;?(Ean&}X5b4=)1vaTJQPRGE2lp{xQ;3dD};QeDe`)i&r3 z0QMOvD+e}MnJS7higoIBNca)}!a!4cU!C5fNz+Wad82xaf2`?Us9Mf5$mb}K5zm+E zTwb}TRR|377N!nr)h$VJsD=h=owScj2#e48NR*|1XzdkiF2iNUltN~j>Au9Wubl@X zqx3$)b*q?>`yptZlN9t#c;`7m{x!Nr5Aw@WU5{lvi}C@Qwud}HW&AjuSG(ceDRL=*V{GqqvIpl@hE})PVyQTBO_-2w{^j8_?_qh zv&Sv&HH~|#Uc7P8R7)b2HkXa)+$cdfeCJK|0`9;j;CSPKcR0*4iUheQY_}RyAiHC_ znL3<0Aw*%`3$^{-)#u{HM0HoT4iQL0up1e=pzC1!z=cw)E?=TfA;OFCgFu%}7NyqS z>AL}j*w(yClWD=};(4bWS(vx*tV7!yv$X=JUm=%XDfb|2e9v(1LFCAEOUr_(%BXOQ zM1dDDlq18FNRugFJLLSjQo&?H;{dNk@Pd~o!nl^Qgcye=qi*9Q*O)Rfl8KXUZeL{> z1$$k%=Lp4aka8StMg}TTXvWw`r3R-wRas_oL{G zH#1sWl3R<1!lrSX2$s)}O=g3cy?XMHCVc>*_-; zWZPRj=D*Am1PQ$ey8s@&I+LND>AK$5ckzplaa|Tx^|!JN&Gq(VdTG&S&ZhieWgBKN}o_v8NB^=$7M^q*2d?sjDh#pSJeO?4^u>-fC!^PhK2;EJ4@(Ygq6Qe2#9 zJ<^OJ?GXdgDhO=YrfKnzzYX0gp)kU)vIs#$rDn4 z8fcO*Dn+j4s(I6F!Mx3K=DKq9rh}`c`#|su(-WSt#~~%<^awX0L-6-(+1e4JFgqecMAL z(iy;Oh*z}kqR_M!vlbQ<;Aq~IKX#p0;S^mZU**C;5SI2Ux<+^6;%lvnwL@K*;o7!d z9mIQ7$>57{lAcaRLgtF3^6u{vh&}tl<6b50Fr(~ps6gZwZQ-up6jL1&bZM3{4;FRr z$E1UWM9sy(XIq_0b?LK8Kl)6|_v%5+VMIi^H8vBl7&T@h3F%IUld?p*5!sO+)9WD} zB))Ao->p8{8>2TwJU>QkH_kV?*0z=fcHNRm0}t%=>?;Jp3{t8ge3s+mgkPQL_&84U{v)x(Qa^d2+4#Oe7 z7LK+^u(4+U>WYeA>TR=^+tzzU$i+v~B(sAF(eP~c4B%;U-u5qkZbZamSI6{5gu)we zq}bU{d)#Y}b0@f>l7xb9=2unCzqG@cV~WgoyW0LD0?(5rG8&&R13L6=vn)+V$RTng zSWdw{I$>b`@T=< z*L|)JHclreBVOW3KM@LOQ)lO*yK&zW@Gy9yUkNmR601E3Bw^O_LSvR8e^Wl|P|rCp zuWG|b#9?G)wC-~&wimUg4H*=1a+q@zrpd`8$5FTN^02C_^xQ!~q?h2zf{llNX)^&f zj|Jdk?+Qo%7&Nw$UL*_Y$F@vW@WW;!okW(C9&!aOuaA8O|(Tj(FW%EM5~S< zn2lE_wOL%|oZY*6s(Hj{ffl!s=c46XOY9l0BRNI-EcV(E5Z`nDtcrbks`VcP=xwe_ ziT>sGfw@8dL zQR+NDhq#DK-a$kZY{#}8awM&b-Osm^kc`RN{>vA8-M@+eE%O>}H4t47FQCdTV`SvYxkOs?VxjF~D(5gdb7c-pFgF)eBrKIO z2dvQ@G5u7)^A?3*~-iZe2VW+ME(;=njy%JyZYP~jW&URLUsLAKWbNA;7BVVC&CG>D0H%{ zamLD*aO?#o!QHF71k9ZB#JRrh&bPhyjK*Sqg#^2%JN^ka6aCDzqc7gxAe%x3Xiw9< ze>0)I_gqizfsZ$P2=LRbSyJy`-^b~f$OY~HqJm+cq1CL{t91bPcHd6D1n^1yzUpbW zmz?(VQ^4%LkLB}C28Pg^$Py-PYAdqH*QQ37hjWjrBL;Ym@2G}=yfJTJ9OlNO_~t?N zrgdx#b*>)YA?l5CW%+fqI2snb6iiYKmNt`Do7~_T!$$enXqvS|{M69W(q`UIX~wyX z^JoVB)T;hAHwTJN?+#}V+q!jE9^sIN03iNd)LnzN_*K%e%C6jb+nu}R)6cW_PX~-l zAQR7}!<=DlkAz5+RM$yvSrQ^u2VOhcXmTqCr!Amp%qDktU&pww?Fk@f&Gem)Yd^J% zfFs)p=NKAd(IxwSOT<(UD9?kH*3t?<)8JWF*HEL{lzW*BbUFJFnJ-}T-r|(NKe^Ff zgvgZlnRA~KZj{7=yu|3LS5LTLNnpI=63M`?R)U%-#?)IsQSu5Z(T3?joJ}kx1^>BU z>%bBzQEAXl{PgRa3ePktS_U*ek!}G>nTSJJ(*|VDuO(_YQAWFxqn!r-1p#4tYh<3~ z6i@WR{JdX}s9TSh09pg5(1y0e6x3GYW`!Y|OP=!w)!skb+o0FRYtIZh10Xq(*Tb7i zcwP3VSsDP9sG>erTi6B-OuK_-fKvf65A=Xza=)xN)kP4Nz1 z^{|fKwe_3bssz7(oRzp$==1;Gdp*Rp<$9kW5#4)-EEuuT!o?QWCTgm;Zw!VFk+j@C zHq@l8vnsRGU5lo*_^Zzs#n)@S*Q8LS$YY#g(`#N7C$eRH$yvc!nTptt0e|1YaL57W zJQNA=53>3L2qBpbbA3kp`S9Fm^{9((pW^uxo(f0;CGOe8y3WA2v9fIJ^a$`(sAl$R zeaL7Z_j7!X@L#!V8ZBHhw%?6(BVQ}OwxTL9`#n6l1#wy^>g}bBYNP9M8Gc0KalUP8 zyZIHOwW}MDgf%!dys%Ro-*#YDiHdejBdKnTW#IZd=iWG_A0R$!NI%($>=Q_$cvGls zzI4K+f}^d~x45&3s0I$-cXpQRUYu*e*J!b8*6O1r9nVARKrx@4h1jhlE@j;6-!-dibDWEBvsJCDLi1lN3JIEjM{ka?h(8`6 zWezn?M&5J!{Ig$ITwRUdnW1N2{=fDMHu-}aOHbXyh|ynREH99ZMuI-KF|mCDI7{*wA$za} zccB@1uh>|?#8?!0O!z2SYuH<(5dnKbFOty;2ZWmm8}~QvWcymj%)KxLoH9}!)4n#M z9;p_dX~8Y7r=4Kte_1IylE{EcI$9@j9o9=8d~)(oxV68ps6e*iIO}J+e9g&%`~Y9v zGjeKdh6<8AJmg;=yFSU^?~n9S-?h06Gp$Q>umSW=!$Uz8U^?qL7{*MwKXv~$yF4`c zoSYnUqA4rBoF`kYdJF#%7t{lR4J8av;-2hr$8qClCStVgzZ{fI>&~Wo?Rd#%t4MF6mq>PE*if!5VW`_|NAp6QLJHCnJ>Ko zMX9N+3639L9ikKAk~cMsxFIbZnq3RH6wlQtYoN0nwgQKq2C)lympL+)W7EV_O54V# zyNIW5GQ0$}{4mTdk7Q_>`Sf+>o9#OnZjle(sv2zM=2qX&6NbyM&l2l~+`@iBQk>S* z1wlENyA-1Bfa`tNg%x>@olk2a@S2`Pr{O_Zc0zj6+&Gz)>bsnT&F#HX-2kf3+K?dCOyJGIx>- zH+4EW8cCpRv#|A*z{PbLrV~g?1XEBSJgUJujAK3@RgI~T_tbKQBs*AV1impgtAp_c zveaPBtc`4*b?A(o_9ptJ6!kQ@8li^iJ~hLXcVs0DB-lEWPov6#abvX*fJUl8qa1={ ze)pnc&z|``F?3uc{#P8nZM7O&a->4G*z}P}nP@uRP5}K^X4P>UErV7gZ+5uucI_d; z`vd>#-*LRIXi==5l~1bmCK`bug-`c;2=w67!r|b@t4C8R>Wz7VIljosnSYshsNNUl zbPg6EpF6a>4I0(^vIwLZyJIaPHAP_lmGng5b3*I*WyDU6KQohkN%v4`1wKE1MMOkC zjD)E)rjq*oeV?C{ju%;c`@QT8mayMyy{z*2NNOg~>l)uiS{;4^)-zd6$-T@v5GqWw zJmG6$y-U*=l^yN9wGo?6lYo{CVe3;ymZ4qdRQ*mHl%N%iqehDhYilR?7E{r14C!8Y)-S~@iOmtz+#jGen% zurcoX&w-1Yuphg^do3wELp@#5Voqcj<>#YS(}?Vk2YKbpOCgoz*R>2}o{x$mTw{D^ zvphkPrv544js%=YHSmWnld0o4V3=RtYZZA*m0Wq52&S!|l3hH0 z$&QQ(+r>`wU-AN^TGCEDsx;xYYJ{-8Ue3zELfe9u8&2Fz%V+ByiPtZX(&@Gc!KXj2 zLr4pLGR@2Tb5q)>a%Jt!^?xt{FMaE`z56d+*~RZ`Xor)Ywt6X$waSoujSUw-5zhsS z_;%K6i@#mKijf=QES!H+D|J(tIKrfVm`mO>;J!d-T++-{a$Pv?_QgtARLHGDbg98% z0brBi9{6M$kA?#0vU;YvS_&wqZ%BU9umX-jw?7e^>M4?_*~}Q!gp6+|g8XoS<&i&aG6@vKN`mcEnsv7xTyn6P5v1JZzr?;y#du3*-W&tbFs&@} zHVIsIqmWbG66rZ4ZU&Mp-F&msS^ot@&o7U+jXy0r|1(>hBhvHHiHDJHQ2Ox(;2lt6 z)%gJ4S-p7Sa|EXyzMM8aI&QMj6Lgr%q;52BjrGwf(=q49f{u+e&-<8gkC$-VbzH;-B4&>KkpRsiBC84 z=KL)&s~=#r+qv?jH;KMs?{;EV6j;$D?GNxgSnZ+b z9F9Eu)$33#wygKkm5B_?={F@Fk=f^CzaLJ+GoNqW@27e%kS-a4_xPELdJW8@p2nm7 zuR@FcGvev@iZrkop@Z&Tqmx8?Kb-_^L&_HvH#JSYYZq#HF_Z63lWH)nK465N#F*xt z`cA8h^sgND2t%-Rpj6_Y+HV^kyOUFBKk&j!x*?> z@d`2IZ>Cg$9mPQ8#Im+b?U`@JY2~IkqA*j3{S2Fdl0{i|b!ykfiS~G;#&$h8ek^FrZ_;3dHR?p!Y>sxB3%P$)J?`rPJt!ioJ(w3c_9PDh_y ztr9Dop}>qxMrT=RNyAcrVWao{%(Kw3TJ(DgnbF$~-E;q-u^-VPhp2R8JpIfTyj$k- zLHm5sl?}H9MX{Ek0+0d75Z?q}?_7*G``RZrkm40Unr%dhmo!I|tN zU`>lrjh%fJn4&<=UPjk@XJFkrUgS2JciGPKutdPpDfd_EWH{g8zUboK!4`X@Lh}%mv*|!mA6qtI-}f?U8UtUk@$SL zNvav#MFU)F@<~h5Nd2b@Bivo7w+myL(-1C!v(!DoPVFJ_BAw<@%dO=rn}wKcAP>w1 z2exNY_dAHuF3J-Udn>I^Sf5P9Y+uwRZg$A`ZO$!VzZ3GCv=(=-Jcb8u$*0quQhv=f z|99=6ubJ>C9iUVAn~UYzW{VBS0_R~pA^&=D}I7y)U~Xs7DUsDMk#&UPkgx;QQ|JKGUx{WLMuaK(ltA zW+dy!y0GE6MGqJ5dTkViK6~h0%=*4#P2J0gIzZR_Sv-=-y1!0}T5+YBSQQT53XyJ$SdC3U~Wbi7DclNIqhquG_!*ltQe%co0c^3i~X5Z(&M53h{E z?~Ib)gT$Ok1~S;mq(F{jlFct~1OY!7F`7^ip<#Ams4|?$!AYn)@_PRz!k&wJ{BrIf zkTdIiwQ#|)CJ~$WORd|!M8~ehK2dKN{ z*gdS#!3jg;{HX-!MVN^c);t2Ut~-8=Mpk|@oVcj1)kul*(lOMs^9&U=RonXOOS{!H z9)gnRGkt5RvG?0GZD+p9Bh9c?ZB=rbWk>t*o(Do?gx`sE=NyA0J_2Q9ez}E{F=kaf zkyxNAZ~tV!@j+sjh{ytDo+c&6mclOfOTQ`m;+r+?TaAD$)*9T}ZB~|wpFrz?cZeY? zNbs4);|W6I9`EV53dMczlf)DKW7X4PZ>)y+4KTeZ{`>z)fw88_zWyLu_M2TBN>j)qcwZ@7F76Pqd_o~cRm?KC0M1753^S+aqFv}(iuzWfRNar;9( z5Za;o-|mrErV%g2U3cPGu_v)J>p?gX<0N2{@WVK@w5y!|lswUlozdint}*M6)@6+n zluf{TRScN1eRE#%b#b$&Y80TS70?8BV>xJecry%PlrdjDl)J6QX)& z%lqt9vDldf52dViMNwMQ+MIFnO))0-mcft+-awrvD(wKmTb zElr}RX}n#{>RM3dWzoOFwumXHwBbQYQjb)O`GgXmbr|wVe;OU_t8%oCuScV#dv$;k zPqGBH7^onRkDUG00`z~s+qH_}K}Zf*W3jF7Dr<@v;A%x)r-IFILq~Gs`(6vSDc-1< z?xek-2E;vH=d}L-u_j3959UM_~V0)=!@>2%(wr0%>P-18rMif(I9o|RZbE|*+h%#Wr?>MGw|?=FLr~=lc^D1RBI-fMaXnm)SEkOD zRlRxkfn(E9j?~-1r9HW!EcNX1S(<*x`Wq?TDn1iT7 z-rnrA+&nqx{}3a0&$jXYWpf6( zd%xEEH#lCtsS43f0G(BYq8SA_Kl>-KL)@jR&%vtkC)Aa@ma@NME=kb%5H5eeTKH6R z{pkA0(t#eplPT@wT4<;??lMfS5EF^v*aDgR>zPpZwhLf>q57F!!;*c+uO!GR#HQ*s z2YGB-g7o@vv$g)Qd|Q>M=I;+ZbW@Q7WXNs=FOAZTuDB;FY!y&K0*yICnro)jG6+z8 zf;!urRW!-w8Bh8;lmM`}f%beSnWm_+4IKB_r`{aUy?+EBUhk7SYFyW?vL_!-@#VD= ztNUhI1&xpwS;goB>64@9UUrRNGyw|K-!Pb(Ra-|sH`jW_t8rI7vItp=6FFf*v~+hm zz8LWaY3;Yv>zb-!9G53eh{hr3t57KQnEH(+?Kb)43>E8RF75F~-%t7=aSXz!f;4vT zx`|Ss%p>yMEq3ARs?swI=%~LVxko+xoj~Hk$T>ND5rF;e(TPPVGAF){#3~EBAbAx7 zIh|Wh+3mt5LsGecc@dpSUhpYzaDS#DzDSl+qm0DJSb&zAVlHNA*GkCU z&n!UaWOJ;QD$`-TKOe?0556U+A1P{V^f###3cB`CqYJtWEiL(Y1w7aZh%DWdHXG^H z&@^ScMjTE+Y2p^4HwU!yoKw~|)BA@>FAfUC_cHMymNU;=GYg(8$zyg@J4|>3mWr#P zuM1lu(ebpsE1BMQ1TX6jZC`*VIy<&3PWpnxQ?Dy!dsYLf1cM^YkGb%eMklP;U_btX zxVJ}i5{w^?Stf{Z7kD*qRrSzfnp%$R0G{49`jg2C|1P~EBOIX+*iZD_V zSX@tA&1Hk>p#DwbCFHnD|8}R5|ZLRAs26>PF`8|YKd~8bBJw5-rW51Sg z?fbO$oJYTQN7b6wd$m(e||hP z6XPj1V`CU;^&Xt`Vb>l22|s;Txa&yL6LT<~_;ufvW$|JxdCAKH0b#+^t^R60W3Yil zECjVEjNHuNS34#tM*4~sMcC}}w^ND>`SSo1B0Auc+uG8S?$PnFd^cU#M{offo=sr_ zdKeiEEppdO^i7)PXJq!R)nDqB%Iw#akr5~I@unOoB9)kbAaavuWM9`WW959&TWM-p zQ&VGejyOv(hlnl54CD%01fNKH;74-BwDrw)XQ}INygI{>mwN*IpwiNad~QV&T!|jr zqu!4DF`BClyS>^davY*Kt@B-Qbo$L!x+e)4^woD$Q-_j^D(AP>;6 z+tE7fBv1L`BcbGy`!^Y8Bx2)V<*Fz@7Va+7?XX&|HkNcAk1krT&s+_LL&)A7z4=CL zu$=ojYaW+O%W;^}oZMbQ^uX@ZF!8!s-b^MjnfXda^Lt)rfz%^!7B(~$y7&!5-pmIQ7AYlund;cX1 ze%zeezicgntR?Dp=H8ZFETDE=>@Zw*C^%mz1}+pM&J3fD?)K@& z!rx6vyWVcWLh~#-cUPHPVBpZkAnkQMg*`9|<5Drq&A@eThuKITOG-Z2_$x)`@~35w zcQiMauDU9;lF@$BM~6ZJfvlRZ#}~OOV;x4{%8Rcs|%k8+NPAk;W{E+^^czi`h=sNE_)wbM|z)nudkp_ zr{G8bd%>rvCw^f#{5t6o`o#S>XLegSWcE-M%>Rho+^(RUeZpSp3;1_LFY8brb=Z+` zvMYCiXn0-OGLmJE6xSr`y$R?g72F6CnWns8q%5J@RpnetU5(C2lxmdx2|}k-eydzc z7$84`7>fblh923quFfKvnTdh=lvVSvq06O=7_KY^;!id)YF;>lq~>TJKpLeig&ZYE zZwtrVj<{p-4JRp7td0GqQ}2b%Dh0HD2nCn@#b7OjFK{oOZe3ut^mdh}e57p{ZU1%%I+q71x zwlfDnwTlgrE`ql80IuV%3m>o6JElAUvBrn<54Y(`RkQJ}GBom&q$1the7Zx_Z>bAa0!Rjkz#`DtYStI=){T4B8e3 zQe26@&p_zdfc~w=a{qI1+gN{V&i>D(uhl=Ygj;}U*t)%3uK<^>>#^|spo6Ejt)u4NgYsQN(iwAy&w(qO4V@j;dM1| zeGm-p`v_JVtG!%Hjjppzzi@bjfz9ISO2@op6*rr13+!oB+m?K&mR!6)U(iVwSW_JJ z?R-CyUa<#uB%=#3%!*QJ&B~JacxEKzN3CUjBhmX{IV@ABu)Fih>&acr=gl54>I?H~ zpt=<~97ciB(!{p{Tlv{;@+s)a-u**^!k?<`8zytU^?<7|;9Y(jwD<1h(ddFMsEMHW zDxjA(_@eIK)w-8!OX4=^Nf3eTojg@Qmmiv$T~+=YU^IPRS$Ku4oVk{CM9=~Ps)%Us zhw--VB<{_f)|Qk0PEA#`L4^I7hWKoK+->VGiN0Y`a|M2b{*{X_Ey=k~=~o)k`fg^wYao zvB;Q&(LMJYq%aP&z@D_R+)JST(jfUmdCAc6y98j+D_eUZ!AaqEcu>zjm=5L6%TdAm z>tpJewzbldzswF7^byg3BPcq5dP{#q4+e4wz820`{q2Kq*F3i1Tr9j#)nnO`kfX%0 zy^}Q<&BU1bGmG!0-5()2svu2ISU`YcSNpl)Df?}3k8Duwh`!}EQn!&&y@#q&e7fvk zg|GG^=}+cM?f;@J_?hT!r2=8j_hzGmj0<^@R^Kb=Z~|l&IjtV{kn8RSYZdF%k853Y zdY|8-b+ELgz?Zt9^I^P@k47%gM9k&=lGPs(Ua?mt0grRy5~BP{=crxNgJACDe^lRuD;%frgN}#E{>B{Y~vOQ(Vg}_;z4^K>z=rT4gcvt zA)6-HPoicIEo>~;OXfjePu5qH%$MmvonOvve*X-5|N-(jdKb!?(WQ|NXP)%$aBAnR~8#cVZ_8 zSemTOK!!j%jFLY^vh5_CH((`Q9*Qy?Q8r^&2}E>mQ}@bNZQ$nFc9S%eku;ZviE%iu zJ|i8_f`XQ-ubS~9cpL}8aW8-GS__xU`BFB!I*kU_JM#zKcs2PfX$mt`EC%(xFn^x= zBG#9BtL70-b1dKztl#yR!uYV$#=^jHn~@(I z*H7WthUaG0@!y3fo+eWhmSoRVhVU$w5gNS z4i5~S==&Vk+?BB`1=Zbi#bQMAtc1M=L4v=U+p}6AtdOhd8nFNT_98%sg>2g&#$Vw+pdrN$koWRb?jfY z722<#Z(a8?(_9)f8X9o~37SCW*$ZaJ0r$O9&IdKE+wpJr=sQr3eAt;SO_w27{(sd1 z3(2DDICk465jq_ETUq73=i0;HuKUv-h)=z%C&rA8gN%1Y5JBMeu-kvjyS99m3qH6 zvR1I4z!~sG6FNs-B0_BRaPs}+(eq3RM=M3MMYR^@qM*4eR^FwS>xwVLbryaUX5(M$ ztt6@1qJeG^%j`bS0iH+8^%wa8-C*z#xhHqn@M0vaNsFS6IMNfcA;%UtO_Sh{9hP9+ zPm%iE*iFE(Odi2HMs$RSz!Lio<*wAMj{`}G{V~ktB08A7Ujk`6lB>1N5HHheK$JYx zOwMa-nM=*f)44tmKXgs|G>?iDtkd)!_19yS;A}m*u@vbwk3BjjoVCVewW&GpBD?7c z`I{$`M88Y9V@m0qgA`!yDh7T^EK)@nb)0vr&9q03)V##^$hnlp*pKg#sK`9rlJG!@ zIwXAdg(ZIbfb5OkqQCud+TfpP7eYf3aBGCd9ANejvtx+(hk&SF#dfLjcuMcwv#U0@ zi^$o@iSeE7&UN0tlsb%Y*W zaL5LWc}?x4lAV`N)S>WYzA(q0IYIhY{M$X%(=3n^*}(hFP{eTNL#E&TxGS&5^9PfFsKV)u51@<-2B zyki)Fa^1(zP)@)e2Z0=1DxZ;=XYbWu`&7|a6%Kk$x)zAKCF3B{x>^~z?2!V&(COq- zw-?5_-@OX(>9up_&|N`OtO@n!xld6Z5zTb*rtG1+0pzP{HpI$FNNM`?CiD(>fC#Lv z)+|vQrU6CyeJZQGDxGb5f)dMtSGBPhAw(*U&8PKW%f+Nc)IAp!Y@4$xLGpt&i85E# zv8B~S+*~qnTVaBplVXM{P!1?;dcJN$;RxnA+lbWcCc&UHLSxub6bNVFS3d&-SL3QS zZ58PF;tO1V0YD;im`;>NaF(2LG~#iNG#2^sM*h+Scp)AnY}~~KKrX#bD8~5CKrWe( zu~Ny^jS#5OI0*gZAAPvgbyZ=tI;7Q#i9lcc_=&VA|*=gs;$r;JO*1uM(wWN`|q>QHqxrjry zex8=)`%Lo9g3_3;z9#zQ4gAWLcLMHq)uxK)%mAoJtan{hLRULAcVcnx}GFAc)Hmq-UCm6&&n|3`Ewbm1+03u&YN?W^%4MfPY(8 zlpvZ>V+X0Qb1f{A_mt|*T4`9$v_jI^M=X_%5X7ONt2 zdI-d-_SZm00%J6_c3!+}JgPiD=0DYxyX!d{$~gjD*AYEWe(fq0Z;GiePz1sPon2lS zE#zh1=S+zsCX+W5rrSD;Mc0RG0_Nf@uw5*Tm40=t8${siPaUWdN~v;6v6+VB6rh&y zZtLu^247Ki?^hRajq`4d4_2foixbKkr=olvE&83aUJ|SYOsB}CfUqVMwPSX+qW{xU z_(MfEicOs)jO9C9sBk$G9 zGB%W|jeMUymT~|qp0*Fm1VL2PnPdyi+M_uw3hFAJuON9w)Q63g^vBSpGX0q9WzM#$ zq8ci|`qGS!jDWrX?;uA6uR5QK_95mxLEbYt5qEq1xV)nM;)4Y4V-kTohBrRy;X;cw z7K$Sa3M{s3Qdtdq_GB8O&?8P^GTX4Ov1g~TRmQxkKOS84>?~&!CRN#-6)}_LIR2VI zRA+uU`Z=KQ>%W%;^nw6}<-})_p`mDqRs6I_SjE+OyA7=}h9r9 zDqDk;Q6K-8xT$hf5_X|Z-jw{miBZR7nbXH&9j})pkW;Tc1IXl1YuvrJQ?=3A0kppt z@r4&uc*XHOH=OgF3Q@C#CO=9)a|y$|Dxkoe?YK{ihe8_QHuKkE4EcGAaM!3OymMBv zv%TK9fBNK!Qw)ZA%Z5(89WE5$Em?#u)sh(t|5Lk9cO}OXi|L##GH_?Kf9$TIiy`w} z@yw3$!pRNHseZG^;-nP7H$cez-__lHT7OT{9-=;mN(snX3v2QT`=m1I9*(d?p+G^#2DuDK z9J#Y-OtMxsHdZgZ)o#}^F{hk9(b7s8+9L1OUy^41EHiXvlpxNNbq;;U@4B4ArbURm z+J`)DL!kkzB&$3kiqoB6iEF#*6}VV8dJ;Q1IUkDz&);Ae(b9C^o5isM3r0qc6=g6d zTjnr7sS<`|`0&HAc~o8{a8KOpZU#}ccfD#>;dDksIA7IxZ111y&8)6RNg@O24LT4B zQVex=XRPe_*C=dlzG!%i)DCj?lQ2YC=Elu4CxkacuZWez{l%PS!ZD(SO9yWIlH}>O zO`GZWw(7spQZQBu7Lc4Ol(ig~zcV97612}@f#I&ME^6a2#bx1?R_s>O3~x~PHUnUy zsST&Z1GM?O(qh669_X)}-JPk(3t$FzDflv9ag;eoLB z>E&n(9kyuJ72UiGy!X$^EZgHo#Dgy3#)WSGjwwgd%i*KFUxL=qFeD8bAD-DW6y~ms z7!F|(AsgDa;2_NPw>u{ufX-0JpbImn3E_GIJ~SPX-QOGJR%-gqir}9dYwS|%U%&4P zv?Undc-{Df4UgVci)wXez45%)$oA6^oaXlZ{A=Iac_*~n)BVNSok^cWZ>dgcsQ*&y zL3mP|`qcf9d3>>b;V{PcUJ&roAk5Ai+l*uRIaF>}==}g*3sa(w z%ZD>h&d5VXauR(l9q!2z^ss&$Ggo^C{*Dmt}+ z@-wt~{B++nS8zSOx3*l5t~^7}l!rj6pWpJRYXhu%wh^KthSB}2b%%^7P%6TvW^Dzp;I zWP@sLih=tK*xz*RH>_4x(M(CbfZcX?!f`Z zq;pKccK7+GaVCNlqB0^JOa2Gt$J7q^RFfiJWFB-MhI_}}i{UmluCvv>}bPd>}XE>Bq#t51*ejtybv z(&}FcxH*SO(;mFGw{U$ifMlLC?Ej`xpY)O6#!~+a!g#{pAQFH_)JRF&N$rZ}d= zyA_;s?%7odx{{1z@9pn9M@oOi zf#o!`batw1G>uf<v=T$+Q(~SJ`k3Z9rkNfDDo2Z^Fl96umla(P#R&R|;%nBx~bE^1s)e zGpnod>oBR!%{c3ZtG3o+M;Z5tTT{tH6mLx>t@EnxdAxR1$F2*wlSBIgt?Mj z&0(R7I1qG%I+o=8 z>v%0+)_A%;RfRSGAeJY|iI{KwEvCdq@!XDoa`b}S|A97t2xB`&{@;NGmaq1|Fhm-g zYk|)GhvozwDu-dM$>e(|URt0dptHr6etdsOuT*`f2ma}l=6trnVRY!tBG;_Md%lvX zm@>R4VJ6782N|8OWw(jr$>;?bM$uwjVD!*h>9Y|1w+!VYz|xOsf)jfK|o>?`ZI|iFbe}f3L2>eqzgnjTYH) z^x)y6Mz9fL+e>A4ulm!jf7rHjFqsHlBe3nT+{LGvSJh0*+!HoZKYc8=RHT;r$CmHa z3Jn+?OK#fK3z2pIt_(O2xpiRiKiIej?LhCo#c~$8P2h|Rb};Da{}&imZ<7659wYwmDJl)3lPjZV(2`I@-CuTzL*W32wF;H=g-yV6Vg)J+zS1Sy#NH zg7g$O)UbPkoQg&v?$SYt*KaoMn%+EE*WmM4FXq%YxEE9O9%X@?;muca|5w`l0mvDh zJLKQxAP@FK|D}u5p4NX(MIYh|tKtz3XKVcJ9Ob0WpgguWa_}3($Jz5((e0)SY~@u* z9DU4}NTkW)d%E_~SMVxy*Lx*my^5-%_JfQenROm%*uD1)RLyY^58zNFbB|9rNS0=w z(j@&Jb#pCS7Qh4@ebxE|Te0r8%juf|T=9nM=QPmH`6CrW($gg<#?s23qt~{DdM{?2 zYY)!uIH7C9Ll4ZN)?VlXq1ua7B3D$KvF`?;W|x71pFhagiimdQ&DW-e7MtdCk4Lq} z!_nraIQ|!Xrkh4(msDTw!%a(g@86E=>0z!GrOt;O-(JrLJIVZMr)-JPT-*Lwlt>fV zT562pf0fEm=S#-oOitAGpz9vB+i#moP)^WEww}UYN!dcW5EI5=SY0J(D5l@R&HGAw zuO$14;x3$Rm{Dd7_aQdI6x%QqCnuIhwVS5ODWdJV%CI3+WeP!PfB)vJ>YJ7P^#zB4}jy&@GXAO44!e;mYd+Ctx0aB9qIc7!wDNzceC5vCW1Yc0TKWF!wgPK7?q0GoHTbnL2&>=BM+9>Z1O!g7m=o z{7mI}yDWbIA^yMl0uP>dU^ge^`@cmZPgvzkn;9z)Xjx&@abdUyywUW9^hVV81bn{P zvCwOYbQ3Ds2?|Ebj8F4TF}Uly*SQe9^fVMr0!d|+4TJ3aZ_=Mxh^8r@s#30WporY` z_+iwNRQflJN{ZC!7P;>SnwuzQGt}%~-Ygl|L2rr;{KI!Kjw=D1-rYv~`H<|m@#`w3 zZjP-_OQx}Yueof!DLZ8=Mvuhj-we2Ac=-fqtTb^>&gdN=?Z7zdIUg!soF@PVQ< zZVz3%syZ5B$3s4)VDem?*$@mF)s)dSHZW24``0Sd-A6;FHNCQMeTx!p-peY6MMStk z5fera7mh=K=ly@4*?O39liJdl&f1-PuuE&O*v9wdwZ(%&)=`bLknUl(2rH!eT3`{e7=Y|+5Iw;aVAt!+$P?$DtOsqg+p`ZjT(fV z20+cuCb+ZqPzw3Rv=>oTVbNLLim85)&n^B6<~eF!>UPH$d4vvi;5S}IDBel-C-d@k z0H$}e6_p2)%6sLIOu}!P%NdO|$?cCO(^4BV&3H9d6D~5Et9`#vyi1U@*84(m*J(2? zP~RAU!R5E1Zg7!OG_|fcJb)LyH@o}&7CCgvq@sgCDMf5ir07JJt+eJMh246@nIw(D zrlDpzG($ERlR8Ps>?1}3QNp(rTIy8KjoYkQvabui+-X>yku6=LN3v-*qNKB;^D4|c z5jrNn4AnO1*VSd2ckxVNOT23R)yFGpQE!sRR9|=F%JlV41LYHn=VO|?s*9_5BiV-F z!LIVBdxE=W3VW=#KwbbACHkq@QxUI3+RXa!ozga*$b)%~FPmFH@;?_Vs2Ah&VE`YU z(h4*^+Rj+rn%+TvTt6llct8#8L?U1Mvu7wTL)>g=m^BRb{^sVbpF38pava)`qz0sG zsEbu@NqBy;hQ=Qt9(oM>3d%Udmqh(8|uKzm(f&oY(FXMAfn?!MA7V-<5j}%?*bwnbMApha5 zx0WAw+rWBj0HL5GxeRbIojJsfVxG(!m*RrFz4S_l^C+%-+><0$3e8U{Gl3REH-^CY zT{;2O(&Xbu8Lu1f^`(`SXsF$TLatu51@dIs=jnSL`C&GE6qC?lkTlXPs|)~2-@4bG zqTYzjlb#lKdS$EZx8-uhYI3RHDSAO1FxSmF8jsB{?lXmg~)_jw3ZT)$O zSHtX~@xy!oL6}m-cT|>&8jm#P{PNp5Lp%PmrencksV}E3)cp*pDzs^>@*Ccw>Rxnyc$r{(rpO>w9Coeu=D#$;G7?T4 zhOPBg&)2ZNpTG)jEf9g z=o>w>e=?NDdhbWPPrf0&%&gCK&`h&cI#i#fhrPBDU_gCwt|{!6z$XH?l=zyebks z<`tmT_^N=tKWhCwa~wqXe_p*{6nS(f*nMdWaKZBExfg^Rz9VVPB9JWetoWi-RPd;5 zB%Rtg*Dk}zeQ7j>JJmz8lUoSaZyY^`!qWXXx3#ghs8AX2& zIjZRGStk2?^RHi9)DaC*S(?eLfrpa|hi-+SL)}awncn`+sRDT0OnB1o6M59d#YB3C z+Mi><{#Ki%6VXk!*M2Ka&EVi8pgbi zK8{L0&44`b-ha~bL9ihfn`Qg)*9Ra}>WaLu@HK1qm)!`<5VCuyo11}KEIW4!I*Y7L z+;vtX(-F~bK4X05BP`{$((B)ywkOLwUxWXWE|NcjA?|-&kX|4>8KLj^Xa7-p60Dc_ z&$F6-fhWs;b`R zU<2^c$*9w%go0J^{7A%vY5`k~J2C?!JeZ&^U_kDXSFW!Sj!~;2sobNz8zgOqUtlWOMlW*De>Ao;?h~FYN^^>SMk>@ zzpb2~k7<=d1YOAnls?;aqy?;)Cw)n_$Xz{3QCX14&+&jInmxP=p#tU;Vv9QqH(M@w zayIecQ{g9j>wM@_iNPJ$-sWlb3fYGXQO*$ z=lexHmGdS$#_c`xbQfs^hmR@fry)P84qc%boU$tM9n4{ZSvnaEgDO)`nEFJiMsR{N zinGdHINr>U9!JNzL+$98O97$5Y+J&sQBG}m8{teZ)S8R$pZa_Mm}z@Id}S&vyY1i? z(CVT~4^cnCd>lK|i@5NCQZ}G3$7gkmFajE`ia$-DRG^m~ZTX?GbVwLx9N{raIq?V+ zNfl4FYN$JkiR7>%9>Z7j0yEP5zmGFZ2jnq?H4fJ;kM+&1cuzbI15>@m*Eb}yG&dTC zpPg!6K^}tpgw6UKsI9L-W)upo>(MPO$iZ@WEDLF#Iu}?4pwq)g-3c9eO?E8thIKnV znw8{1%R}UdPx`4b@F3sHmasN)z8pCf!Cbz1%HmJ#nXw_oYA?#nhXOwN6{sl_vebsA z3Bj@Pd;^(}LF@=}R)q?OkOWhd1T>{y#ZJ@Z5wgpen@weTf^5rTUCRXGR4zasZ)llE0k+-ny1lP@x4 zQzFFC%F?QDag3Ml?^5aYJ>l^}%MJvhc|s~Zy}lmTy5TQ^=D2oC*m^KK!yO#u@RjaQ zkGlUy!-X0V_SzKh#4~H<(dN7j{@F_}60tA&C8hEGjm^tEFbi_8?m)#Gpkg=FH&~D5 zqy}%1-IKhFO5c9&U}<1FR_mLu#;@zL+E?8-Q!)`3R>6Jsk7N2Q9tMlFLJFWcLy=OD zEABOp7ezjAqvEzY=!*2W`|MCXgTj8XX?LE7h^0Ru5CxdNy$<`8;ha@)^vBfK&8Q7V zOhvYIt3Yzo$@*);opq$I1T$tC^9rF9J=3ZkYWDu$f~v=!l6L0~yt;Y3g*~HxbpAH? z5sZz&y*%jOd@j0#s$xB%{fvVb!zbS&m6zR`x9gg!`kNYPAJA_UCvqpygV)t{x@5&! zxZt4U{JSPc?_FQS^wnM_Xt0kFf!dgp@QF7TKKi#^mMkolbcv`uq5|C@%q(nS;bP#m zEC2x3WVvniFcWng@F8?PS8$aLA87B;6dI@r&+?2RW+B8l{ zep??gZn0Xiz6lLb;{$tI(hbxogvQiF*|E~U`S1DJz!}*88Xe8VXm#<-!L7r<7to+lc>yro-oRR&Gt3*D(oTuDNTn!@zMc=r(&+%r5|I4SW0_ zbs_;}{n)dNB4C*WhDMrbdD-^_lCJk{ubnxY+1Rb`hfgRUVQt&TCvuml4zIzBkkrEl#+e-b8VaZ~))|*BpLE@^h;b)-OM$y|9Buit)`$1T~hG z;-%cp!f0~?h}WFj^`OF+U+_puDgV;8=KItw@wf$qjgBrdvX{T0ZJ(ak-f zG8s7)t%NhjH}Zy@L^t^HaL~b0gU3SYWkd=g>Q9BdNysBVf7H&?Fk5~-8Ypw@+XZ4o zs~*E-Sf6_Zh)UDL*~5`h_t}##+;>S}8t;T5a(+ zR32j3s=XIyEFDfyp+XEYar3SAma9c=HmF*UI$iHt5*Dl*20{HUu3KA+7OeFsDg}qM z*HT%-*By8y@MRy^tv#d5^ciGA!wSR`bVHQ~OryK4H`yZaG6?4yty5`hpF&aUT2pI- zs|$%gaefkRZ9lSb{4#1c&0Vs`KUVU}D^sA3Wr9J8=Ttxd+mf2wNTk}bqZGzCmmDL+jCvZ|sQ~x}%FQY*+^vf%p7o!COsf^R`3bZO zLaEHs*miX~SEK#Q%2e5jsZCATvj+2@w}zeX=6tMSs~-XX1fi%fA}~<;0GpmN1U1a4 zR5!pP8uVCGy+agd)zUF*)VjSnG}-2SrFn7!Rh7gE)VBuEt;dgQwZAev^17wF&U!T5 z*twnZK1m5CRi?Kak(hNe-|=@lfLYL_Z-K>6kM{SETPx{L02!hDmyd5d7scLQ)q)$8 z`J{k^`wlc<$UDyEos~G@%8n>E!04ZPCM80V;~UD;M=q^n{aldY>*wX7qe@pL8@P1n zEJQ;G@=eJXjs)nrh{A$=VJ1xBC0?4$4G-hrb^QeumIjJ)kx z#`x2dOaSG&;XKv2(u03CDFO?B!}Xe+vyXvZ#oehmx6F781`F4ZzaGC$g9Ge`)0k|t zG9*GZp%xZXYnkmg!cRH;3ucXU;P73w1cQ*>FJ!@{5X2>7pjo32B+uiMfq}-sNv?@Z z`5(-8_W?Z$@d&UVeyeI{GIF3~u=#bc^6=ap&P_~yYtB2W`B8a(Ry+mnZWXNNInG0k zQU1yg`HZ1axuTKg1Oq zlww=%`}^QMZmdqXme9j4)VcCOp@p!Kr6)NzxIL? zr2#uq4r%$Wbk`9c=-+z`!}&zT#MZDxcPcM?SRgi`eJ?b1(mu7*T+l%*=ybpK(UtMF zBI{^+0&-J%`f5W`(2qBjkHOx>)0{sD(J&uBH0)ZF`}M1HX>-1c631F=tEWo8wb#Hp zZT!d?(p!}VGJ%};ygg;eK+t&MX+6qdDcfTMr4S9IkIeEFh)8r z_Tzi*4tgP|rC1~!S#m){QPA-C6w454e@0!Q-GmCJ>A4vPG0JSh)z+|GFTP|$212Z{ z9hM}U)f^OZKo(B{$w(iz3e?v=3uO_8`IEiwGI_6)Vu@<2-B0*oP2ekfYdF{1hnW0y z57cw4yJk28u(Z+ZgU8_=biHPtZ%t{H3#~wt7)9Wb+@#nTj#lq)BKLHg@rJ1;+QpU> zf-xMjB$^QKmjgz&oxRiS%Y+4qd$49&8YNS2KYk*VLsr=$XYXX>rb%?k<0 zs39Uh&N2dwv(RX)mxzjs@P@rf_0E3(>E-r0*m0eU{jok-VCYIMKA41(AYD%r{v2&<5>9 zDH3SwaT)q+_(uqYD>fUyXe7Sl(zqVMV+_v*Gk3dAdm&TWQtoRgBdp+xM2(8ljqK!J zP6@XEEE@H*F)Y=_75%GC8a0ZM`9)R@S*F5AfK;jFxIMjQu6_D;w^w_~B~@$k+x6QM z==yT>1;2Zr>&oFh@VDPqH#+cl7MW|CV^$EC$cM$}HYA?SDeyVWS&{a?R}03rv(uz1 zYZ0`zwR98_@_u$+SzcE<&3$QVbWO0iN!wE~<9+9qE#s1=LVdjVzA3}V5JhmiiO?@! zl*Yqdq|ox??)$lXq{VOmI+5U#Kk|m_eN|I^=TZD06X45B|G&tmkf=S#UKudCujEdg zTVFJEuy;i2;4=?Y14K8a{J@E8-GBK>eo4MDf=nnMlV51mg(#h+2Ghndd7&4IgNYDx zG7`cY8~^FT^+QmE{dE?rq?oSKhz9KTV?0S1gvH7{f_NxU(0R40r__*s2-amN%Xc2e zR8g%(mALfv*MX@7zU2<#nB$*wpPV>T8s6IA3#>BZ;2Y|2HU#x5{e#*8*5~TBkiTKovY~f`L}ddT`yg%VY*8r zR#f8WO-1Kc$t!!+F)oEogwtHzcFNnze#;tB&=OQPlYT)UP$3|`C zyrJrhQ7JeV$sUQjQ@;!MIkM=wFK7l)3{3*}`nM9`8e5S_0tY^baq4g!1s(B7uONB^iE1M*@f!`S59$#gdeU5Q{ z>9(FV)L!4N*f}8Qbx-73sO#CeYuonU`vVaE{j-4wv4)29B7~xM|3{@9vn}UJMdKT< zkmvQcl>o@d!H;HOLscy0ub)&cJ#c^CCuk)uCkogDXG$<4h9Rc-ZiQ+i>wkQ|U#^R% zT|0){ncgD_0||FCT1x^Ovil5dW`z5%2)*DJJI6>QS_o`^zVNqK8>4wNH~x!uB2xse zrSmd}(B(+SvH(;7Tzj6QEqaV|+Uhq&4?Umu=9;}D;Kv+qjbbh7C*eT0sO+(xXiHaw zfNirKZKr6&?kmoi!zel8#(A)R9~(^f4_L2Rk6s_AuVe3q{NB+-Z<3f=V>-%h7?aZw zN)gWTpN}IeF<9`B4T<3&T)=MA?@$`=npjfNNTM&1L?G^V)uLMMjI!n)cL2$2w!LEM zhRjTu7-+bC3h&JSKr?yumKN&SOYN-_^wGh?wPU&-jJdXI>&$sKW&1zH2Phc5+^#l- zy|=JsG+425JG8$x!5z~+R1Rbf{|m$NG2`^)Ui%8uLIbpXSP_T6aN3}?2~inRcJ+4I z2l8!1FDT$qz6&af4zkMrav^JcPan&f)68YODzHUz3_i^(9u+0KF{$e3n3|pCU$PwCuP$R&`PXDNo^RrrY4vVMNP6U1@A5trz`} zd@b+A+lX=j*N-PI-7}5EI8$gj)m%AGWNqoeld9384pv;S;2w~eYj2nNhK(q&%FUo@ zuYa6hAL^eYyBZzyo7xxuH!#$2LL6c&(93%egX1f6V|Y2n5=y0+XuP&S!%U|&R z)vO=ax_6u$;r>^Vs!8)=yXX8>hD7HK`vxB%reQgwoKsl+2j@jY05#2TsED>rJhx4M zjuWGYEkQ^6Q*I8XltABom~m~BitNi7>kD-MM9=%RKXIF>CGcMjbNBwNs?X~)P&P*c zQhI3k@vP4;pRk$?Zc*lOzArG(?P#qt z{u`oGt$TTLZnmTPBJV-tSbPHv6fbo)!#BgJI}zL&$8KnqMsNI4SMO1sx7py#gQW4! z_?WgoM7O=}S@S)EkU?H=7NSBud}#t$EL!Kby?U6phC$wKE44-bfrE8gK|D2cgSU{{ zl_4Bu%rmB8d!256WX(PS=1DH6WruAY6$k$VHm9w|zu7PQPB(`PyXuBF)saJ-)4w-a zdw~vq*t{)=E&0KwCAf+YR|kO**H2q?-X`$|gARNTv7VZtVTmy^Yj&BQY;n2%kmI{Y z@Lt4v66;R|+K%{P(&JvbA$+tQm3ofpu({y)dTOE(U~p^$tPlW3>_P+K2N2x(@plMF z!4;>Fbl(X_3*yi9l@CmF4*iNOk^QMbH9n|h#7x|4Yh6axBbR0i3sYt2bLVe|fWvV> zk1U>^p0%sbs&O?!A7l{zXQ~E1v?rz!Zu`1AA8{ji!>XK{>(#6owZMVyO3X}9KE#kEPCIix`Kc*gF+Nqv zi0qh+?2!&r`~#U!i`K5d$bfoE;IlP2Vd!;6E5F3??Q!_}@0^mI8J{p8Zf$zsf*j>y zAB?$#G$fkm!on6tV#=#S`JwBjpthza>AsFyH{$T5Dcf82{FIERRkdqb_Ed40v76g% zLEzNQ3G#dOxmRG;F^1O)mc`Bt2WJ)Q5>x0-)BoORPz-UN{wOQcx(4?8o@! zSqy&%2M0!`7Q(NQ^o*znWfXtwWRVKs^6HRc?HMO=?o(NP>&g7e`RY>UNto{BlN8$Ki z8}Ri05oxo9Cyv+gk_Mc5rg3Tb5g^OqWYlJa$Ks^bQ3AZ$c?#sApZfP(+k`kypsGig zCU85ZtMBNZNN;aG#doDH);obz@R5l`_?e1JSD<3X>d{WuOs`nPiFFxKJ!UE4+`s!> zN!7UU!Hl~ojh|i{!P9E5J#|(P>~YSWi%tVoz#yb#wd9C9f`V*1{4OUa$}h;ayF}}+ zqyzTAA0arsi_a^nQF@9_(3H{Rty(gyNSpGwJrj`B-S zA6tDEq<+A}OfTme*Ml99pW1ubYtB(qPL)PeLG*VnFI^d7x<1-Fs9_(+Qq9H-Ct!ApI6rEcwGjWMc7fc9Cn7WenjdVB)X*ZnJKwe`Z~_q+^6Z=sVP$OHwMFB_lC z7Co~y?c(tI3Qp^|2$}CC2?tK#6U4nxxP#M)gySnV$R1&0wqjBZ@D-Qx0P4n1-6@jE ziGSPVQDgB^8-z3Z=g)7S>(|Y0(uB*4f`mI>#0Y=D8+N%p2is%N9-3g0IU%|5b;+w~ z+T`L<<6w>~x387h(EDA*2gq-{UZ7XB&&klP&$<2ZPV(-6d;H~?ql86tOr2^UT_EQ% zHu)oZcPmvFiRegz|>9=#tudb4G0!LC`YX1%4LvY4GqK%k7Tj&0B&NA1;RH7&)A%qrHkGf%!@*z#moM?QrY?^$IEWEhe zYAaA({S%71cATBBszIG4XSg6ra;%Zl?PAz7>kz6`|F1#uq*-N_zHQf*Ph=lK_M+2< zaYJLwh6IQtRH+WoI)&MH(MamKLgUzhG3DbU+gBI=Y#jR( zo0(pX8uf2dswBqWi3Y~%ddY7({LdkGNA{!E#wV9297XT-+z3cnlTVs5e87Z92gp3AXcqp45qrIpJntKsbIw1V)xKn3 z<&}+dMI-0Ru(z1G&!bm--p9WgLqowHJwfqrNcC=SqV9^##hJp^Gpnzmb_u}m3B`nM zjFq4T+Dv2-wX^Hn=f_a=I0Sl}SCfDjzB>drZ;dBBb)CTB<~IuTn{=(?-nvGZuRy<( z$%y_`P>4rwf41{l+>`EXpXpi6s}cGct%ZHEJ+8Z}{>`6nghQwInoEIPQ8-3|uGJrh z*pfID2bWM+>GwxRtEo))@DFABFG!MS{_M!dZlS=hv(~cJhO5Ln3!e)&K~CWw;(P;xi&y{mo8YZ|9#iN;C6K_?u>M^|=-h57YxKH@et6vT zOn*v3T3R5io|8Kul~@B2|1&o{O;(|ta8efkiHtke;4}RrU{B)6!{KV^Ol(^EQ>j zBhnoFTwhza=!wP&_3|<#wZPM-D%bn*_-(gG+UV`96-;`5e^1xN>z&tOH_c1R2lz5r zM2wAM1nqID!6_i|V5;zOWKH|})2;SxnRoac0yLk5T^!u_D_ortTB6%yYXajtQN@5 zUYT7-I2~*a8smv%aI=_}L#XrMN0=F5C%xq~m#KDVoLXIoRJE+g^Qnw?p)G$Xvw741 z@0f&tJ^2~comqqG!aY8W15WJ$n)sCW5?Jd=c9HeA9(Ux;9%!?#A@Q@lTRZbMr_yLO zJ_jGCls;O56%oD0FZI|C>H06p*G!gH`#J}>BC_w@de+I8HaH{9qwy{Rm^FQ&Ergz@2S^G zdKS4c#~If5U>mZ!qKdZj>add0eXiB8V+_vQQ8cUu$3=nRybgX$FU5OsxFl`UA#Yzw ze;71AiQ5s&z!%exKZF?ke)G+uk?`ZWKK(9V0TPj0Z!`sbGR5MtjAon3K1VjyI>8@g zR*pUWu58-(@r*Y?@Bv(50GKz+IXaCS$@vVxK2H1Rr>m#^+AFu;^HaY4Csrku73QCznc?*;=|a5 zUhj7}bI|6-i|`JwcX{JN$zUc+h5Hy%d&;Vb``=0G@aiFzU`U{@k~GL74PpT4eAI~U z254W5ca47+)OYT1VA<4!x29FhA4iWr=v8kMMhU}4v!c~=k>Tudv@%Z{Xdz*VKzBid z@M}!Q`y1{h%~BKq11n~G%W3P`+kBi9DJbwl$S9DEHVDiPp&pY1rj+?N9rJy(=i#N6b(0hye#Y5_MtSUKUWPd~#bXAehqE_2%nk7) zg}sl<6vzKiF&UI{81>iKox)2Xo^pEhTHM~mrXLSZu0?PlVF*`9zge|7__;0t`}hI}BSJVTG$=UPMFW$+=ZbHIhRpq(E^75x3a^!!bV zHKXu=LvqcjX=*o6JiRsK_k_^7-=e8O3E)D!zEoaKpLLoN$Mz~wiM0L)`alK0z&%5L zWs7{s<2}JIX#km$yh&*?_ZMp6${qh4_BsG>!GXLUcj-y0+sQfRsMwWZD7pPbw=dbB z!AB+_B5R{}Y^R2F7W9ROhr4O7Q%}2%YT9Ynq|f!!%acKRe$-8u(iy7Tv0eFgxomxt z$!Y8W0?kUUJ1%ra=GT$)92VWca(l=Fw66khllGScaN$ERd@a|{htwDRlKQPTg|~XY zXbOdM4RcuJ>8dt%KYd#C$$S;)`!g)&WjFNrmJMe)d?O)|L>&J|oE$EHjA3kx=-q$L znOG4=Y{bNG!Y(|~oiQTDg2s%KG2W+VU&A=QgYiP2Q8r~OMOKn=-WV4KvXRFh31h;( z^L5^g2eK;^lx3QMMfYl$l|^{2xQn|n%=oc}HTs)CLN+ z+UpPEEGgnoN8>b*5@ci9CI%u_@}#uWY1ufzs-m-Q7o9!T_1tRIQ?-Kfv|)qHpx;d= zM@OmKJx=HP7_u5@c-BwH&tIma=cj2hm?$Q>V(ih!rPmj|?xP6M5$}3{!(kGdZvg`Tyv|FiCYj}klZdQA-eImTEF%iQMtGtSH&M-Xj!6tA2@u5~>IJ*ml zbOLQ6s8VM2)P@wxi&U24>Mag!Koj2>u)t!bBJ>Ac8xP5c6?xQWMRi2IP)3YY;P*-` z;m!hsje2@!mJh}%%Ey+9UTLQEAji-Le=u}noWjru4={F>wo6`FhGC6zVfeBEkxRk> zMn;5$dabT-R&ucoV+bsii(Hc1Pg`1BQTJJssd z)M&L*qto;Xwdv?QJ^lVk`r%)HOuf^Q61`dXP1^_FEcNXG?)$ABt0zQzK&zH-yCj9u@v-bxEFm^;nBk@^5Z(ZKJHa`7yNL(FIXmH z4Qp7#8^OYBivZ_Asr-5&>&1%rc4s#|c=WNiG2GdCkPaVyp)(}ubC>CCIF&xZ zq_xd7mP|d=wIMkk9fEen;A2;M8QZ9%1JoqPv)kcbtD64!`>)c$ZYTZi`{(IjzI&QB z&&R2*WVExL-97Ilae925j!xMAopXp$NhH||kINzf9_n)WmSMT=yv~5)+ob&^0bKCw z{U+dqwG>7YY8# zt=sn+J}98kE;ihi4R~uK?S1+v{qz6)-=&A2eUdgSvATzJEH}moQj#*Wy~(O7b@J-y zy)B^>B|a2k_+m8|tC=RAt-%s!6sF-|WMc>Cd68x?;0&phK7RZtRjRer8}!r3*@?q2 zTwn~TN`Wd1H*XvtuxCH~kX}B2s*jrRj;E=6+)Xc^K1;_h&eHiXmQ`ac;T$eX$j5Wl zR)_7wz4X3oB? zEca#^IIHX`!pZ8Vkv`lQyQ)$`Q8H~5+GKOa5G1@>&RZaE`lH|NowKC^*a~_%FN|B@u*3!%Q5? zgTc%K1_m{SWB6lM4lCR`?T*_cyz?v|@s+cDh)C256*obz>SzyOU$KGlM zd4=}V+1W|;76!GFSA0GD@r74?b&u8VmYT#G*06?m2OF$5#p14aH;>O+YSIty@8(6! z3bdClA}|C-99~WOU&14l#QJBD#mW(bErf!p2nMg?MBg9%Ab%0(QsI#gsOUe6C-BJ) zM&blS&O&9t=nocuQ;4oVCRgCPLNg%_k1%e~?9@y`xJI+?(5*lCVSl^|*M0FrF+uXa zz$C3<4QqG{h|WT96Yn{07+YI zr<|2MVOI`CLJyFfzAgQMt<#aMkEIu#ot}A;-M;jgy`8pnuh>5Q;|IIxci(*ONsupJ z9!Xc}d-56Ek$>{(Cuz4?bG#p(ousEPPdvy-IXrPt6m6jQa4)EfZ|59VwVi0ccf)ep zS55az1Gum-ru=%~gtsJq$A+&D1%9o4+HLSw?-xy>aQ@oh=h#oV&%m)j$}(M9h04I# z*sDS=vT-_@ewOeNlzGFX44&f*Fi9wzu^SNSJpo#GE{s`T(ZzTXlf{KM`%k8<8XNf= z#aI~QXN*-czQ$M;c)YFRaG?7@->QKpiRTq#tZW`DE#sVMR9?l5TQqtsRJm3{UkY46bk$+di3A}sdPjWd+CF*vA$ zr_*P9zSz2Ml6pNUKKhU_;D&L6j}RXh3@xna;sXH@7)(l1z&f3F+Uaz>0?c~=3uml! zN;X(vm}%5%Qo71%qz})JKYW*tUpzO?vGVC2oun5}o~7gGXK6YPBi99|GefiT!Vt9# z8&bL+eEC`W-Jk!M9(<%S>aX8BO9SEWb-DM1XPPdApL4d#m9l4wOhq3bM?RvgJYs-= z)n8trq&r1JsbmWgQR4Eob~Zw$X&>g6mh@r0XRGn9mx z=ETEB#FO4oAdsiRi=>XiwJE=B#K9*Uv@VsNyYtZf3T~E}GCLEQWt#yw~bjN$)Y_<>)+6aP8`KM+=6c`uN2Uc(yJ z@W#L^t7~IBZAq@gIMHr*(xZou)BeGOw6p&x?d(1Dw%XezR^yjFIOMn8{heI8=Ygc? z3h7UHrUxNTepTOQF#9^>Jb!KQHl>c5xQ-$FIGpbdkgLt0ugU_y31WgCGBi3C#!q&h z*ecf~H&4?^x0hZV9b3LnVJ2 zmLBdl({8(J9g4KW(Ik~5(|_^VC+WdnQ*!(uJvr*9qtiIEg_---qnI2w9qAi(p%%x7 zj+Qv5-QV05Z6~+qyI?u(^1$qM%)d;yvz%hfjd9$@ZsGUa7`~KgtTcTyc-3~W3VyA9 z(tX06^>Ih=ueC;Ar!6k>_&(b(m@O~F<2A@sELQ1q{V&tEs(m<*S+winK*Whia~#Mn z(f4FO;^4M13SEhBo^Ucv(Q)*hv4QLI+`f*hi*FG?6n1%HXR7gdSd95GZaLAnig6}= z??z0lo_gZ>*;&_H`Z8YC>vbJ}V}nWGj1$II!Gv+y7zYV_O`RV!2i;e}oDb&}xXFJF zYj|(qw{YDG*YJyj)9IdVli@h^j?dD|XD@V}==t0Oh0cTTjBwdb&@iwu>*HJ>GH7Cj8(aS6l}nr3tbo%eO!=_QpAX!W66cRG zE8q0dWri(^Vzt#w?aoeWshnGtvXxK5s`Z+A;MpMza_Wwf=`*k7PkAvkp%`E=^lB^d ziH|68;8Up_E8*hfD!Ql>DW0+PdurnxMkNjzy_j718Gf>giVr)AC&Gfy-4Y&5dC{`PrC7 zMD;K9Qx_`3#s#VK&@5jgAm{*x^HzNFS@egVpcw!+$`R3m?+$Ugpc%jDB5uH4l*Qix z`E7BB7XXM&nBv&z7U=>zWzz+2<6zKFP$V&iJNcn-MSN3!=v#xw`+_LO8rJZOhx}UQ zH}@*M@{5pP*BNZ2?FwhYR#KzUNuPfHRXTX^I5i|&?(FQPR;wdfu&VH~s#a^M-E2yC8Ki&x+jsK2RGT_Xz;r`IF;rdiwG# z^?V*LTPI4_v3wF|iur3S8qrDIj8$IBm+zSe8Nx??`r|hM-y9OYd7w0aQU%P@FGKhc zZp_ysycbx0cNfbZVCus8+JKxuJ1QQR!2vhpj+Omy10k`z30&vHtHUx+mth(AUGYB@ zxUrt!0a(nu1>QFA`>gNVAm_WP?|B#Sb8K6gBFYMVtIGVkTv)`hy38x`xRKYl@T^FZ zvj9bW8w!vIZFN@0rLmw5>$8eec>63e(#Rh-j9|X;5ObBzfW>c`^gS0UN_I2v3RtXz zyW-vf3z(Lmpk*cPYxuyxEoNPlYxw0r(W3W1d62&S$A3tl{N~G4YBnsEvPuZ!3fuD0 zIcLKct9NXml0wDGA!gJa9Ua@qg`(B#_G|>hNX5(v3`ZDGP}s`bQpieiVfd<7t5Vtv zrAK&dq>-|>2VtNx?%VljZ^=mn~tBqNJmdk(`1NYN(JG2p>GA- z(`a*J#j7m&yZODYnzQu%Qk5wyPB> zaQXmZ%#$)VX6B;uv0|kQK9ou-Q>)>bxm!{aS>e@g@1`n7Jd{zEZhHo%6x0%{vqZL( zLX3Vs_e%ItSj!4yNj8Jn7#Nww%lT;-lrRqQp=Fy%^GIQ1rDe-VjEz1IOMcmC#HuWe zWzvk}!>kW9hA6f%+!THr&Y*!6Uel4&QU{PZmIBO5xDDl7uQgo1d0%Cq?5$BsqBGhG z1~_KiuzkuvG$9Ol%S`cxyxHau>4Q%_1~9g4WE(}kziuPOqdJ#jj$v^_{AW1W6%sDj zwS^4PF;ZI?oOaWT<72yPs-t$hnf4F&eIHLQ)2Wp0AOH3wJ^kUi>h|Z|eYuPM)L@dh$`gN3N_ilO-ew<6P0A|N6J zZvW_+_TZjF>E&`(P!xGC;szmkgOL~z3);woxOy-YkpqPvx%nAV7?lxX+Asg|zJVXY z%DYhH5dbDd-h?L7D~^JA$2V5-L$R;m#*cFGY@r>>fpC+V%R&rrEA2IY_&K6GZ>Qh^ ze#lK8V7NlF+=0T6-2A-6kDysKhSA3^;_7~dACZT_2r=g9ZsHWCMC9-71u46d!Wx%D zX`_7*Cz51-&^`)t8zBTZR`?X<$^39%LVhH(=~4OSyz$oWwf0e@;Zgwc9M@>{qu^-M zPUM)}e-eH`vym?H!?z;#djT?D!y0}Cz-yIXuxR%AMJwLEJ0Pd$wk0_+&g5z~+v(#^ zzK|^QQEIpL((e9Ysx@1RA~|rIb6vNUD$>yxtb&{T*YIhwIsVs&(gPn&r`Kbx|o>8x3D6ac{Djs z-To-`htqU?CVi_v;8Ww>JXl3I67Erd;+gJzQ_d$t$@LfMq2%lb(yOE$*&*vl;+YL?%y2mu^ZWpoUC$G0@c;C?-QJV%(W<>2=O%kS>>0ZnS?%>WKCf$(N< z$-{XKpzA7auMcld`+dSPkAErsr$x(q0z}i>;BE81-tJ!=-evv04IQiCLup&9-U7Hd0(xMGrj&$OiPxNvj50DRru}q@}KCgiZEw1cd z0@3Y|H{>&ES3`tc|F*8-0|dVkD{C@0fcvQC8#8@NxNn+)H9rFGi)P@haSOr0=O3j% z{F{GDk3Rb(m77&{^P5(hn33Qmzv`?pdSFy>2P}UKDhzzmv5(ZrBLShP(SdtL1T!C` zK+(C=ud=FV6T^?(2;EgFW2|Pv@P%Oq!x-V5?WJ4P2OYlhK07%{{qCuhIkvVNr0&sa zI(qRUoxJF!$v_&FJ_MNwEA3v}8|m zl4EM441){c;XEqN^MW7@L|)mXJJ-1nhu%(=TAf@Jf5Qf@Eh%xErR`L%)l$2?lRBLp zZxzTEh8U69vJb@-g%G@a?7IDax)dEKfnt^Uit({lZFmMJjKc`YM-yB%DY&FX8O0#C zDSAM!=Ln6@x=fwyg)H^<*AODp~-n~ z{@^Qi{s0pf;}(3vpa`$1Th0RDEHV^Y3|tr|OPghHCkekd6jrO&{84A?$>FfCHYjew zZ(ZiA%En->>p(cTvxUmp%hPmndYZ3xTAfBZeDEN(ciYN;BlV8D>B--orYAo< zQyNjb+&FFm*sv7$iq~@ZiufzR@g#8M&x!ucMLpAu@dizBmN)|OMM<0vz+g$3Idd6; zSxy%#L+nzr7}#eB0jUi!hbkmJPfh_&(i-L55MX41W)@D0kp3bFr|~#IcoiwHfHD1- zY=uc)&>7KU;J%=WD9*6B3fuA+<-XidE8ajLR2VT8=AjarqVQmEIH!pQPryzHHN6&;td~i6u)8HBSs6*WPF%8ZhFwIdn5v7Qan_NUVw8Juc z$~O?>3i{$V_yUDNv%vW%1l)4xu!t=HxBTIsjclfmWUs;x#n3-K*Z2XRBK{SA7y@6k z>A?4<{GfZu$$;DW5t*=EZ@3r33M`BKFhOA8_Z9eI+Q<{)7Wpx&xHsm9Kf2CRp>M+v zp;~^&^|YAezCoF;VGX|q;I)c3oo2uIlJOGo7G8zooixb3A^EXdPi0;8W+y#-{7HJO zi|q?p)zxgYQb}?$6O!m{oYDpYq`1Z0uEU2ixVDBxpjPMg76XiudF3AKL&It;01fN)GDGrTcw?=|m=+CLvR zL*`L_UVhKw&GW#e-vdASHs^1CUvpZ%lXEZze}~^c-2LuC=_0kS1JTBA&fzxPq3!!zmK&y0_;+tWp143j&60&=;ux+qVSWDRS$1^o87mE2cz z0Wa_&;$HJ(4j%+RKvp1p^!4ZI&;Rz{rkzIzsZ^~s|g#`o5I8D^C*6URtUQ7~q z+`8B!o)u86@Is8nID)~8SqvyO%zD7cq`u!koQXPmI(^RXYDuYYH0u5^^`%siXVY8i zZOU1EG}M9jPft>}dzyxWK^k;>sds#uPL7V!*~?xU_gRK4LdhdvOMv0)^KXBXzWMW? z(*EOzqI;Tp!q*kvfpCtcAWlX@(G~mDW2ED4hi;#Br84p1W0oWW z&mnl&XkYsMg+1Y6t^f9n*q;{v7cK14|(QcX6 z!RaVH`TNuKR2K^Vs`jxG+yFerWOp90h8Pb-E6}LyU!dhjL2kFoD9?n)zJUTW>6~`-7lsT(e zh=bA5$#f^aF`Bq2hjDNhJ+ut5zo5;C`8RIkD8OV=F43{M73FY#N@rrB$B~@cS#2s@ zR0&VurYj;Sa2N6H77AS?kBo>zyG8H=GyX+-Kat?o_(53Ih2l|WN5_AGA4GTNDv$G4 z{Gtv?55$Tg9u*&dp7if1&?S0k7j{AeWiQgNY#;hF&Hj@YH0Sm~ETyp_)c42))5+Vm z4+>~>B$I>q#wcFfFoqw|!M%bXIgi)khvG1lb~ir)H{M(3hfq`Oo>`fS_4-9K?sy&Iio+5$(13AqS9gzYRb12)T>=xL9v>xP~>{1Mm*t z^lI@&F1`xH<878Kg=|-ENM6}X4<9~Gk3ar2wL1H$*67H;?Ugok6ikGQ0Tm1s7rf?{ z%>r(JrQ>_Kh7SvJd!j#=OLae)QVz)mKo`L1;a=9wJ z+tTSmw__k~r``4r3w)WFlvFNnro+9R)T)=$)}?4vPT*u`jPc~$Ml;SAo9LT2y_7C= zewq4`-;YmDeC3($Omsw`sg$=a#%|8xHr%9oTaH+0S;Kn*i;DLI$ho({edfIk zp;OFZ{r&rS!E*ill(0yPd$iXijr8V!)iffOTK}D+jmg#TK!KHQYNyS9*^Pue6cA`2BCwAOHE^q{eP5 zZA#&|#K@qG>99SsKpkkKSx?nU#oO3L2TBL5&R3l$=PW@WE5hh(*>;YVNhoaY{OM@j zp(~y47-ld^bUGa=H4Q8D7-&%F>y4U}G$}bKY1tqn1+05^lFm+#(y%v5gVVEg^71&H zzU(S2@L?cX*+;7!TPo8xfB9qjO66>{nn~TgjcB7@H+8$+G#)Yoab#tXZ9t%dj}JoK zM9LWo8Gu2?E83WKDTQilvy`?gRd4yn_Y6M_U$tg4m8BGN2E*>|PO3G;SK(we6f2ju zlm|TFEGzg6Ut%>~@Rcx(Pi#>b#w@lTl-j2}Fbu_3gZiLS7fKt31u3{vdaJdHaY1YM z?9}CB^;M-*mV!$BFtkB1b*ZSv!IqN!Vb6xE60e31cyIdL@{E zc7TDw<7v zB!5!QMZ=i0zVxv_J?o}kx9|FINm1_XN-1wOQhB?a#{F@6_TBUJ^t)%GE9f!MzNuhn z)Xg*)w|$g@+_0Q@_Ct`t-_e|xZ2}JCr%;eZqdjQ9Jj>T{^gz&6h!{>;gcnIep(q}l zY(@wX;S=>Tj~|f&$T^gH+F21q+#(*&;a>$H`=t*LkQ{l*TsN`GbfBV&|ZW&AK@|0 z;36OSg%6-`Ls3p13ulJl$2ISjaj*I<;9eD1F!NpxUlsp~-@?O+xHr;#Cy)@hIpv%3 zLp57CsZagt!MQEq3#WePFPHALY5IwId>eO)IF8~DKDQ4$BM+kc2frf!8SaRXja@l@ z`~(EeB#uF{9JI)Ta4X&t&EfA>U8F4%74R7Lv!}49Qv6U*-Myk{}e{?4u9zIH+e*T4ImHkw!H6-^o(sl_$0+X(EA%p7A z-@W`U3*sftuX1?uJzT?w2Mn44F&IWYMmqxN`zPwMdxLR0I_ajDCugZU7)giFH$iQ} z=K)JjXM1(Fj%Rz!wq)LBqwaRYB(H7BV0ubK*ui64xcJDRW3-wL=f$~RhkLDbxZh5@t!k?9p;a0tMoyHD zofbI5_qaPsC%s|n4Vm1>`%n?8%XB8)-J)23YDL24{Md})Ra!c$~JT% z3}Sgz7+c3%78DLoR@~aQh=}e(ey|e#1$~Jb@jk1#T$Y~1_mZt1DT>}PzTd_p*)>1A z7Wlr$^L+rgZ-Tq?B<;=VZwJbk%eV?|!%eEU{9>gS6Id8SWQ;GyPA`kqUyRG1^?IqV?`s~r9ghb3rg!zN9C{p*aZdahbK}nB z^z(C!Y>Y_;PR1$&f{u3$%k}=Ib-IRk2Ck8HEv(^#g;fo>)M=!z|NO`F+rRuVRq8b< zJ`#voktF4cP6$H?tBN>xitP@!q_B8!Qeh|)o&l&1n1OHZ%s9Y+G}SX(Acm1dpo}rP zFf7jM9kw}SyF(NfuVT_42QgQr3{{lBV#j$})3MLp!ie+o#j|uio}@vypN^h9PbV)q zG%^f77i=cKsvj1uwN5kr_OE|VpMCjdDp$*Cd{G#MPLF+Nm^;_YSWuZR1e_7sE9I7-Le9Z4=3llH5yHC)996e;w6eV3O2?v3>WalhEvfJE8(O(b79n! zgkj#1pW@P%rc!PPHhi7wgRZiw{nZ-fw0F3dTAhyLk9*_v;)fUM>5nhec4D7q7g6aHKpqM_`EF;VT*De}gxtPqFbmCP_P+Qx z;_wy$VSKiOA6?;Zx8KRaFa8aSP0{bmEFc{GI@Q9vShylSF&t?Lw;u5U{7hWOi>LS% z6f~23j?oeAa=4>}+i@~t0VxQw*A2MwpVJ(eUymQewU^`RTe1-A-XW8=hBf@6A>Pq> ze})Vg&0n&h<+NIAwcDxDY^R5hKi2hW>g?>NTD_G@3S%-6aaq}AY?4Jh$*BP3OaJRa zM&aFd{~=fyms!IH4mNZmZZi2obSF9bMN@p3w zAlrs$+bC5N8sKPrnfjdDt1woV<@1*>b%!ZT$ZIugsoj)L;;r&aE+0EdP+p94z23kR z;aK%%E{Jr_a~{Z_iJJ$zom6LA#R|Gs7^_(o7tH6)n(Ipe;x83)4{#gay9a(r`=)f! zYemns8g9c)s=H{r3&iU+yf-LB%zJ?>uHFRqnfDrg*|69@-rXNwjsH5Zsz+Nke60d< zvu?*raAV$lQ?7M38NphX2ld`%v&8w z31ybW=4L6i+nsc&a6T^OdOhv!@5h#r!ccA0Ri?JfhA|MF;1boQWi%Kl9$P%tQ@J8u zNJ+%-!v_YX4rT4~oEezEh|Cn> zfNczPp)9K`iih!xd>N4D+%nD>01su`<_rJ~i%QQ{l(aQwrmzLd`IHYehFH!DGY9>F z9+rXn;hx3KwFcs+cj zFwPfnJcmXM7tl}9t_(tQ$*Ltk5E3a2@Lsn_W>@@%GyEU|SWGm35G+6609A8O&x55xE2l8$jEAO%X_)bL{ zehctB&U1ut8E5fi+(tRao!@Z_|2cL<(i46K826lJAbtfo8hHFL4|mW?egN_{Ufkf0 zLG<(U^Ldo}hfMt%*6=F<39MWA=BnCGcka=nC;IVz3LnYs-`MFdT6fSF2u2 z`+Iw-TCMsFF;84W$J^fWofTl{QLM1yyThcl;b559CLa9*U5S-o4-R(Hr;qm2=Z|+% zrzv?}M6==xBNbaN^}1chWe&z*DBV%lS$~|4x}$X3lind>*~U>nrkC$I=apP44YZ>x z)(XcHb#|-R@}>d|0J6gf zLx!vb`=usc9N zd{`BBpEPIObgkg0OGKIZ^3T6b-~Pj2(&6KWad1AJpA9n@wxZKwMqH&5t9#sQ>y8qE zv5T1j7>q82)WLLe?)WgGFvB2b1!Blyg^>^HmXd@qiB(Hw;dN)I_!wE5Qj+4!a3NZy zWU0d(^x4YpER6;|Jzu1*l$>WjJWFRNg##2Db)NYQ$3+l5o5Fwi=|}0efBIwE+1pQj z;TR6P>aYi*a~y^gNoQVZ)E^`!Qo;jw_!!hM*ikkcnl9AoXT#Tq%g9*_yL%6mQOxjd zbXqpJY_s}mTgsKngF;!78`GaZf#BC41|%DyR4J`S-G-tmGccs+UMdvls4)N z#g7$W+`Y|*h>cZI7{K`W3|$AL!Ptcniy0XHFuPv$ag&lf#@ME^!C!@h63quwN*^oA zP!vgmfs>V5oMXl|A;hIVF&wgNnt0GmdII5(&-u~^4x<)Z8}boFxr`6#r4?0g)gl@x z2a2%*V6bPEFr$>RdtfNfEYY2oOJ4XROxyS-8rUAC+wG}L6A^Hks?BO@?=)@r;?V6$ zf0~|Q`1<~dm0!x>bCB$kTga&IC|s0-E%-vB=fTll52!4FwAl^339dD);nxnlL-+9> zE{4A@+&AuJJiwygYvNrSzSgjYcMZr37_K%`wb4jBJBO*=+4VMtpMUXH+S@-&o8_va zlqG}ZRbBbzV4xx7oIJo{*}HJZ?_zvpVu1qk%jG!hH|^&EQDN8WgEO=cro%h#`3b=v zy=fx-B@9~|UhTB8T}kZ9eJt6w*Bwe9V5`At8c3dJ*0#3+l(nzBH z%hP`P?#YXEbk-FQ&__zntE4mr(ai+9k;;y~U_+qvGj<4Bx~jnpVh*AXu~;HR>YFX|z@ffr~E%aDD* z{kmYi;|9q6z|C-T+Pfey-;6)n=S}!Y_a>#ya2xJ5+y|@;Uu*bKA@`AY_lIu|t9rCW zS?nfoPnP4|(w7%8!%6STM}L;%JY9Ud3$S-k#>7jEPpg3U%lR*mYMz;%z`e-B<#NSj z8RP@}B8)grlj9SyNRy3Vj;*xbnMtxoOgfESzxZ}CCOI1SCC~KIpg-^gcP6oO`3y4o zPbaa<6cgt8zVlsY%SEvyoP&(qGhaMCB$p7X3)iswgVniLSBVT@iMEBtpVAx5oC0>CG39~Tt;S&vPG04`0Rn-dy zD}NM4{NzF(DU@(<2`7poWkeO{!!{6aS@Bh)>?+f2^_F;9Eya0gsNmJYIOt{AeE681 zDZYqkw?%kAR-KR7q7WX428>_O<`sqgz7*c$)IFt6RVL9^X_URWzAu4lmNP zA6}#%zkeEA9V*{EptOcHTm`*YZXfR&zzf_5?lr98Zcx9P8{zwabwgjn2LLzs%a(O; zNH)3tRX`ToO66KJ?HoKzt)0EJw|kI2`|QhfaPUYn6I&QoKq5IN@(>#1%$QH5X!q99M=LZ3jWReNAU8_i-oy-a6=NqTwG zOTD3VsBOvV!ix@p?8+ptQ^~fy-Y5+@&(@Q`&_5*T8n1Gf8=2W#3^{vgG|0~)HMgi?oV4X`Z*lSnQS6_ZC`M;cAygc^#WXSpZJFT?etffw4D>c~tLHV)5 z?5scZiZ9AI7*A4vBz=N&jTK%hvnAoC%6%^XiO)Ri51BB?mWac2*6o`vmq)r7d?PQm zO2jaS;fviR(8I#$g`Ohru+my-(2s~yuLgY`(Z?jnljAe*D8Y8}jd~?|M;1Oel_j201+Cn=mwVKW{5hw8Ey}KHCUzv2)wlGRiOYemUF);?oIHz@z?Nk zg}V$}*)X;?fc?CH{)MV>9~NG}T3GJQR>7;pc~h|5undb{iSFAeG-Ty`8C*mrV_erXy*@1SC-Wrx^SiieZW$uv zHdvJ^!`-RhGq}`08CCb0`K#d0RrRy0mJbMi$_7N2M1qP+yP5vsfA&94U;g&D zsnUq^wvbRTX0YuYhZAEE;%{SHiiNPy3B)QQ&Z1%k)W|EjPzYEF<&4z%c-uQJmcc3x zvj9*)YTjalRbNtQ^hz;TfIs|L@kMf0JynDgdRgf;>~(GY8uj}&hV)On>G_iv>GZ`} znhvL?lYZ_RNbB7D=u!ISFMmvrKKe)uxRgS3l=|IMcbq7#C^>Y#Y}be)iNVdFGEh!B zRg5g~g-)A8qpkE3McHD&YqdM6)!7vv%4woB+fw+d^|}pvtp0-E({p`rHsNmw9PpIR zAA=Cvd7z{=6(8l(+Z>{_>ffENGK#aVrm7>=Tbcds*)}lF9Yb+tR;3MyHp zaArcXEeS?7jB7$09~qS!1*amqw@cf~4CR#-TQSpu?*=RK=Vv0<8tLpwq`rYvyQ^{kH@O7FRiXngdtf(qvSP!;P{}`3FQ%mwFD~v2xOFl(TZlD86j_&ry>APnq>F-Zo zrqkX;DvWe0A>Z2GOr2KU*K~ZIULN<-$r)$)a>fP&I^>Fq5)RmW?HkN9&!h zCbXOlwHs`O9`ZP0Ojz^eJcYAeqR&~DTz)CJo^1s`{q(VQw(q|GA$|AV50>9+)lzzV zc#s}G*!RRZ2A|j-aWovKUa#+gsfP~_(x;z1GR_~LzVMk_Y%N$XZKemijr5Vyvb8$~ zD(LQy7}%0NHoZ(^bWX|pYz<#3j8+#Hn_lt78DwWYW{@*jMq1Z^?@ZS0iAT`D_Dk?& zTfAh&7Uv1qsui&ybXJUA7^j<^R%)o6t!6#7r31GboSn={x2{*P)ub1dw!p3Y2JA?I zzN0)<2e1@<(RHq8^c)*K&2iMWTn})5b#IgXmf^1cg3#Mz+zjNuNW(Iq6LPJFRXN{< zaSgvzSR1}RJji{E`!L+a_hb#LVO5X!E+HFM-UYZ$_2(Kb&?27zVHA2B(0A?zMj(Uu zex)oS69L&!l*6IXor0c`W3oRtzNeIcaZyi*XN;Enc!~9 zPuL|41KD8E)t%#C_+DRl;yvS3om|*w+PF@af?X!q55D$FzA7^um0)Z{k!z| ztIyLVhAn2pN$BTehyoR>aMW1{2MQZoW7yy&;UA+{oaHrkd^$c>M0v%Q6d?>=tSoY; zB>&QOIUOAANwKOV&bGq16Dz>Btsrd6UEx_uih3m}AI!#!ec?F=YoPm}duGGe;Ix-s zNSWe{ugL&IiVBs>wFpvr9)9^*`qRJpr_|nUdyBr_>8X@7;ZeCr#8!iYURPy;Mz#># z_KZk?Z2{?YQK(Qz-7AZe7^&bR<=@yUrDm&@+B+)Sb}5a77o%6B)s#|LwGwFqn#$`L zn63-)OO@*V`Q@*k-}$k93C2g1(lQ1ntX%4lz14|mCqMk46D7-^H{rn;#0*X9gu2*d zkVgFD0}&m+I(qUUjq;~%IU@^YoDYDvO*937+5z<}d|tM!vSU00Ft)LJjM&sMM!VUE zR(Wv7n2nq&7sfI2vQbR*ah?EeCyaM0gX)@eK1V=2r2fVz&=|VBqEPKZ?S^M&baH^G zjdn^)HB9-?NeSjK>*J#nwTXe-K?TFt!A|Pz@7VCh*>BIEJWt<$_cWc4*mf~W8XOP6 zhb#LnhOOZhAU7Tum)*d-VB})OWcQ-q+rWL{1_zMwW%xPM4BRK~HTg}O%DKt#zELfu!=0uw*if94^i^`Q4?=?hc=~~vC<1&PHLO-X42%*N!P2ps@_ebrgB}1XH3jvMH;$Nyl+g5 z>ko!rnfCJZ%q!%GYtZd{DjcG--EOMHY|k%UN_@7SBz+Vet=WicV^j61SQXLGsBEQ! zotE^gl)63P?GIAFKa#s|{T9O}6Ev-diEwCQN+c@)d415kXfUB6#p}ccoZ zalI~(_ig!89I*7kQILh zATn;JMc=bq7~!-5RsyB88(QymVaL$%CyyC?yoI zWg@c&F?w~+PE!9&>7)qtrQ94pKS_fVmcot`=Y_3;Eh#de{^rZ{^e$#@ zcG%~9Drlv{9HoAbZ4^f;`=)3pNio}U`6(O9s#n0N1N6WK1PV~LIE>ngQ?s7xjh2mf zD3XnOJyq+qRH;^dVUQU~`ErM?H0QdbfP$Y@Z)}AEEhtmeF^54jBNTpM1S38jIGsD( zp?Wu^plx1a2*Q{Y%YMDhp^akDH%)`04k!CAnoy6B?(-abY3iO~`TxZ-UW zw_ML`TS(c#%Qfw2|1Mxv_U{Vrfn38|(!4f&t>M=W@dC_c=<9UeYR`v(ssH`gTMv8oG$7qXbJ3SD3fS#I757*Acj@Tw|uhU3-t!ipXuCAb4 zOk%~-Q1WPhvXPz~57M*az71bvRy~1J`q`%scO|P&y&~-Ci__E_Fq1j<$N;P}AO}mv zWs7pl@shduhEqkv%0@ct0P;954nsx;_qO43s};w#^NQ<9Zc3l?V6xlZUdNNkHl_Qp z;{!WwrCuAVjB}9nWT5jHi6PtYL)HO=`_8iIjf}51)!1b45!jJs@t2X zS*s{r7>=b$m>LM}_lN1pi{o^B(zSlTBsRUA(gh^*D?O7jV+(olQ>3DcVYnOWLf`Z* z5h@S*LBHEmk~8uhC&oBfO z`vyC1T%^Hhnw~s=nU0Q*%|G~xUPe7wH<3Q(OBAYD)@QQ}li#*{4-T(}+uqG(Jg*Dn zdu!gN^`;o)x}5V}7+(kOD%HEnXAQ3kSzmq=aMKsO4URRu9%Q4zn*iUAbyZ!3RXyIj zgcvJ$by)m1+?96uJMy}DU4_MQht=@f_-Suka<1ZWKKINkv?xmv7a$$wyPjw9EWuzF zTelb|y_5{mPrcr$jbzA9q-O`KY#8(EZpC4jEEW#1k_@?pg&nb206A;wF;B)QNgwxc z#~ofN)0MO>`~9rJE$D-y_~!tNOuNd!8`!zzeH+tn3tI`VhtndrG_o1b5*EGwImsL5TDb3*QTbb&Mr?pKKJsTQ8McrNRS`9u&dU$;tUm zCss#2}kpu?&x{9|9$ znC(cu7(wVDScyZ2fwi4@?2`_S?bc4J);RAf_Pd87cWP2P(9JsSj<>a-bHUiefy-sZ z#eH^sl#Y*HN`W~`gR^ex9-XGs({7sd$6oQp5>`*YTmn|Keg6Az)5Fg`PL*2OMvwtB z_s;0_F!ZRy(;eg7XgCm#3n@kw8(uIF!6?e;y=B!&vNZ-P!d!k`l}bI;+U>Mmt4ayl zPV6mT7N2a;+YZB3qfvJ`y+TSIF=d}jrL3w0WxL0U(lA(JL!!z-b&@~ISxrh|quy|R zbFejrF_dZe#LQ6$BtAwl6kfI@A#Q)z_Y6zU-l{4t2C)&Hxzf`Bn8}HOi*~{pTGSQg zEp5qP<+t&)=)5T_mBnmE+74x8wkmmh8%WjH7F6h;ZCE%vjgN_yKUJ(h4ob)@Qp&;% z4L&mX=hcPa=Yy12mf1^w{-6k_4XvEdrL-uU1dfMNfK~s!UN4;`qb#v=h`(VHV2HQ9+=EHyL*>R1G-j}l% z;+eF(Bd)7iZuF1zpR9mL{dt{@k4m={w?x@Fv@?G zAM!O1bmw^`&7@wxIRpkDFdA00Y)mNwQj{>g@^-4j!ky2ai*$ zwVOIS`)T*^Ak`Wz%N?O)lS;A;9V+Sl3*d^rGk}Qnhw~UeD-c=BgCegA*ZSjM_}iYh z3c|p0DVdgS_fC4l^n>KeSD-BrF1&HNH5QZX*gz3W|~gBJ<08x>9=2e17a-IC6(LtS6mjG70+8 zQS({DOjg7=dD`uY*Qcp3J%LG$oc+7oX{UOFGl(g_GD9buoTsCc)70(u<#CBQEj7ja zj~}XDAMB{kHm#S5fOIOI_{E8I4xhWG`cfNUwHbVae&kckcul2g)oa$bEVEK)lCdOt zxn8clM+>n0ZeD$gx?l9mZS+-uTyM^qyuf`^4Dz`~O>w;~WV|<(CFgN-Udw#DjmK+v zHL$w%hES*tZ-rwGuLrrGy${HG;janc=KXQ>I=oGvb(c)HjQjQC&*kR3;BEU|r#FfM z&nvX)SqwR1p+W&ld*yq}IJ(@#w?AG*ezb2^eX+xqjb6xAtOR4sSI>-dpHDe{B@AJf zm2_v3h<7=gD*T)=X;z(2J+2E5ufk`HSLr-MUzr6tF@`gTSLN|CKMI-9xEArfHJJ17 z6yvV}7MX@XiYgesF%LXUAcfZwckM-^VGR)EyFGIu^ zHU2v5xk%FYoJA+`2) z(nt!^uz0bdz07%A5~gkR(M!y>5|vV=5aN^fo96{*|8?SE>^h%}y$T8c{&3(GM<^Vu zE^0R0HbkIYF@tX^YG#HH<OD(5HPewlvr=Rc;_?rxf1vixZMCQ^ROA5z{#Mxm2!*rgL?49~pxREz2=g1Gk7JKZ2JGL_sZLU}GjC4xKIbf{Bg5U7W^{YNp7_<3tb<%IzuR$K`O6wxlMJkAHubE+%@zgv6L(fFbgU1{Ck()u#vz zn7aVp6O78lVVM6)|DmvW_k#a;fG^`F73IMVT!M^ndE%ZOqOCu3Q2l@$k>2eFK2YDf z2?BTY6GihiI7h{q8HMG5Eib zj<|s1@GJ~U8|9H-pm6%Y&BHuB;552BO%cX3xE;^wBi^h4L;xHX=>s>sD`=Ky5i(21 zZ^Y$i=6#hPq$9nZM&hs>5Mj&w&;!5RfSjJPDXq%}9_~eYgYhkLG|~VOH*gapC&B43 zBP`M_g!w^z2+cDG1Gl~}L{x*GwQ08}s3u(?4^&Wd)B93*5T|%ws8zq?l<|$<7x@LF z4bTH+HpKFd2l_yzL{8zj!8@KKYq=dKV8#!7>RRH5zIO|;?;VQLtziv69mM+)%|71y z=mWTKZdX#R(M%1=ojZF6>G1HeWQM)8yStw{y9bip*n+LB9r$?H<6bmzLlo;OM3!^7Epy5c40>z$rLO?X{WbmW<;GSz>5bF(Pma>_muEI^VNlua zG}7T-C+%Sz!Z)G&_isXV+>{b3mDa91&q=|1w7?ka=gzm#16 z2q3!U&K{_}%aI+pruJ0?}S$`;c(B-7}pv!P60s~*H`Wg<$Va$?$yhzYRpXuQ~F9juHJmVdMTg;pTYq%B6EU^r+*lcs-iGfznmeezYJ)1N}2D29$ z7avPkHeq@I1I^eqAn@#dJM=FBkO5W?9|?t5IT1!W!pYi^i#vY0XmEjtw2p3JH-@2j zF^aU{zMLz&41u{!L|6%6BQWP$q{2Xk-wbiYV8AN$YMva(!wrz*EZ>1e_jRDW3?E`R zK%wb;e3<^>-~QY5=|G4MRsaD1^hrcPR5xFyO0#B#ikB8EHgCMoaw4u@O1+HwWBa?< zCW5Wzq;OqG=_{3O_4aHxy_gh*a11z{&vkry>inAZhK*(@V$lgnajLSqYTKPlqtWn6 zCh%fy=RjyyLvhIRSRF?9=r|ocf0}y7$2NNPm{EB;@)=G(Y&eQJgN^b=`uZRKlz#i? zKc})3p1zb%w!D~*IE0yP@h0Mycv4vZy%h&#kkXhr360ENWOWvP)k@u4eV}tp#jh>V zTWPkvrC!xWv8oiwk`&D?@lOh;+_C*()C&R$GZHZ{jZ{XcrXwZ)iuj0e@lu^#?Ad?r zWGJXX3$0p;tm*`R3{xE3j6n*c*JwPjGQ_M->cJha@G~SEX_Pk!m6!fqK)+eSOMX_E zsZ+VVSH19OBOK8TD zwwQUUKUSVW3rgIk@NuqM-f9v9n$SlX6m}v0_c45(VE9tKN)ZKTqghV77`}Ep-n$>e z=+hscr60e4=7|=b4_XX@8)1+Tb>#j)`C!!MeO>H4G7yD}xX{m~sF9SPc`)sZ zPwvI=P+;)Q=^Q7@<`lw%>s)=0gXNVCT?Xh9#IM?bT}l}v{7z%mLYM9o4U9I3m@v^% zF*WMSu>_B+eth z<9EL=ai`ZOLi|x$h$Kycut>|@G31x!nhW@$D8y4Anq$5XAlEgl;im(CPvSiYIfDWG zYN|ClsZwuCKG;u>AAg*7_6}34bKq?aIg=GxiB&y@0*6z}4|&+H9X?pT{ce#*z7`?B z0{Q-$5Tvh!n+CZlCw)+cEMMIOi*a8Ee(8p;Wq{w5`CN59kiNkRtnYr59x@Cg$#w}@ zd?VGX)zoRT>PdQyFliU zEeM%J_{m2PQ>)$ZmvD%FqAGwT7y&t732XOUi1tx#50cQHBiBK6p11btCF_ZWu_iW|y%kY2t# zF&)$cXNGKTU3!HXM$Da7RXQ#5hw!^rZieM|lcz-p=)?A;4zYWg0liYycze>invkg_FOFCwKyx#2)yTcf2+OnG@R zNWeFt#b|_*5pCcy4SKzFa(ZfotXg4~U2H``m=9F0NkNo?!NO0r1jNsVui?OXd8-V? zoeZSV937{Z&!48#=g(7DID04kG&mdCP( z)wu{ihA%n^whoKVO&10hDP6R?PzGZw5w;-2e1n3766pA99hG`L)tjAE!)RBks5eA$ z+)U+a*$N*sEivABFj5QzCo93+&S<*~VhY%29_5ud+nZ8Ub!W94TNrw~MCC(g3@voH zHmHd|w0jgtwl-vjVZBzjALn9uD@x%hiKbFn3b4{q4mwFz++l#?wZYiM3{wt#%!V`S z2m=&~8}BWv*igW6+bAbGE-$0grH%NbA)>ia7i^=#MV&yiXF)ig@SA^XhkEuFENT}d zM1g0^7W~5KrgUmw&}e>7spL?|sPn0mP!5}B%geLlL7GY-CI3dNoc0cxxxJS-t8Aip z&!0X|PriR?W0@6Vm@af?G#5nUw3O~%OP63#nRJ}|?8E{+<6Q6t1&=v;1Q(IG0V-6{ zv#o$4?iH6{@nHeom2hstJ;Qtx%}bE+T#3Gz39wA_4Y-R`0eX0Qeym{)x!tUSdB|cb zT5N9szE@hA1JwV!pD!@H%KIYk+@`ZUL(Dtd^o{S!RhsU`tsgs;%FhBP&oKjEL@oT( z*QyV8toH<&vNf#XCjx!v*}AzR*`?k}wR$tPJG<$@qsM9Q;8AL|cXUa1lmF&c*@M_2 z#{}@|Fg|Ws*dBVTuDn6f#N$2Vhrs1mjDU!D4HWf;kibM{ih%612=*t!s>Jxe2l(|F zzSx~$BlU)p^!>Br^!<~UsW*_Wqc(y3U6!6wsgxA+GLDwfpTYF7;o;F7V}Ve zesX*qg&)81MGifI{>=FFpTFLWEUuz@&U1xH#$il5P(@7e#6%yqb!LoKa*SjzuN*^` zBV4ixW3*GYVALI1$mf^#CC7MNSMn(Gk8s3UW|B3EejX2!7u{(GH=6;GNJdysx14_w@S!z_%XTSY6{pp|o zF|~F(X@F3#7m72OYBq2ry<8Is_wmB8vI`}HEh%ahg-bEQU~<;)dHcW(j5%TwFDlH( z$b!<;KkM3f!lA$z%-Gt4RbRC#hliJ~Xh0Jyrcl80`Cs5+rRuNee%T@X;b;qQD97>^EjvT&_yRf zM?-beW-xqBq&QN3w)en6nZV6^LPQK?G^LXGP+=7ttH8>vTq~z-6kt}$m9~7&7l%6A zPy}+(l()xX=A{))l?~&T4O%t`2|pc_F8qmy0u6A^6?T|UdxDE4d@TO>Vk4ikC_vMdW)^mRDf;6}utPtDsY!##YE}D$LARU!^S}J(^z6k+IygK?Uw{3D+G#WOdi`|P8|oTKt`EZ( zXG;0}3e`1+t!kN-Tj*OC>9jXaJ3eGcfLLCRy{p9+}FLS zvQMmERZ82b-K?aClF@fNRp|~&Z@M5sePn zZZ@o6^)dKyW|-;$wx9%1gWhdI_|W~>F1{*V03FlkoT2ZkLfL+ZbntX2zVWTJu~6yZ z$47hh^uH zE*%X67(1DC+Ktq%l~b!$N>v-cq+j}#itl&4UHXE{fqsWSe0Ix}pL?qO@CM+)xnj&F z<6ea54R3?x&{cHMbLygC#W+sDZ8U@T_M9XA9LF;4%io5@@SDFIH^VaiMYt`mWmt@R zTRh-R=)6z3jha04coQ&I0=NmhXCUjJ7bo8jyp7?Dwztf)jL*8nuMjBxn{)K%4zF6L z@4D`9=jc_V%>BcvzC8N{rTp@&yZ$j?0n1!*EO|mdLu`=iD*;!(hgEcdR^%Z53m?M&dGQ zXhcqq&-r9@-WL~>f`a!5&Jf-ySD)|1pFGVxg|ce_?8iUEBFH0x;w!*sU0BS~T?wH-CmC3UYb0w+; zNC|uV)hFrm-+hzzA3Tr(DrHCh=VNBz_0zE53!@E&Fa24OC%x`$cj&Dy3PVhEfPQnl zV#-Fm(xzx`_~KynO_WEKt6Z&FY1GT&nUkynqeX$*otqmhTca?uQcAJ%L4iam1u!h( z#?W@5j)xhTD5W+C$&WUPK?x<34iM!IzMgxAz{K=l%HKF>$q=m{sa95cp@Dj$zTi8n zrhM3(Vtg80tc9q%R;g5m4=ixahnGx1UNvYpg^ zD`|JPo!UD)sorR~Q-AU7MSAl6vvfX!{P{Z!8UP=9j^*t~a-7Auz(S8?$j`3=-~tx$ zy(?Iz^IgJy;r4`=d}B^LL+(L+Yx&)Gzlb>yq>F}L>x>t?ow zcM2i9Bj?5Q3?w5VZ)}xnsomMpwU?T#>^gju4j(*B&6ebV=C0(krsXJPy=(-qTv5nn zH#OM&(pctrM}S)5d)!vS>}7?-!a0M&BY2`HyyJ!YeZVh&#TUGU@get5&NtH2m%a4& zr!Uh9yG*Ff0m!NtmoRu){+E2~K|=Mzo`@$m`T%}5KuP9BrbU)7ODB1_-$}p!_KWn% zM~A6y|rj7ALl#Gn%Vm`Z=89Bf@#-9AsBJlIL!e)XC1+VsRp%DlZD+uff@zs2y0zCxX% z3$n^|Bz*mWbR^Xg6G+*v2qPw!bso{wln&f!sLyIu#fy>+Vtmg1T{qz>5%nWlcy`^` zABb}jIgVx8-KQ_W zV)$~{tH3h;MYt`mWmt@RTRh-R==`bRuJ2<0*1hTX^L9?%4)FOVUcL!AuS3gES%YiC z*SiHu|2FOL=MB{9&#zuTls@nZm6>MVAzdsGxdw#gyDr9Aa~}z~-1?t+EreO#(%s*W zB7MA?k`0jS^n7t1TPhOHWE;lhW1N|tw^#{=(JaP}ZTylv!lDosC~yQ26QYoTkRcfp z{vZDP|Ch5UO7;%HSaa#FqPMRL6v7Ha8bsY>z@MoWMcT}OSdAoq=P$SDDyWF0zUSYdt9Xn%KR4laIRrD@^Q6EPGy+%>j^chFu$cJ_ z!ZVj}DbRp#)QKGMa|VU*srG`xdMN?^@z7&m+N#$D2jh%C>_^>f676TZ< zIt?EK3@-^78yKj{mDJMYo;ynX>(I$QGRT7QL8pwHrJBcl(!>9p;7*HaNr^gK$w8`*!nQ3 z(;1mQj9sLio{wFPD7NsNR2aL^xMI7KP`pXwC9aAOPM+ERgw z+C3?9jYgO2AA$sGGoaE>^tAv323fHcEZ{FP72vt(7Kljt%uJ*E^diW)QwZO})4x3X z2`Kt@U6;{8gtq`blPpTHNHfnMiT(p0fI2le-rQj)iHmr6Z|Xym%kJ8n<#m-GK%}?R zKt1s2^O=@t2G4bVL>yCcCqIgELiZc-qsUiR{0JOx?r?b*Bk1uOKLkOcPNX?k{i zrluF?5;J&!e2Pwh;fGxmxO=;JrDmlRaw~=}>36Qg`!bsKg z*k#!_yWf_J0K>2u_{a%C{JjwFd0wsJoRg17DhYC=4_3wVp>0-+_XW$*p841 zd>FmZFIc(7MLv{us&W#>Dl+s*-aB;2My;Z6iM6H6JGh8m^azRvt`qU&O!`89G*KB< zbQNgAgiq;RoXN#RPq=ALU4}wAo(xk%`syFPk-q%dL+N298_!-Ivz_6wdX#BuHOlGZ zhkI#%e=l`M)Aa1<%!W$FL^uib@0C{ zcoRBrf>re2hX1wWbKMY3^}lLKR^c%2d*VOYy$+wD<8>(cDUC!k+2IWUo-9+I@vRMC ztAV!hF5lVr3()<`tk?HlCyV*vzOnDZU*WSj3-R(wvJ8aeadv<9mSV9H>x5sd&v5G7fDX?;%vH3~*KmVWpkCI?g`mc=R8mLo*j>1S) zc+G(@ZoWs{P`koGSdQSb6mB}45NvfXggn1w%EVz8@*~f}pFjQ?6f_D6Qrx5P-~*Lh zCbFQwcmube6-J&6ZY|;lF*Dm(%w>Nr5-2^QuIT~4M~8#vh)~4yUAVI_MD~T#ahG65 z&w@MR2fo6mxaZ%(cQNob+}y9=p4|-D&E4*qV-E4Sh? z57W-xUMiz>svOy1gVO2kIFzqf7O5OguM2B9Gcz&N*jTo$@(MpZfKR+DoEOH*E)GK9 zlww8uM+syLK#Y2gW<%8%{H6}z3uk6wz@psn(Ux}613yvN=!BpTBTz-kE&0Gp+5{`S zsQbK)AS=;aXTn2y2IHam;hB_DL{Zk*&XGdLEKK1N?x-^(gz495{C%OZFVgI|gk`_LMc^y*gR%&Z zV;YZ>>*)r5EYrNq562~ua(f$o@MH3f!RZKF&5wwG6F-*gkhmaK2_xOY9U49)ek_8Y z^fUKf44(%q`Wgr-oHv7FkTI{dV+UP;U5j)s!LrxlbGRv|9fIr=zd09vui!4+i(WHW zNyJTw>Fdw`y`SF?+#n~fVGY+|_KvS;(lgl5cfVAT?A1&Mk3LNwfBtp)^z(1hSKt02 zef{kp)8}7)lRoT<^w zmy6|$mjM4;AoC;oKkX3p1jtUc21L+yL6}einGy@yRq)5$t-w21F7)DMo zW+}kpA3TNz=^vaMg-(KukKt%rxq zP-WW?A4XC~`}&!9@Jh%fGnwzYke_fx8?*Pd_s}?XIkoQDZxNP~T#1*j47q(S1O6G7 z!`<6DSh(zPNqi6Qg-)`#@~$dER>ZvuIlslMR?+pY;eF(BpYXc$uZoY~trveQ{Ph!c z`UdrNCX~bK7{=JbzCR{p$QJ z{ZPxX3f_0UG%xf|L1@AfBW}07{0D%EQbl?F*4$E#NrkNATU8( z#EOBQLevrQ5G;qK8~lotans$giidFd2{&!n`STETI5S|D4vZ1Tz4)J{@dI$hS-czy zk2H}U-1#|T&%?405ceg|4;oZK4CGN!l!rQ#!(4Ltigv(*>zU}Z%G^Gp9hgtXfde#w z$N#vCyXyvCyCH{iVSnL8kk^B+Xz0bu;Y^i}vsdeq$CiZby^kNI!;e0)k;dn9ITRZc zhA+AG5QZ4`dXH`Oq-i(+Lx*R6C?0v)Sfdw*{KCL8P2Fxcot~bh;h;aG5B$)MafB5< zUV16z0K*CjMOg|ZYMfUGDG}+MR@Y=WNWJb!>Yts;&AD8nK?=gfM9Lf*=V!XNvDDWR+a*WfsM`s zWs2}H5QSx(GRF!paHDjJE|t~wD4_mq1e70q^ol#t5Hl^MT+=3$2*Y3)s6@NZT2p%J zL1{4};dUM(*2Xk>m9|uGD97^0k2=FJ1&@JH+SxKh`FW;f$p$@I9`wgy-OQGbEenHZ z!9Vyxi(!iwlx-Rn#wyAeZ3AOsDCAbmrJ$ntWg`@LM7^kh4>99__KK1WZ@It+PdG1u zJbm!I{!pgrDZMp`F6xhc_s0X2a~DnRd&@>I&IiCahce67CL<}mBF%Z__s#D}aq&F6 zXmnTnz#MLo6@K=br}uli@VtEKhyQR>n!@ct7Kas=`000?OJVSVtbLos!=2x8{`4FX zW^~w-u<#~={pL90!tW~G#0lI4`meyv#b1D2j*|Vuy@)r0=6>;ba*{0L9q`3vBgTM=fjB98rX(A;nFis<29 z%@2NFpC1JJR}pw##SeZcqrL5(Uq1(agm8{qH{M66dDNr#U#7};ELEZ0IK-yQi8J$7eN8p;32#*$opzSYYk=}k-=+hmp0D0Nw-qzl=d zNpLZNF7yawZBGUh4oKl#W#^Ah=R7Hk^5K_fUFaKJ0Qw2~81g^oX0cTxyKcm4E(~C7 zLym5+>9e2P?N+Kc>eeN=^IWaR4i2nVV=F+mOZOSWDxZyA^2Zp5tj=Ue3``Sm?~ZNk_+L#V#XE5|r$ZZb8YYcX%N;hA>z#J>T%Q zkF4}MJsqY~@edKARz=SYgB#}?Lnj8uDLM&Ns5S;KnV?szNoP^n=_C5Xv5jezt=*`l z-FDOU>Ds3)xIQmZy;gP}3?`wga5O-i{f0i1Qmaw%`Chx7w)(7gs&h^maq4v&_1Wg} zOzrHr%l1R##E}A1w-ve$?H>PsntKnW18p&@@_qLE}TfUaT{)PKhU>VsFjzysRcfm7at5bn4SI& znN#1&S^dgC%W(@d0nA*Jfs@^^C4$o17XRTD9pjW zrO@agE7HtejnXW=0hFsFj22Ds#8Ue`+Ge-cAL45HbfTqRg85TT!MG(HT zD8Rx4&diiWT&r=*FCKn|@aB}cn6u=5@_(L%MH{n=`gBn7LCSnnHM$KH4D%n#xSnV; z_FY(6GUIiG#NRBfG0*+1)JM8#KMwYDcC)&Qc3P9*{rIy_)8V6s9w-nBlK4WAN!-zo}X4YdURM6@bOcL4==52V9 zFdU_lLZ&=yM3ExH+cadGisR!n=%M^fjQ9LpG;*Qwk#JV%l(wae9e(sEH98%a8G})5 z0m#Mvr{D&MlvxruZGlTZE}#7P!;Mjh{psy4ltJEC%3iLP9 zP+x6rJR&~_sXn$-tx>f?$+nZ{Y z^9o$28CZA*LGgGcrXArk*)a(`?^zzZq@)G(z%wb#?aue=vA{>h_>cuPNb>};lLyQj` zg?rX^z-?c-9bUwtzcU{7AVT6ex2Mc!;|N5iKjZVAIN;?@vF5m=ps~6x zXvR19T%?Tq+_f6iU#|^cYxwzt+J3oOPnCKn?LGJ;eg4I_>9a3?m%jYw59yoV|0R9) z#ncR%iCU~onocj%STZgKpNZ~F z=4#Z#D8+=iv$JkGIXg8D6v_n;S0l5tPo?T2)?nB`Spz4ACn^4 z>4M2@=tR0t&TXt4jU~JbDc@C$eyqS^)f#7d;qFWS!vNUr_I=jaQ0ds_k*yIaW4;() zu|ZMvQx0~VK>uV5#A=O+iPT3N?jAJ|llI_0hOW@P;6c=h^-|RddL{-tbPWuI?WTBe z8QbL3_h7txadhIlG%z(3@kMe7f&r5V!N)=JBk3aOg-jG>;v~k+bI~hr8@l=`Ge$s9 zc2pfJ+k}>OAsRNMLooq!o1IZqm(+p&4ODm0+s(k^2n%rA`;)_LAS>?CFY0+AU6#Sf z$?l?^5QTVLoVj*RJHFUVBUKW{JTX9i8}ie;0i}u~&DZaQnuE$ud4*NDnD80+lnF0g z0nsM$446CTe!o`8ykF$c`vP*jG1sMlMLL&h4cT_-?rY3?E5IV1@0ivr zcy%qqD!*SEP(qjUhU+H2yz2E+f_2fK2`wKYEb?ygS_P}(Enlw!tI~1l3+cc3PV+}x zzTvv#cIx=1M(muT_#@p?d-(7EoBtZa*QOPE5b=?=vW3+OxBiedxD#P9G4c5RM-Xx2 z4us$kX^Ie}3j5iA0gBMqg6r{DV|iV?z`Mcnda#^>`Lyg?=)l*3ctzZWB;gD9=Ym#v z&T&UwV9=m?s2hY{c`?vN7?&#7&aunZY#bb zc{{>hUkcfoXZVpJ1`C9KX298i22LSjyE?X91Sv)zlran?gaLCh?a04_z#+bFUs%2C6xg0|@Tq|C|} zLlksi4BC_uqzBil_iRV`km4hB#zUFd_KOe+Phh*-r1pI8B9qY(wr zg~AF?P{e%bvGQZKA^EeK$_gY(0z4v($^u5(AOJ3mTV9bT8oj-U=!Zub&B)&dIngs! zyot}{V$c>IM|(GJ-T4ooPE~F_voAmCP?S;l;16|9zSNP8X{s;BQOck-*#HVU%7+4M zzKb5*UiGLew=*xhRiTJ4l*S8#$5XZ!K>>@t6GIrZM&oA183P3U)b9?`RLUakfiIOR zvr$>`RktELl~zf+9Q84L!I4N`u&{W#3X9L#y?kE={PP9w<>!2@3eVRn|3$x7Np}~H zoBVEiUcN71tNd?@n=iuim7ka6+~mLL_bTb`!f}(|P0!2sy%@c)s%Ua-5s| zfqY+th3@c;U^$OPcw^i}x|?vX@-y(-=NFuAkVuldFmeS~@=ZT@(P7Y!@QwDL5Gb9$ zx8R^3Asz*xGv@<0>x2jbHweK|#PgML&x3+CxxpI|B5&O4C)FWG9MXf^{a+E68$ZO) zeVhG=u4l^@avQgO6)xJK!B70fJut>S-1!P$^}lPw*BX8X5N&sU7f1%ERO|X?x6faAUw6h>|Z8Q9yPfUxpyf-M!H(!6JP>H!$~9mQ|O--Tyk`-PbEX#(OKgDr0W} z%b3zdx`Xrd{gapJ>Cu@DP$IzcDighsbA6tdI(q)jl z0d#=aStEEw+hEcc+rh_bA&e%hdYVXHmmG|dN6+2~LKkWHsy%!0BK`2=kLmdMC=L43 zxrP&e%E$&;83(ko!l_)Ap5bqjWOs!*Unb`1j=seX9GSmS6#eQSx_owVz3TGtjA6@X zeMzpiaZ0jvJddqs1)j@Pt(0x7<2#0N4xCJSEyJVPEJnK=~>rjfA!gxuovfbW#c3ISlvc1&My-`rHga;sd&tIO3u90XN zr4!M_YBdgtr@c_dp2BRrlg`p*OGb=&gR##Z8^S-)Ozon>F=>xoM7E@3v2AO)Qu8x3 zS5%%FyK;yp+q&2?-bPvLlhh||OLR9gg7u#;|7;t%g1*la1o%_xE;CZYyya|}Ai|k#z zUIU!O?N;~V`l-P*71z%h7U_J~w7O5wJzx2~$&kMrA39Ku+pfFdr{cmYT3_c{!~28# z=C^8eseVHqn;XC8`Qt`2ihJ?r{`czj-~KoM^}pYc;Kg@W(e(i?aKtB6AKg2ESl5fa z+V^#U)XSaGGR)%GaZ`$`{;z`f3S7yAn;w)GvXccz`I}b-;{rE>@Dgt1GNbiup+@nY zj)ARBgdN2)4&sqRflqE%h}<3+14j|5h#hevHV#LfL&P$PP*UXKI7An%UX3TJe9j5w zxspDEQwf#=ujTg+0DLndbG|pgLKKV}TlI4K_{%TSw}1X)`smY7)42+MF8|3zY<-8Z zgqeTLQp>AsJX_H#rea$@3?O_A`%*4Yg6dL?@b{TsrxN_n&Lq@#E%0L;!x)6&E9zv! z+dniL4GGW~f?_*7UO2YHVfM+6W>?Xc;!QlQKE$PT)eXZNYDLY z%w*gWFE|$sKC%jd)o2(CQ9w}e>cWc>#tJWZjDd%Oc{ZZbfCEDrZM`amh%%FYr1D&- zyq>8kK7%`Grw*mG38xK7Dkp|J3~O1bL{XZIhu)?Vez4^U&4+WuXcwe~H^f6hn@-2x zrUj)awnJnU87tJLR{Xt}K73XAArKm3YnEjCoZtDx?Gt`6^O87h>*(_c)HY((m+sWB z`0w+M)A;!jr&p>l?~NaZI#o(;eOiJ#g>#kwZ~^qo~IKjrRQUnA8M4h zae=J(rFGIqxzQG=dHM{Z<-P-cdf?hg`3eB>y9kaie?o8>Kv6_>UU(Gw&2i{%zZ_$Z zBgi#Hazu(59zSz0Xy#Xsv=6WJbdsDR;xFTN--dhUuiusYhflxQ6 za7efWa?JTrz#H)cSfF|4!~HrxE?kEZBT_{CjN9P2fqU+&`;Gj-(}{E^9?`Gz!(RTu zjRR-ST_DGGe(1`H3?wF^bByN&R|eb}NA_R!yecgF$2ak6JYX>_hi6!hzl?VomT?2w zZxPpWoZzuSbEF)@b-;ZVpxc7Gs2f)k>90V>!B0-hk0Z~#)EUXm19vl z7-?}U0;3ViPtW$!a}K{ov#{!Jnu}yXM}83C)OXbPnKusbC1%eT2;U1V5VnRjxCzH= znPG!-ZR)-nt(|oE=%dux*-LwS`)POYFx4Av$&NM2POP8^9RVcBOm-H(=ndeNq>$g3 zYq0E}aa@5LS}d>Ut&RCgp|0YN-kskpE6m|moCQRxSBd#E14v%M;#=XaVix$2^{Mlf zuz=%=PH+p%a1o!jBq!%AegE_{{pY_w^BG^PE~14Y|K@G%wxz!?=uf7WdnaSbyR2Y2 z_c>OLMl-dVt>o?c&Q7f7utNko4|1;c9A#}?Ksp2~sXDEu4KPe*V*;ViFs8h^>eW)( z>(tZ!en;=fZaS5m{{0V6Qm=cOhSHP96Xa`*MzK=_I!dRrn|5~EQd_oCuRpMHft6EZ zmKZ5tbP}JXRnSB}umk;vcFeZ;?EbJ_ij_F%62lROFV3*y46)et0iBRGj$QyS_zbn1 z&D3c(ou)VFNjG6~pL8+h&3DX`^pubF3gy$3zOuj9N;~aFDsA(t&3Yg**Uy{n5j4UK!GxS`qZi|Sn7oVl2=Lro(v~7#Q_#@Mm)uu75l~fla>D6o%iJ0M?Oo*qPLN^Y` z#z?}@?I`bHa+!{MqjX%Hsm7!oc%RQoW9p9o+bS?+yJ+=6*!*9t>$&gJ>1A$k=`-wm%%ZvdO7a@ z;lKJ{Z%9Vm%Gll;KuZkLMAnRTEPj|hGgyG1jWl}BWsA7P(H(}^gAY5t0Fk(dze9L- z+`^x<3_AO%Na;8@fOv>Jc# z%(D_PLiC1xZ#l;v=ENmETS1_(VE{vUKrnT^(x@aLBS2S+S!*a}Rz{QuN@2r>qpG5z zV4X_=VfJ1(4bDze_v9pvx@T#MQX(Pw?D#C5zUWzqzLc;He=?wq?0@z+{qZ0FA=NwW zG#H1m2|?RiBu( ze(C@|q9jsSZz&?YC>1Ep5YMd3f$*d3popSCqjXw16;H~F3q9WILrNg;qxUoG{!z4ZLavvl1dAaYBpPc4H&JRC7;HCGA@L4=vEI=`-x@Z@8@*LDfyg6?9f`_=e zyKIgTeF;D+`^X{I-p&u*pvYN4E&2g{7q93ITcl^%7GX8mL^Lge9n1^0X z5qRc4^XGXeu$X??y%-y~$(WOS#;wDWUV>G zSK?;MZijfg7js_&ddO8CuK+Q8v7W9&POmsPiyQqZYi^#M^wNL+?qzy@Jdj^8xK0G+ zjlqUCh)jzfQN!c04((E8PXd1Z{zxDm=kWdV?vH8v_UJ z9+|z_sHH}uPKf&KvE*?s=?2rW^p1^mAldfOgMH}~73*C15BuHJ>teVWOaJPn)6)~{ zavy#4ar)w`&r++^PNT_1dhzlsy?Akwx{{sw`m^00yF0LY3j+xg;xJ^eQVQBkugYwH z(P`a5mkklLOZk^8+o_><8l3?{1}nedR|^A1v+jC8f50$;E<~A-{n2NT{i~vZ?cy<9 zRHPep8dar}o>^w48mq9xhruA7cBNmkvx5j@vSXhu5eFlmzcn0BtP^p@mvPAuAqd!e$RC-J&aPfR$x6z^C~ zI8<3FJFDTmbBF4PMQj)f%Z*k#8%@$#PwmdKY4k+22;M&%26abIM&hG>F=!5@m-U8I z)m4-``dxHA>IA(|dBY>=WM{p;_!jyead@Y}S5}!zcC*rqu>j?V{#Ud^rs`q@MDO(q zNWKoD2R*i_vUHlYR7J-W4lZbbRt%=(MV)R)0B0Oy+XhzEp)N=@DFWJkK)x3NzGwFu z-Uqnlty%u7fG|$KKDd{0UvoS7{V&|h5Pj8~!`r0}+9*T5-vrTLzFK)-4Z!zyFIc7t zh;jU@v@M3;4Xf$7n#a2;`-cz9yj|2q<`ABI%9rcrF8JU7Z~s^C!0<($uY*DH5iBq! zF;iWo)C&p%1-KLvCe+UIK$^F}Q8;%5Q<~s8zxX+gB9e?J2@%YZv|u2A+EN}2^K5nU zk*5tOh42Gbqu6jtFFz-pNm3Z@7zlJG*Pw_t1L7O9-$F9H{CM4QBjh$P!}}hAEORl$ zR4YmF4ByNj|H2r4@hFTD;FGA0&}~6=G_)}UH!G1a>YzBF zbdd{2Ae0)Er@rEyN$KmMSV$9N=cgABGA_3LT!U zHUi&C8c1;*_Ihb}CIwOgGkKi7l;A8O`+`|@1zUh^3AB&C{5XC2+iz69TIx@Rp3#TU z%xb9Vh?Qc4bgnX7vQN9{w8A7lp(wGZJv>KPkMkqgn>>W}*v^pcNZ8t;q-P1Y?PkspE5u zd$c>1mz8Q5oKP50#Gn-e6=!*2L=+Kf3t{x^N%5wf)GI5|;_VW4jbo}x(T~5?%sc-W;W@@ei?~bWl3gj`UUjjUr;x2owh%$qW^QQ0& zH{rmazTbFO&;cx`gHNiKaL3KC7!QA*Z{kNz_oldM+c+F&Auy*|#=8u}TNTH+SKtM1 z!hK)-u%CYJlOKdbe-uLhddK4X!Xy1c#Nw6mq!VQnH!#LKNnhtzE`pr~IUsr%Jx5fP zUGde2*tfu2pb?OlzeM&5@4%4p6rTEzboMKdgTez9$|KWP6iHDCcfu>M_-I@L;|b># zcZOAIZh}?mfxGYmH{s4{Z^FF_mT?2{XckZ)%6JVcG8hcjhOagJ6d>85(MgTwPHMIH z(&590X@CDgYPNXZNwsD>aYiZ=i9ESSG7VQ&=#U-VaC1A)9qIyHQ~nm>;JTjT^}z32 z0gHKMynGij(2vbQ{g|&e1AiB;cwU^~SCa$Gvg-+moa8 zQm)YnkbSF?_gS5VZi0~oow-`sPMwzY82R({!$@{?(oN5vzf7D})oM0u6pD#= zVNi)deCZZ!KS(;ck*~dzhQF`LMv``?V;zGPN_`9{lFu(CdsoU^sl`^_l5Kt7nDU)6 zIZ-k>Iu-5Z#j~gByYIe}p0br5ee^hWc6KF)m%POu+X7CcLo{2hw6hlmw5eoqj3MX@ ze3PMvEeP3uj}>0fdx?I5(MxhV;k=`~X2|nfQaF$$n9vvD+ulMDIxi&CqhDDEs)jzu ziZtD%A8_`T^u9`&%Cb&|5wTX;@;O?&?S|-9ogAO0C(lpPi&M5Rq`ufqLpqL}7=O?W zCm07HcV+B&XRToXw z^l-109!t-_<{8^hZb}CldfP%)N@4h#NJlyAj?&BHv()Pi+{(QDqv{sJCI-%0HS&g$ z7`!+)&4wSjX=fOdm~aW7;W_#%tFm@GtPI@rN$s_2rJdDlzt-mhiW(Q zkkxk>doJbAB*io7)9?)g65A+x3rOi@olZ+vN4yPVo{FI|i5JrphDPCZTXy>hgQK!@ zp6H7`>0)gA2p#D6fL8&EzZk4250e$y6^3?*?u_1uo=M$!42t%qcH}x$rN*uw)T!F0 z;-Vw70+CGEc_jFwsV0;g7jS=s^}ojwCuHcsI|94cLr zjo*Vp`fw|hfh`0#<3WfQ5)VF+Oi3(I=r<4EWp#`+2q{QcR^UuT5re!Wagb*iT^zUq zim=^L_zReiz|01R9AXH!C6O3@~ z2l#3wIqHQw|0qAN4n;m!T-O1i5yNTc(SG{lKmB9+ltp;Xc7V`8 z7&9i}OI`eGNGW7n2LyMN0S^j^9viQe4rLbQf*FM=+39IF9ltpB)`tL! zReQggcK3Etz14Ib3>9|t;#l#H)5VxJfa#2WP^DJ>ZaFw{7k2}03cBz-yUQ=P-awNB zhyfS7;Wv4Fp2Ri!7ANj37LMOfwGC1V7AK^UUGE z5-tEVK*XE#1IS68U*WgN57L+n9`I4#vn=qj0~+vzA4JKa0VE9{TtL*t95;#NF(XvY zB2mx;bqoB6pxHfsZ{r6K^O#(&85~#Q7WV=cy>rwIe%6ogML=#%e#{9L6XGU~=!vq& zH-(wCrqS=5TD%ateK-yg6a)@FQ0j|lTIPt-MH40h5rbRYH^mQRA-7MW=m!+R>xgCW zGmePh_r>>!gFC|G27lr8r6=_S?l7WKKY@FeM9-9ic)=TmL=^i0mbH8jR}_b^2*=6y zW%it11@1_R|1$2N&T$I}8s=A|4tIv$+VHi8dxPBSGHj%3y_wqWU44gl(%yr|>A}O# zQhVpX1MW4+Pu~7o-&bTm;``O$u71G!4swKFQXsczyskInYyI*<99-aAgyr~m0q@r; z04unH_JEM-Gw`nF9^v&NzOpyvzJ}WXp0BEBk8c;8bu3jEUKq02*6@dCz4YTzFOAM6 zw{BNbtx-=k$^PuZP$}tKELr{d&4AJ4kI^sj$^lD>a(ocbelCEhdPP}H|&u-&ew z#}D??#}9VWgZ-9tG$s^E?+_mb!%^yuSaEgXiH#HKE4rl@M`!6J+y0Hi0La-`@S)YL zrTv{oYB%d{2PQ_emDQ%|Dg$~XhM}=&pr2&oB1S9tx6`7YH&gHQ*f?n`)P=bzzHDt! zC!B|d9zFuC+Nj!ay{>k`R-9n~#Xtw{spPZRHgcpo+f5%m*h>}FG20>bhm&;N9ois# zHc+|5S0-)3UskkHw*c=N+bs5a!_)__aN2043u6`S#r03Qh}Z9nKDOM9cM$_CdM$Ms z2Ig3WXMKY@Rw=yd4*gt7tb2|}%5&s;^|@#YFG+7^RdGXnMaL!{b;F%@%(#Re%#V*A zbke@+w5Cd|mXT25AZtDaw3Tr2uykL;`vSL)HQU$lGl$$$tb)6m?`>)CAE54CzF?H* zYKdM~-VT`4^(r#|uNCf-5Agke_rLjHN=4h;yy4L9_;^#_Uaf=Eb>(3T|N5Dq!XLMV zSbfxac1#4eA_{mUlL&RBWx&>PEV&n9ii1diV&}%;ym3odFdiw9PH&99N4y2MLm&jl zqCW~KUOY#vo1qB1Ey`QKo1qQ*%@h8Ma)mgfJI~@J?wLYCK_!5CV7ze09Tbi!c`oxb z^SZeBD|qcc`xAxq;fBwI`JX(CFk^BYJ--&rMkXSyiFvm zEN!Hk;=}rn)idT4cPzzfIvFbeP&P4cP@io1f#Qk60BtC5C})ntC4czC zbG_bl8U|o3jGGT7r4Qvb+Cj9Bsq#nZ!l*SZj6B)!gi>I-6(6246VWT9s4wVpdw}B` zVRRHfpbeuVGufyU?%?&-hjL^5K>;8hMk#P{o*H@;_~>68--;kgV6ocDb&mo;nWJ8P z(6o7RA>4{`2;Zn64|`o|9*x(x^c<)jQ;(Cu`(!&B3yN7^Fw&P-HL zVmuA}C`8m1Gat{>NcG5;8DlBxQ?)rq5zDK!vK5~SMnmWq?PDoEgZ|Jw*ur=QEy6`T zxUP6FO=IAvu&zJYA3t-q;@b^F_@B9pbj4#1i+7y=;!Ygji63pxZII`JhM+Ctgqu6j zm!6Ao(z3M+43JX+MH#_egfHTD5eoMeT)0>A19#9Jxba#JCk^Z=+{JT_H^ZIXx}&TU zDd&$n>ZZ6H-+^||!c1fFM|csBKipSv5Uxw!Gq?SVG>h?Za~CDT1YP(QG+o0DDrgSB ze0SI~?);1!+@!N#t#WhPV@Z?t|;?c~po?E(%gwLkE4~vvg^XZKIaD|QlC5wA&&boAFLC6? zycRj&r#9v%Xo-H#Aq8#oI2aFwZwVqa?vw+_&s>1|EQ9_>5FgvkiPlDU(;8=`*ZsA^Ka6_$DewINu}11%v6c~KyBGumaEnB zZibu?7{Q4A(q zlO}Yh2PPKnkfH9u@H{3E!4 z^>W(VWeYou4Y5U@^&iQdmg$j$l?QTYmiK)X<+c1&fDHubEQ-fKJvf*M#zZs^@C&^4 zo#HUzkF&OhW6t1>xFfazA5B!U%~WT#S+nVF{@7w~r&Uk;d!6*)a6cXDdhp=DyIVjP z#x7)Oj3Fl{r-@Z&=m@q;sZ8i%yq`XctWkIVaFTniUQN3@E%AkI2`{A+hI~&^nQ+IB z4)q3S7BgXwl}3H*ipo|vVGVi*tGr5Sr&+bphjW;zAN(5P_qOoHq&;+(a~n)NVNiTz zQYB~kR;z43&n`4k2gGBw7RDU5b_Z;16wR!tBR=P}xi!#lsC=xrYSb#qSGu5NQzjK+ z6l{pF5+0e;o7Z|^O{Qf%|YIZv9)K(ZIfbCGEA8ep@lcWZ1H)wu%7^113!i9gwXZk*~oY ztJ$`sH^x?z=;=N$48yA0lUJ6BU+7(R(Oj!=3;~l~C+Sq};^~XibaFNjo0LZ7U?&tC z1#PSvr+$BwUcNl>7N0$}r4eVIDJ@%S+UV(bf-UV}buJ9Xrs=2zPn6y&90S?Ogu~Cr@~UKU+f5?uRPJ zh2n0Nt4bSVBCJ@Xt(dv0586k(v~yVg&aB~nV9n(s(ntm5H+`+xtx{Cj;1x2(|1+n(HTGr-}2DmjSng!*vu?eqvlMD&0L z5&S1N#slJBNIto%Fh0yhh7bXz&nxlF};xR2#55KvW0_W-u6Onj6JOSVx|_tDMk_- zO@!YwzoZ?FFo0MYiP>b#m_vE9K||P3NH`A)MGM0Nh7oWx`wit1%>YZTp7&AeuD5r#c3H&W79=rSdso8G14WN92(}FhJ9x6Snj8HJB zcN7_f<}e;`7al#^UkU|AEgQoy#t8=o8D`j7ITdacXWEyya=-wlGC?;q5yuLz(y|9T zJVg-!%tNJ&0oF^Eja5^5U;9ujtt7xhF3}1uX7OP(Gv9Qf0FLkzey=hU4#L4t7-cJ~ z9IyyJFw4?g2PzB&1VT}&J)=}OtmLCO5Sf8j(EtwWnsy7VHqI$7nz2gf{D_yst&k`j z99BrcC4ZDJ&+HVy3w$Xb@0|IhILyYxpb9_n^Z5X(cLtx#ReBgfC-`pf)~GguYu@(+KJFbB?`b6TPZRpB4^$eRSJ zcd7%J2hSh$V?UhK8;BG^)cVdXmpy0<+zu#sW#Ew;KTcHK`7P2pt*%UScx89s<#A4P z5oR3m!=L|=74%H~hH*(3?*fz)r1as&5qKjHN`{{z+h~fPe&C<>N?BYimId~Q)hZl6r(%3Vuh!AmSk5~P;(_e)j>qIe68V4!0nxe8BfJkz~**pw06_ON1vuozW646_3af$%PhDyH3rX76nEEyAiqm&PFTrA#@qOF*J+W_u1bw$@27u*C!u6N}ql9 zar*5yU!^ZT|J2(rqDwV&$AIH4>!hz?w87xT$~7j8k)F7$*y8M5w%|h#>vWplPOe;* zt|MAmiL~2kq=Vg-<#r}9vdtj|6l#Jq$ViVLx{-Az@gH5K)v7rU!gh2W>@?HiuJkwM z(QHUxv=K`A>MCtx6xpTs*jj}$V5uyySOS~0vZxr{ns6&Z~z>I%K=GX3zw_v!C{`!03Q z&b-zA{@$K=hrz3&ayEod_eNcLx72Q5#b9P-!Hl>|nfQ4V)(MG&N`{Z3=FB2vcU8;Qa1q^{m-BcT>q`kde z8$5Z3sUu}KgRA}g8tx0$TwcS60PA*|0ZzOcH*W4jk&(D=i!+B`b6*^MdbR5=SQW>H zF9{|8l|Rr#@Fm%RyM1UXR1SBN{2VCw@$iNp;+a)Nb`tj<0qo?Bc_;{8 zhK2k^*J^4CU*9N;a1}yX6hl9hk@A59pR-|bg87cPF|9xngQ1Mdwe1IiS6d2pE(7S1%6g)#;` zDyj$RFiE)3;s@IV@JKoZiK_xJj@f@Z4-QjD%1~JX@1)rNF3Kd~9m56Ex1KSY9G{(7 zIE^hVV#XZxh2p|WAKVDFBNQ?TvIvF~3Ad-DlK_k)k3xa5qaj6-1D46htAV8KF_?;i zyjA3m^B z=T%9%d@dDqsywsRkd##p1ZMrh;a9Ks+-Y zDG$aY@FAR229#%vHld`@io=Knz)uteE2C02F%U-WibqQ4d_)8@g>ECDJcIY5L+O}NY6V4Mye}woDAOo+7~aUAEfpyb z{I@~U3YyBUGQ?SFp)A8D3~TVsTcDUfs21=b+AnEn10HWz8u(zvM}OqSKp5w~dCSK_ zA+$l3_~5wQv_j)8Ojz~DId967%u7-XIVc;Y8pCB?HO7I;L$w=qtSUQi3zX^-LGBm) z#M=}u80Y>(`SI?#pCWIUqj1B=BA)v;`l-Tyei@bGkncP`0mkp__yw~g`m&GnBLqLZ z$w{IB8;f9Q`Q#GfN&H+lLg{Cuech-W~tz?0nzzj33_T=0u8 zo&Z9MC`BB@0xqtrxWg|~lI1zE(;mb%N9@Lras>|jC?nt19FEgJj#Ky*7eB-e+<_zG zafIUH2HvQ{z~>ux6M7Z5jdF?++{0b;X+-9cr-JAHRig1^vNn9J;q76woSN-}^zfrE z())qGAAg?q4j!fU&c5WYrerGy=k+%6E#t1%h)iQyKzF|n zJS$9}>3e~AQ{E14qAlZH#P9ce25*;pq`WWA{Bq$+6|4lcH?_I(g{16F$%wR5$@bM+ zQ+iU{t4xsL!GpX@9jM8sYI)m+FAPBR=@_HXg({V8Z(Y}DRBTM(%Ql`Ob4!j@dW=if z;|duaIX2onIsy~pko7U_#A>d1Up7)xI@`g)o>y7X7?6jJPw~-0&ar zLF(ZH=~wdOj3ibiu@!x_q&&xiH0bw@XMeYqc6XafR})dvfy6t`j@sXCr#;;}?YfOW z7@|1$3f+aR^_sPk@Yd7eUNh}?q%$&!O}MKnYe{8fmDHmL`{|*0(rE>q=v$stsCr;q zcElOx>Cs_FbktM5R`x_e^bTqRJ=X>>PYjekqI_X0 z69w6B9lZ{ytBf7CC8?uT`bW*Qg6{ohvdjucQ6Rmd_ZnuBAX|L#`q@msI?{?JgcD<6Y zt$J=sFK#r1OXWa!^tocZ14`p`v|+_zbsiICc`x|haJC-0Ejy#+6@KWKq(RognAyYt zES^$^iOP7U@}Hdb)jw>7A+TIA4rS;xKq&xW zW;f@;GIoqFXF)j>!GtXz^guBgs0NYm`tTDeiZ4$kzK}q{gl05^z^Dfgh84UjC_wIs zEDOIFEi*)nB7}z=65PZOgh%5myk-#`2lEMalhWSfhw0OAf0G`4{%NW=nl_jbg>CQ<`hYO} z#B440;6_kHfJBgHMHU7H_=~beEkideg)n@fFmPZltFbVKU=YIS!S*)$yL(>Ug;K!Q ze<&0vNC=f);bbKH_ewDH5~EsddB_Su z1`)suF6fw_@f7VBBN?-6X@8#m=u)ZOGJ_Q(mw0c38S%&AWS2)}>&h2zf7h#eMnYWtxtpysA$tGB6aR$f2w7r+#4bq91M^f$W73ik!!x zmjJu~Vc>F<0>>h5-?G0hgTr4R_Z7GWcaC}!ZsIy!k?1ylvNp_cfy?HtDDxIdTsdOFWXSQC$0K#^M z5B3^1)UX<mkQGC{UO%0jp832hR%oHKVGLlvUoTQj4$~)ubGbb6P#*>c`}cQR>F{7DRkxIv zbh_c7=d-_B)Fb_l((mrCIzod4v zWusN^>{Q_`=`WSk?RBLKo>^Bw-wHLyTP`$yAPNy`pw1om=$!oG~ z9gN(cb9S6p!l_;Xcx=5=k8D4Qo{SFI>-D6^QLeZUywEQ%6_G6yS*f_GO2G)rsyK8+ zaPWO_f2w~bNupOn#~C}moORuXnMjGjt;`BN)h%&Zp~YEa#1pEtx3`m8YNzO;OqO&y zF%1JZXUOqhL(@=oai+RwYf=0#lVUv*n;w`J)?fzg;JO8(5w1FB|SE^P+y1 zfiu1~%H{GKa0_J1$yWJY2Zo>#U^x_?z3?x1B!Hy)+CnG8Hk1d|&Po!Ei8w@Y94Sxo z@WJx(wOrvD5DDAEb^1aWp<&JaD6A#_Fbul|gV@z!eP$r&Hl%FqfHVbtzlS zLSz;l#+GM4K1u)bAOB!vWgRyImH)g@ct&2;0zC zk%GxK3>@yvYA|MSQYMr=j1Ty6kS}q;i2`tO317o_6jtBgXq*IjwiQi($d1KG3xIcEjvizY_cG-006pCUKe+NF2@I&D4OqYo4(@8- zHl7%Pe(VlxPERB!i?li4>^+C<8#m8J75JM-9`>K(j!3%k>|{6LUWi}ZX1GbC-x>Y# zr_DRmNaS+pnmD3&CsbK~ZGzV{PVGjk7*$c%`Ltja=&`>~@$R8*9mBXUHE;|()` z+*DDFvl29c2^v2ob-1UrW|Ph01$Y$~VN;|TQrGcay!dfkF0P?q&XU1B=^xig1*igC zSJ%Q{Pdld|cqT0FQ=fiKw9pY3y!_N-XCar|u1sLshP02;@XT>!VTd|`_M~8PyEA42 z8D63-kHd^cnV~HYNTv;5q#%s;qoTYGhcE*0qD{r0m$3?5)>TrFW2`C zWmMeCz;}YzaYfy^6t@>pXJrQM7-Yl~h6#)=mrNq#JuA5tBTwh(z%p{Z z(MmgaHqwK;n?93?-8wK<3`BeXu$P`b-%kgJ$2MFrr4-qomFP@n!Nt<9b9|is;UE7w?MpTWVmngF-qJBRTlu3$4^v-dUEf&GlgKX9(cz)b z$U>*U*!1ARL$4@f+egYbRKCCd&9BpMfBRdn%DT6+of^_NS)oRGnIO4+XFKiOy_fb5 zI_dfDuITi=vg@;tAEf(tcWhKRIT@xECKRd(_xASEv**v!p7=xu+1QNq_Z~h~wOd zHtTke#rJ{@R;)Z)rcKm;hNIKeAB?T@p{p>76JyGm+LF~&>&>cHcAcFK)8YO>I@o=o zxKY~jDyFt|RSY%DtFis#IXZN&uRe7oz2qX@yStI@s*W19n#;@iSzkYSY<+HLYa{K5 z4u)9z0ERF65W|Nv+E$fjLpm_4>6qwve$E+Z7?voPBm?n_v6MdK6${XeD5+gtP9NP}PZhNp2IFPX zsV>j^$b{~3N8_ByysA9jfqn<5rg#M8XA`=N>jiHF85CkDZ_Jy|vJVj8`YDz50Y1Qw z5dO4B_RYaLTiV+PuAhg(d!_E-IPSc4emrn{S$^E`dc#+4Yu}I{xJ?>ee*Wckm|Ij0 z>*#n%5@xR|j&OGff(a`4q|S7Rz^FCPwr%of)hlp(FF5ik0V}tR6}`!BBfJk#9?r+* z$YB|#+|i-oNp1-zt}^{_CYM<=6g+|1o^rQ6YFMgWVx3|+$W!Xv{0xd=?Rjm~Q1z5nO->{kqp%X*Pa5!{PyhR5Bs1y=- zK9_*Zj77H3U<*QwG@KW8BB2xG2*M}|lV^WPIAyk=4NwwLTT<@Wf`EEN*hTq-9s(CL7{8b+231Ahtlr7*iA2Tst*Y`hWwC-R?5a77VeMVjX-ld=9W;w&w#I*wMNzN%I6p|W5wBn-oyX8;nf z@=^wrN9vEVumTGOk#J_hof4)yf_p`DFw7vp4=^k$P1z<99!FAWm~n^V)lm7Ng#u38 z@uy!;1%JJM&)c1#450ils}tiKV=4ByA6rnr z;Lt4f8EsP>NzV^*UkrqTn`sZPe1{)_ST+ zaYrG=(8X+3R)?MQ#p8nh=7x5D)Rzl8@#rV>QoMkZOcNMzQeL}B#$6YE1Gk?QAWUe0 zc-$5`P=*YZDSCv~yWX0>I&!Ms@=@CvnXl?ggp9BqHDSt6Q|A zIHXOk#R~9na~z17H>a6NpA!&wEv-ECiTsu~l=Q%Cx^ll!eUm&U?r=`P__N{JAEd=M z4lW}^D4t0@I$S??>nEo#{VYHMGq|pgYw2*$;s{>lz71}~TU@Y%hz#N_kY>~~u|9m(ML6t73 zagqlh_u_sTUKRdb;cdGV`Mzu3uLjBwyt>@P-_HB{F|7?rLSx|t)Ov~;VD2Qir8nSM; z)3w29JnSp&Kr(ky+J)3o+J_Gwr0vZu>068GL^3HWNDhuVX?H))Lc*9}iL?)E+ z5q>1u9o-4po*f!kNrQpF+r+V5ocLka3+jh0=rHQUHr{NV{gfBoI>f1mab4pjEf(qH}Z7vjH`P%}=1KOSG$D1`Bg-6%Z4Qum(v(~4+5xVN3| z-r4ZkWayME68^>v-sV^_8Xc`KOQc{N3^d zMfAR&`p#juYkeJKVnc0C&-W(?#iL_UPqaNcFUHl1`p5E$(yP3zY&(_S1J4*l=h(Vl z&u>=Sv4tY~)`G&29C*I7f(=6{1}hs-#V4z}PNhqA)u%fBv1xMl82yuWvLQ*&KzKr( zV{fHt?ZR`QU0Y2Lw_B-MSx$pqPh0e+P5r$4gG0KHjK!e1V|Av1$J#lKyC zp8YcL#}84iKP{LTzGxu7!gAYL2InQFKVEvw^x(sUUx0q`3479}2nI6^Y&?k@7T9N? z^b26tZI}k&0%oHf`%;>h!Ah#`nZR{p zGpBQwhRI4a0(1Br6>1?U;tUir`w=vRDzCBao*go9L<|@1n{lMc1mdo|Vk@VdVm47E zFq%OqU=~Maa=ev;47hli+hT9GezLIw92H2RnCUCRWM;>y;85Holiba z4}bD`YHzQnB`GQ#IE%38Lx3e%A`l{o(=QNUF;Izd3#f#%7diqpGq?QVO>{3VMZ>f6 zSaBpF7lmZVDxeE?eP>!iXdQ8kPz4Vq77{geBhoOpXC#2$7frht%6k>1Tpt>atqZ#!De<%_d zzt|>|Z9A9=+U*=gJ*l4Q>PaiNrk@ik`md9{!F z2=&M~#8AhKShmx|`b+$&6snjZ*-L|t>OsmCj|aB8Xs%b&#@0q^ueEJx#VFQSf5Gr| zIyg)7Qr`RwkKrP4Pjx*-Q2tfG1O-q)Od@czMNmP=iKjHc30yxg^4Px>$Vf0t+t~c% zd`z40e8&+jtLxinD}I6k4etDy4wrs#=fLnrBq4yKX^&a>F7=^%343jQ5HSfV&ph%E zSA>ERNJVMH$9UjA>%R6IPTx#J31en>hQcei>;`ZGg@+O~gAzOxL_+1hM*9^INoFZe zX&NA<;D`^*NuLe$367Bz;hTS_2qo<_>;~khLZ;k{$L{>BFG8L31SXXgEj5$cFhSGb zB&I}9lTO2+??n31|ExFvOaNabgEsj`$fQ1I0I!2H|9Gy^R{2UB8qd^n8|H945jP7n z<#LLf@d{M{v?DHJUnv}y`sDT|Kpwg|HS&rwot@~!hd$zt`@J`%{4Vf{LVkev4W*H9 zYk=qvU@)i&V0*$P$u}$M(Z`>qyZ0WZYO|fTwzpHG)z*8NGlWM`{nG998@K*d=`Ey+Oc*am)^U*k|_wc1@T|Cuf(^dtxg?w#qx|^iofWGK=RIjmv1(WhF{Xrfh75Tywx{oKLsfh63tTT~o(}odn_%J^lF%fajD_xi< zW?pq~N*8FV+?C3TWp4Dl6K@mFcH;A?(L{Ei6QBF(@NiFZ^I57W-JR_X)tSb-
    D7 z-QD#nD~uoLDXj3~{G}Du5k@^SM6areH}d`FtKZuow!X2EYK^APNn4ga#e_+=zF%Ir zOjV`FpmuPuZ+*g(DfMm=J88XDPal2uX=-oYO|7*x<;7~LOVyp)RPQn-0CsxpI&zg- z(q$LsF4B0=NxM(K(Y@zMk$ia>sJyjC+XnlkmAbVhbc(9#oAyP=rF@98^(yCLNk>u{ zS&_H5ci>5z82*@0*^_>Q9{BLl!}M3b{0pzD8;zqrV|zQ!kUCd6#;GTr2?Ni`3HldX z;$uWz^$I|??xXHcMtyHL$>hx^PoAb1tYCZbEL|#(&GohP;K9ArYPVFrT3TOg#tJ*- z)9sJc<^vmTS*6z$ZFFJU7~rI5%7bo3|HNR+xWf44-8b~SXG_81=tOaM?U*DA9&Jc| z^aH*pD2WZ4Y;Aa`dOGZmQh&(g*}z-hX!{$)p~l|PvGiNUr1GQ>V_rK~T|lN*SxtA= z*Cj(~OlmxGR7Du##_4Q4@VRPr;XK@GroaB#qx8wW&9rc(F*fL@7rO`P>5F|E1bM$Q z9??-eh%@lU_0vv4zT=c*iZOM4fGMaIrWN)9KERI<{`5!o`~|Q2EuE17Ks2F3IiQ{8+sPj~J*ZFZJMA zbm9vmEl#O{Qs2Hofr@e%BpZ$eVNeTq{GaC=%4y(D? zl8_ZlJQLt49{6l|qVlTAsAt9|v)<0w{zQKm4cQX#O7+c3D;vrviwce*Nj2@VVJza~ zCuLw|8AdMnp^U6@!+^x9w?!!&prbj)23s0ntXC0v$+sYe13JhUB>kFk(c+B)OO_!HvlHxPI4IBF7!vKm7hD{VH z%0}MjQofE3kJ8azH=PbI!tf1eExM1VG+xZyfc{LG9nQMx%rp(IyL!?7wC5QKj-Y9z`aI$ za>prmcH$r=Ttun-a)6S#jikhy_!MI03dnR#-Fc*#VeoXv>%{L+ANJ|bLHZGWmtf02urhj)VgLB|4`Ln87u2_LCQMhjxVNDg-l3c`Oki%k6p#8bJ8;r#Sa}gF;I(Ad_*B-0r8D zMvfv-cfEabI-aD^4Q~$2*iP;+`HMTqU4zMF8hCd9$msl1_#EwGWt<6QC&v7eY69R1 zKj`UK1WG@3!e9`h`JVm0MOcgxJ7*xr8FBi{-F=cs{TNF>Wnv8e5?4Gf?W9aOt@tt3 zg2#_KfDK=`Jx&AL(fU2=cEb6?fZ6;2KRlF1zP$kyi=j&|%LU0i4?q4aJ$(4F)U#FuInAT>d7d`8|7RsPux*jznjaLxCRkM{Hx(zx?jojZMqftzDwS(hf*J}E<5qJ z^ZkA~`y&Tc$?bjV+aPMqDfL{WUvloxad&7V79rc4>*d+k7>!Q6iV0&06R_CUZB6NY@{rmVvCSL2hSN7`l&j z2+99U#%oJ|dwBnzSFfPIaL$*vZBxO=lDm=H(Iwd7U{ht^-r7i<3+739lAkfg;D$bO z^Wo8vWpcLFtFJ72b<%_TcfGwKWiOK%k>8gX`zg`G|}J%9GhTlZn4=^Y<= z)z_N%L+8O*xVX6NE%97`(#P1Uek9$Di5Qey45a0SIq4q@sZm|A5$|Xa=P%#c+O(17 zxHnFtb9AB0yxQ$l`rusJY}eEFS}j%hz;VH@7(AQiRVOED#3ab&YGO(sE3gLAQOK{N zwzZC{dcr`|sIq#MzQeY7r`BW9FS#(@!0)+qC3GHE!*TX9{YEN@%g8g)hA!!arwSYl zr2~)A+1NW12}*4*9Y+OrU0$7^nC}hM851AR6?Qi2r%RQ|?NG0&{@PxpM7?9kJv{ED zp2{@0ARUxdTB@5WI*xevmiFrZ=uFFtOqRT|9(8s(m-hA#)US`dI&oS38pA354L;}9 zE|dcv7L*tD(d$cZ#xR9WCe~S5hdi;p-tu{A#SqNyD~ubdP}Wa9j^suUwDC&)V|}fW znvJT)-CXMShN;VzkgAfA`uA9MOh0APC0j~Xs}Aq>&u->iyL)%H)o;gY zmlO5NR_Meh>?FhS0cyY6s@h}`;n4k?wiu2tQfJ8IS@dsq3z1H(#|3dc_but@S+7Mu z9%-Dh%_4d=`tyo-Szp^oE2>`%d#u(hlSMJ`tt?6#KkcVSTaENrzxXtLbbr%^V|G|! zT+`p_2N*+#(x(UN_pF+up7@%=_X2;Li$|CFn8Lr>H^FPcqP^@q-a zmXz?92k-RT$Q1u}`FZ*!;>Q5rRi1slp7dt$b~5yL2Mk{e5`O*`rhVy&>_a_EA-K<$ z2RA`E-oLZ)uZ0_k-yt3Oc!rM{L&$Z$4&%-?5Fyk>@XRZBmbTqF4#WaDbDUp9az|{& znfQU=BkCyla9t@S_fVqcR~#!*hzWi&-x6#w-jV+#y}eP_!m_Y4p-b7EAEXGUtj-{C zdHs|U$Y)=D3~1i252KIVY{|gPH~69`D03KnSm{N(dPSVlGs_J+ z%%TIArenPuZd!snc<{;=A+!@=%t*uV7{;P_fMK9Q(WTw|5mR9c$_wKf3J!`7hBK5y zn4%o4{Gx7n7Ev|~X8`-ugGV}M>ybYVOlimyqvfKMACzzmmKY1YHKKT=tnfs;U^v2f z7UK%u!x+UZSeIAI05ss0K1V*(7w3_cnX9xnN;yVDfWC)Oi@sU*)1 z?QhL9aTB~r+8Bdzg&zm?1VW6>g2%n!Mm(L8tb(2quHi*|2@BeBL3<`|Nbxs`kBb|$ z;UmKEMmqadK$X(|91WG=TW$y9CZ2Y(H~i&3q2=2QPuY*-)%B5S(%1y#cp+wY#!);vZ*lECvI|Q5_Ck;V;lz2A`01t%A>7U?U;E=e*?0VgB)bf`c2LjWfOU6Lh)EqcP$Sd{Fpv-NwKGOB6}q_-K!4mq}g@Cpf~5 zchF!=HvR*yt z{KzXVM!=MZ*Inh={I>A6=}Z3a2c~6zb9ld;{b3>GR~)an-T*91Q_p(PBJ=V&gx4qc zb2&Jh=%_bLhdt>B{c$=x>ZQZup757aoAa`&tFCB1=pP+-)84^RIvI`BzcBzn^U4#k zV60KAcsn^(qm1*%Yjh0s1I`}8P=%jKaJ;M7`2d{*d_Hmy2BUPae_;8S?ZmAwD06ft zzsr=@m1N(T^rjevvqJ>(`nh;OR<<6ZJlGM#^00LewtTOq2IohKzZ%;NvITryZe6P@ zaefj8v?J+A$86aqev$R5vyt=!R!#M~Oi<*!GA67oTQB3>CyUX#_k}YY4!p%7XDY!X z#vF9FTCE|OUGg;Lk$%MaS(J%g9af}6vekNpRW{;pX>ragh5EWU1Bq?&PA{dyEG$b- zUlrf1%xWrMwX0~=)lRH#tFFYEOBh*bU(V-(4#oo}O=2Wu%ep1i{m%Ag+PSl7W7zTG zq4ffG7r}_hg<+-HtVMgSE~$gkkj`HFI~Xown9$X`@kbSw{Vi>U)@4;$vg2?KWcK zAuGY~d$rxhdRkkLe#-WQ-i^a!WZwO(#spFIflED)(LK?bI1dg38NvrT-HG&X>Zvz8 zO)rkR>FXB`7WtUe#6gwZ*H{Zmgs` z8_m>&chyr(b;j9O^lh~4CFNC7Kji$fRaSPvCu2~ZXUqz{GmK5rh2dQF$abC>_-N0K zwMJS~->p`dNP1~QBRc!&^ipGYke=@!r)PUdaUTcJnTesSCZl~$)GtrQXYTjM$Nl7Uzj%%)&Za1phjZXCI`VwM zm`$G}+`FO7U8Z%l%iX&>X-)kTgLGGY<#;gmN;Xy$awgizDMsfdm9eEV*7VG&r>)JV z`T-Mm#jENJLm#`vcuZ@Y@K)8pbp73Y3zX;G2l&%{KYoBW2kT%Szq-EXo^g%#_j&!R z>cQWwtfg*d;if+zo{m2jxUF2X@NMybjPPIn^Z)vv7M7M4|JGeu%=39+T7>Ujm{RyK zNTE`OfkOWgMo97VW8pY*KuC@OiYOg)jG`Zep$N;kIX+y|--*jH-F_$xbcI1iW2z+FToE)xtEJP zpg9ej<=Z?u2{;Z4+BkBY@u49F27|>Mh5!j#bqUy;+uNxn0h=%kF08Uba7KAyuWrs< zLg`{}cMMRXWJL_6iES+~NMb~weNht4p9DA*ID}1b0q}WVk)By{2;3-u>>pp18@>?t z;1wec3J�{;V2`1B2u2r=}FGt+fq*a2XDI=|oCppSzS#A8&`kD#e4Dgx$`u&zu^L z2I=(tM7c|}l>o_kRPf366aWG*!mSNaQgl#gF(RVau_Xp~w2n9fjWWW^l4t%gYYRRV zY~eMw?32(hekijQ7MjB4N4&?#MDxg}FlK8Og_kl@XM};xYBBl=^^btfxZuMRkA8&k zFhXHu60Y*0tvDlqnVVLURbPc~w(p>PtII3y8?-mZPMDzHp~Z|hDgt8{3Icw3CSMFz z2;aO0-V*h%8EV_pnQ~tGP}I0AM#|i7h#kQMFw2_HlC?Z zP{%g1Da?`ZsxmOv+&4ux#+(!sDZfMY1<$5qIw6(hJk(Yz>eEuzP%xlLT8v)fp_Cf5 zl+qpmcODeiym;un5ipB7i-*T;tt)QfnBqsM1MCbpPJno$sL_q9e^`k?{5cF1`zJwx zpM!IN9XT}c93FX{=m_Xqe&Zye9iJmoy21){MYbH zfSqv<>bmE=ohKo38ztu-{qJr8F;wy%I*GG(h#ScY0u;pQMyWG!OQQ*l9$~?;LNmzV#XffHv* zuiUe{)M@0QaQR(x8Lz~b@fPWbn&mBrgUf~6EHK`6!>50{BeAcNF5D3pVTJb8uUmG< zJ!r!z`2=lcPNc8E)tx`WgkWskdPoq4Gp>v~@q?b*2REd3FZtM+{ec?+5%w~jDC6}o zgZ;wKe-3gHqFmEUf5wY+lRBPB%ilDGI)-l0(T}f585KJ^8GkT*{Ye9@4Df&u=vlY4 zR7uN~M!Nse=joUK_J2vg_~pM(pZ(+)>EXwpr|mlrQnkLO_hmJ4e%GAd*_IjIPeqIF zB}L5UnEw) zumX#%0%NknuxGvN1z4EP9d8_o~-*HEh^I|L}I;=ord})iW4oVr7_QYUu;9 zEqPpC<)uZ37PukJ9tqUGY1g+Ux7m4fKpryJ0lK z5XXu&jBixfigZF~SE{StzOE{{opNh-3Lr>tn>U5ai>+rj_Q(UIEyAdPy*Y5wXgEsF$aLM_g*nvPX+^Qp43=yu=P z-bm}Mri!d~Qu!_~RDMq+i2m)#g{l$Sk?r^nj#Q7wUFlpRsyaqxLg%8A(QRW$Tv``q zhZGEbtma}{!4n}bs?OKcF6*0XX=80o?IS%~d?O9C8yFauQ?GO6)n=6?>653!R8;}i z8dVzx8DrKvX;fWo`-r|r-fV$s{a5sCkW_z!Kl%e_+3oHgc=ZleJu#@Y+j?)Q%~*BDicPj^WHnc1#U9|<_=%}o~ zWBe*ls)z3m`}=#=Z8;0CMn9%MH|mMA?Ksc8qJBi1=z%5uRCS_yq5rd*5gN{rfo&%} z;R664YT^R`=s)ihK8(5V1Ky+#ujAfc|M5Khu>)n};#+6&e_v2&zv_Bd!0WDysk#p9Up&mv|l!^C?dJcF}Q6asw#o*lXF zZOGv7dU7WaD8OOYA`Le~tTIdsAPBc1aFrIUF?P5uns1K)hwnDd9=e1cwm$(@r8Oa#@$Q4^l6+iA=Vg(dqlKoUF4heb75_sEpw$r^&KT4bTchZF!04 z{z16(N-ha;<`n@~LLR~{)Y)2qZ9Xt`Fr$!FJLG{uLo%zvxx#0!cWE8b8n zDI2TCC^rHw1{@58t`oHkXM6d~3xs7pqKn6}y30lyW@n;U1t+RUR(44V5}w0F-yf4z zb`;NZ@!)nN45dVU10KL7t+yByuhc)Y1W`0DCA71W%Ze`bEMeQL#>h{6aCQJ~N}ph> zhjHF+0p)K=Wum=?CqwadCZ)0}MWNyP;M_E}+3WPDXM9OfU6kThZLLb#TTiX^HI=!hK7Ex&Qr7!Yj!yb&^Rt`JtAOj? zXu%ls`g7#9WLpJC%TwXq*9@;C+IIld(JbHW~LI(PzKKR$a3e@^GP;&!^gEp9(Y z6yTRzX2SjnZCw+FA`!nO2oHY7OW;r8x(}@AvuYBf!_kx9A?i|l^)=sC3GG#72=1MBdAA#n(@wo$p(GISca2J@Q z&vEo)2k43^0^tr&92wx^2I{2#bU7-Qy#!CW2yX`C@XK?r}4txhFC>#+p zLC=u!a|AxGl65HlT#qGDuDggS^_c5VKaSIn!yV?|9N<`oml}`Y2rsl9;~=-3yQrUr zGo;uavf!GQXxpzJvc!E2azNno{15+>N`b3%aC9^q@V?T0 z4?a$xe)eany}p?$m3pcme<^NmfseZJVKJTq<1A#v+7kFoS#&y*3y~eZnpcIJ3mbi?rnNoM4p|{V71Kt{y{qKbiIlN zLl_1oR&g<2*ogw84+b^1He6bo7ftcQO04Q?YS&g0t6^CA#CB)@@|)kJPPdc(?ce-$ z`sq*q47Etx6kM?ZAhw%;ho5_X9!Wio?AXxW6#?~Kl zH5YX*QCpyAf&Az-u_c~#Iq6s!dg5JD-f|egF08+?EuObRS3c-x7zofMki`)R+N#51 z;9_!MY)>!UL{wNMM?UC(7y+R-9`)1C_Imp4laKtoxs)!m-l{pjZ=UYMb!xGCO?nCE zRdL?d;{2tzQRFk-@)4E7s zvi?8((?6%LA3sh{p6{ly>hs_KhyR%V`mcVezR+~L4#f*+RZ#=b@&vtebQkGK(mn5N zujxT|o(>K;lWob{Th?nBJ6PSr+0dsx7w*g7{a$FN(ow7FC!c?A-Ee<@UpncMw}GVG z-Ci$!`S^+G%-aakRewO|ZAdT1Ac_3LQ35N%g%0PQvE|@Mddg96oO#;e z-9}Ulq@1_cSKf;Y>?opVg6fYmx;oMk8AIru7|)gz=dJb`Cs(n}{!o3OId|r zj{3l_zury1eY~HJ`qHsg{`+?}(#jHNxW)O^7)?nZ6Jb9<0YCY_zgNi*2Jd31p})UN znZGq}$dkt(8N5rK-7J%3(i`Mv>-C-TdPDfO_AK9R`F{7~gu?gDIwky7WkP?*PQg@% zn1#?aer#}aY?ZQ=@Y~D!e&8lAZwfx+t6Hs2sbt>$VAjj^J45c|T$67`H$mYDsAl?R zCEc1P0^`GS25@d94d9cC{xtB7l4-?<*XWETSs?+R4pV?X$Oz&r4Lc|C!ET99;k|4Njp%+1vJWG3!9^tz$ z0d&lM*iul~H=HxBI2@W;Q*0+_Ly81Y6tZ~0lc$sp;bBzadkP;_Fd(t@0Ne1f4Psr2 z&5LKx)8nrnOA*;iyWf1BdRC0YzXbM0W^IZu`eV#`lMt`4H7T^KQex2B$Szi&t=O<~ zAwid|{@{f?5aP{?giagpBrqemQ|2(ro!Vfxyuh}Q2<;dQ*$R;vZ`7pfLHQ7dvPi%3 z79*+$W{VMrvOsNr>rVPOkOW)@y~k8(I2pA0>F4|>dw<72?dXel|aoVg+U$a@yts}+n<5_go#tVSA#$*o&_;Knh*bR6JuNZpkbavLWQ?Y<8;A-GxyAq_m*AHdm`#Q7cI z0R4kw3Yqo{K0vrJ@R&Jj1}rZ?kP$kJmbzZXY?u3sn5#I6*#~Y?`0@B zZws%Z{W>W5zH9z(2jyw;Du|kY9lUM1-xc1CukXX~7071GQj%cl zkMbkQ&}=()BAJj0UTmEfM z&T7k?Ked;B^}EMuYx_?6%fI-!w}!j8IMaKQ-6WV4$@cAP%M*ASr&XyTC*y(ZvC(X$ zRp}>8M8psS{L?@FWBRZE`+rT39^Fryn;RNl6^sr1Ib|DV57S%zt?)kr&c z@22+pR;o6n8`PVgt+*h{C@ZOH!!IX_{CO5Y>(wg*-rur;Kp@UA>#!~!#9;gk`i8+>Qq&tw^#_d)6%C^x=j5Hy52b5iobu`_wV4fP;+d@#Tk0Da zwpdZf_MGaK)~ngNbgZxuMm@DTV-4kQVPzHaHd4`7sXxYmC%q~!bicavd$uoS0xiZW z`q7#2d1awzah?}-&sfB;b=)7M{lkv?EMI#t0Me)VHW2za=alt40h85;+p4>rtxfMz z!-~Xnm1}#enI7F+lYXtSC%#xsMtv?SpN8swz0J5>PA`sz={JuL(sT7E#{62VEfs!Gu79;f|-L+jE^GNzs50x10~L}&@WJ@z`zj}aJGe+c$1)0FD_fx$A?JCyld zj5_a{_q)Km@cqXO-&Uu5e>TpK77Fh-+mG;9m5VZGr(mi>%mNbFj}KnembaJj{ldHU zD;vJ*_4+MTis6JP3YJmy0=J7FzJ3UY*lFSAhbbo^eV~>PseHh2bbMn3+YVywamH&ks7zfM3a-<>6niTK{YV%&kSeE>cgizf6E;@)$V?nG2y>Y- z@+1vGs+erD5kMX6NE1H&1tW$C&yE6xAb~2N4LZOiJcA3L6HeL~2*kqkO)%Ed66vDR??;f{yPuvr3SMbB_LAQd}3zC zBs0t~L}5(ftSgiqgih*%m0{-+=Aeu)hGN9ZDOM{nLyDC?Y`xc$aL87J%qBx&Ve33T zpkjEkLbk+NUdt8$sY;AO(8us*Lz#qPpHC&F%3E_RE}1^UJLg`pr9@B4Dyx!y_b7+Y$Vdo{yW9-5+w>ERPgbWGCEutpeRu17~Bx*5zu+QuqEMDo(;B$aY%fCkAjcF!rBwI$UwuPq zhE*QtuRqhhh(nw!YHMcCLIXvYd}&{{i=Z!HxMZAJ8CE}`Ebxor?Seytp{vVh6EG7` zX=pQ)8)nRffmC%SzULCgKI$XdooxuICyak=dk7D-4gG;UDFd`QXANcOOo|Z)ji2f| z8=w2bz@R5(xHn3t1B|9BtFl{=^02J_-d=BbhHpg*&WdQ9jm}cP(-*Gln>M_{#1>=7 zqeglA=HCET=H%F@N?;a&KsqxZTp}k%FhOw{MIMLxM|4SwGca5bqJ ztn@;1(gMcMKsfa1Izi|bFy+a;xXN$TQ326{o}E+7fI^=zxy2OilDoo`#~f`hG>CUW z3E)PZ=0v{d1O-75WzK08T(Ao&`P$)EkUZ0*GZ3j5M>&BZat}Z5*~GYJYpA$Nc(mqq zh+HzBpLYeDfN&e~t%SIqXZV`N6jzDM2@MhB^pkktb?E{#xSz!gn5~b9&6LZJJC_S) zf2lKb0so}~6mU9)IZaM=vv0aT2+0xcuU zA92&rX{jQF)Vl{C3}1iTFm2CSn6~2#%tv5Hl6RQd z?yutR%hP6`?I*yrtB0d_Cq0UH_{+J!26&g>hF>U8^L{fZG~a}mS@^bm-;A%>GS2E5 zHz8sei?8B4r@i?+nSj#e=gAKX;>X#(j<0;r@aBdt2tY^Ir2OTc>8t-ydy7k}X?trc zZ8TSXX3&XbV?L0xrQ4ZMnLmcS%yaqlBBid+;6WCa46ny0D`PPHFnP^8CoBkW6suoY zt+lZM6C237q~V+;=`od6$@p=;EJhE`m}OEK6TtYWkMZa3c02vzryr+# z+v}po)_5tg69yBv&~I3Qa(FyQyGO&c@9o)=4F=1VifOUZi&ZB+J4^C0hALJtaSs_; z39{UcOwMFJWN!S({umtQ6`!>(j&R^(s^V|5beChD7qezoe-i!MZe(FPg}SDf**cM#__HI?r0#pCq!$zwh1w$kSI z9UBZ)P(SM)fAv-RFaO{FoL=lcOAjACv_ACY@e{8!`d|Lze@JUUYPP`!=Rzs{t4wNz(S)hnx- zSV7lT-`NlidMSFadZGJmt=UqS*0b|UdXMxM@?!NBTd|`La*oTMGPgRW6uP~4u9S>Cx2dc+qpMAEB zrAxqhYpkf7OVY)ZKNCv_qft5;45S~;dmBhpWQ?4wSo=T!?tiBL{lES9^hC5i`uxw* z-~79OuRhRJeoV5crYpVyh%S6`v0W}J_f}~?^;_DORhRpRJ+G?bU4+ibw}VBs|HUcB z(M$8u(zPo6mkE($)qi(*miDFRA0BsXw57hGy=gk5JWFnjD=NH1M) zVw`H&AV@!;k9q~A?p~>$Bt}W`x5V>9Ecq<*ZZ}hKj+bD;yQEV}h+CB)z5U>R+IjFG)z(`{I!l_fM8&Ej3|p-J5#DlaD}XTqVGP3u z2BK(>P;}U*8)F1Bra3(q!oNois~b+)arF-c(@L_HSWZl{<2>F@tO{pKJ4A@%qA@m!=XsAtjk9{E)% zS!|)vYNhQv+o`$UHV$W-g@KIKMp9H&W8}xh2cBZsVI>l^;~9<$r#?@mX`L#5iR~0B zQWC@)S)ZuxP>4_nn01MfD2z-3wH*pH2E(#VAj%`F-ip!)EX_;F6>rScLy2Zf2kORK zdPo`Ig-lbT=)xC@q*qG`hx{lULjU-LtsSJO%8$}aze8wdHYF?A=2Ui8w?%L$ssM&h z`YXKB*ch((aK?%+@Yz0s{6=a6_y)(uN+~b28|6cpLx_M^>P-&VbC?Zr)T8ntozEjv z-+>Ma3;AK(LU^}wuM%JY3uB+sh(5FS=#v<|&ZHEaj80>=WbY)6r0}5(Q90COwI&67 zqwZOsRVk`cMbd>7o3ZdPd|k5DVJ>@ddE$bB)-LXu*DgVdideO)>T8n3kP&#A`p;sRtSqwc;mT(lc!f1QQ?l34Im$U zb9zBxbmp1oKJT=YC*JL@j|@@n96()0;RXDVN9G^Uv&T__TtM0;Uiy<7BURj<_iVmP=w+B%P+GOwk?@1_|d`@Uqi!`sH2WdkHDDbhC^{q<&uP z??Vq{jMdUi z)+yBZEk61c_mYo7+&=@t$n`EjKD@(kYx?W?z8ygKHrnqBZ_eAb=bY>Gb_mL^<69UW zudjh@aR0#}e^h=Y_&GRJt{X*sy+U4St89K?;x1vxeey{LtX8Ym2RK6rxwchZOtn?@ zZ^@W^{2oe{8`?l{$tQiKVPf5U8l7I)c*6uKwsk{}@3VSjG)_yB!7+F+aSVNht@W5} z=k4q&=pKt+5yJbYr!=g5x)7VJx`9LV7$$IGWTJ@3&8MehZz+CpK1w^At@QE32cjn$ zl6|kFYoH5t`~7rqa3sBIA@xUW$0nIw{89KTWd^UTCZnXR$l+WdcFW*RagLlOS{N44 z!PMz2OC#r_zpzsSx)Joyage9cFFH&{6iv#)Ia_?}Uyx3WkXQaEZN@jH# zX_#$(Cd=boHseL;CbvyMTHt>{)(#G~H+ zlHd7oza-iGOgym)iR}m39`WARTH0t~_?VM_HEpz6rCLc(Uc5-Z{>|@Q=XdXHq`3?6 zq5NvKMq1z6N^B{JA&ZG{U;qAh>7W1Me~9m4YBZblC~u9wwXvQ)e)LGXTTI^j=;McU z%Jk*$ze0D*gAr`yVzGszZtHW%@|<`PYB* z@6+b}2cFc5A&dSwKDqGt!U&4dmaPm~3C2oH403cIjK=Lc2BRgPi?)Ao;BO4`D*q~a zW>tE%-fb6ii)nnuc8{$1J99dWxIUX)`Z-&Ko}bNm>|>b1;LU0;_^*lo^=3`9R#orR zf%>HS3eN=akN_!%cP-Ia;X4L>5koFxoXM3K3)k11D%032`)C6uYGVAQ|FAnszuR%! zKfJq@cD6TD4WrzZ^!$^7a*eXGLX!!h)s;Dy`9$rq*BPhh2ZOZV;hemY$f5hrrzN$^ zR-2Z91ll>+;J8Q&Z!T}d5J8Gu%@Jxmr?FRn<9eA3M4$AJ ze~mG52#mnR%)4;=rVOrqEWMT{yaCx*n&YCcO!<#wB`nJ3^I(X~Wrp)C;y66q7K5Pf zJAIGz=V}L5cU4>UbpI31_qv-_Bs^mfL%^bnQEI%Eh5QJJ&|=mfvj@*FnAs;v6iRmv zg2hP1Uf0Z=qz=3?OKA~MJIBZAV1LgB5@t76RwWoOOW2n1w#dpVN&YB}s1_rXN#)yW zH6`%ZBp6>v*gdtO1!WgQlDG2{?TXU!fu?)ZNnif z7xsm(N@#3V)4hB5()yiE3E>M;_AoFl*oZ?zp;&X~)uIG+ms@4<9^$H0*Pw7HI>PCN z+5san#;7GJ;;Spn%3P7cjo^GDx{Eeyfls;EN`(5PjS!%rjbgZ}`ano!1}F87kqDuk z)@0?==wxJJ+1mlC{N#bqjgo_L$A%#;3M#;WNO_ordX7;_d{WQIcQ!OB55iHDFe0)= zgH&-Tj3bqYI#9jn0uQ6x`T2>J%4#KqaJFtB9e7q^MKhF!vGP`#P$)>tim|g3m%}UG z1PJuNg%kq%4{`CKpLTMu7LROCDcYG=Z>7R)JoPJYxydTGGq##Mi`8CI@Xn=(oU$d& z_$&>3gEZ=j7ru-L<`(Btr6J`<3Uzxu4s@n9FHbIQG#mGXD>vf=a4OX^oT_>A51<(8 z(0K8S!8n5TM?&IpFbG8>MripB2%0Lp?z2V*T%-seza`B~D1n4TgkUxYqNnLS?&*9A z3QkIFT)4}MBge@N@9yJ@n?MdP<%`IP!@Ss4;ti!fM2j%j2jM{GWrj|nVV`+|k7<%X zg@4L~n?Mk9!uS!87F6=hamFQX))PETK)6n$pb2^g{QNjy14sl+Df!=s^5^>UwtxzA zup>o3cPf{iAN~8CI^!n+*pn(#7<8Z)0fFi;0)%+Q@FG5gONSp`gis7#=9@UCf9NlSV%!1Klm+k=ijf!KG8d5B<0RK3xDGDFd@qjdwKMY}x5J3z z2Pk3GhxZb6f+%u<99)8~^n9HpcRR>Oyzz3Mh+G0EatP8nVbqEnHe->t(7+>ip>5m@ zIE;ixEt%cdY2%C>Oxpp0S2z#3NN&Xio-s>eqtB^6Jg(%)k6EXFzPFcsKL`ZFAK*1m zn&VYfrT66WYN|KaQ?s$2);71&g9jg{jjf$j-ZLi9|Es|AIk707O%J6xAmVJ<+@pnR~6Y%Xsc|Khi4E7s*;N(cVcM4 z2!!#Aj{v+tL%-|`bLVrUZvjnG#w9EMZw2yjRMJ!(4#nfFy_NF zaxrHQv6AFma&5cSNEONPN5|cCaBytn!{+9ibQFxooLj|*eO76m*!XqS>3afM+1Y`W zP{^(rO@x*%B|Edai(;&|*Q6_nN6GVZSFxo!+l*r9`0Dpxd&SYl)}8d}r=MEBKl22- zOYwJ_I;m1FC4ag!&t_4cW08NPew!4&y~xT*+34sBLjR;ey+<*{FC0&NsjRU3&cWmuYKz%LYqU`>^#sypdiShIJRV$&B4f zR9}Okbum^PQ7-g8b|qo^L+UVHo~2R0lb$_$kvhYZbUI&4ossl4X-{j-N?KoEcl)EW zQQ7d0VQ)|U==ts*>W+?Pf6}M1rrmda3>Ce9S#49l| za6Nmm=dMpiv)tHfaqq>hXbioInQcvx zZSHQxiZ#B0ELW?kroO@X&gW;+<)r%el_y&~qJJ{Mu_b+sg#ACg(;xSXz zeSZEj4SF3L|LXOso+ElrsJ_L5A8Hu7pX_$h*So!R)JI>(U>>{0@SUTnGVp8}DZRIg zRM{HpH(nv9=Lly9!kf1R72ke>mUl;fN2t`I7h(JsANBcTg(#<;?+hOdUmxI)4%7u> ztZMwu_Q$sX%l+B?UEzb_>-|G{&io;sFV|)IHwPQO)>& z+;9>Yj=(*6L5Ft=@$tq%pkK6#Q`3Xz^qfl=PbBO~Qo zV3?>YEnL|TS#C;WS~(cNkJknWGQi`?k2)zInGGcjcT}LDgo!WmF<RA*tYRRLL;-K$e9^rs|epHaT3f!fmxAabDjte#roLywdfpMRx1QF1C0q^Xf7Uw)JR`~UyHrN_VdGMx`^ z7`2M0xzX1cUN4JC#CaUvxL0}f?Dne_hjrp=axp*#a& z_`>)k#RB14VXPvnOX$D6#MmT7Re~}rPEmaM>WgA~Duo;1Ll;6hDQQ#6N}YSFMYZ9Q z+QbSpit>2uK12Q(wbF_6)hR@HB)Z}&g_Aq6&thI?*@?0x>{XGn|IbzdvnA6)e5{C?tFA^BN=Ceu^uj`$aO{U zmV*Z5E?%Ba#Eto@ASbCzd?&yFa9Z}LCT9qzw(;U&A&HOgs~@r z%(n)WKXy-WW}g&BvO8$QNyO4zHl_wv{>3p#fJcAXoA1)+BL7LKJx*VYP{b6f0df&`j_@ympMwQb)(a(VJ8jR|^qoy+n_aFSu(?swaLjhB~NbjJ4 z>>%1@wSN*T0GaY;oCvuEa%>@zk(?in$xqNW9pT1%=Vfqwz5{kcOAhXlMZ6oRH~XOF z{0o#GU}S#nk9sCF$Kv-#gp$?-10No7DUMjXBiaxvUmfcBDaaQI%Fk<|q%W9}8xXXC z5+C>3-vHd9R7AM~!sR-Of;-gxQefYt%}PlEUgE(h88^q#cNtsLkcbZ|g+h+a^cmN) zU|;5Y0zqaPR30;#@0o@d6y%hi?e3NoKLiv8KENws+BN~S+hSVOySF8oh%LIB?e%p3 z;V0?t-G`E2s(ODilb%)Eu@anjEbmJC+HH*+ee!k9ek1>P0zbvg%kA*4^r8Dcy4APU z(aSJf#_6;1WeCcz<69Wlp3AqukHqkG?W3Y#@{WEbfG?cMvlsa}Xxh*vS+F}8xPI?$ zZ>D>9HYE>-QQ|xs4o=SI(s^1+{nLxo8=a<}WW?TZEcsS?&EkT`Ol5W1D`l8a$H(ja zy?sy6L#AfO3AQpkJnBl89@{vvCVhzyPdc`<4*eZ@4oV?j$i)eU!+ey{)jK%(#NEO zNR(&A)pKvj_abpt5$Arb=$TNqJXa-&mrLtMe9UL{8NtNcD3%RlmDP&f$l1vM-hDyo zSmn|m3@tlj-016K+dX#v;M}kEwRYOvT=&O&Z*M3-FR&c0@^Zdwtni}bOk9h8g5jqv zJ*!@0qNCbUOwH+ehE7L?A+z%_pA|QL*D0QzDn^_S-S4F{)h!eG&?A^I*=V)({A=s^ zHs{rJeXl?}u}ojDN>5mtOKs)VKiXH9I7ts4K1wTUW6tP8r#Znug1#j7F!(IfrqVOe zWe0tgS8+BRDU20iY~_c3x{98pGI6#P#+l27S7#Vyv2yr>yOimgX7d_ucdlZWl^7_kF&$aTB~Lw zW3w*3T>3Gql9)Vrpmdxi%~{VPnT`(k({ZQcdS-Vot-uFz564d}yf(u;Xdz1;vST)z&W`zqSsCH)U1 z`@Ux=&zV2O^X0ls|K?!B*T&kqsN_QE!Zqn;CBQd~3niWcPgD8s!0b@K#Azn&(=DgS z2_nWKBLRl;5fk7A0q(SN%S-QeFy9#=Xa`((Pbn0#rtcteLxvG8P`Lc@!o{6~Ujij4 zG*n&-$PSIP1p8$-DMyAt${6wMFu)$&CP@N0>P~P2&yeXE^H$g-cyTy1LMW@0r0W<5AsZ!-E$Ub?#7ZV`F;3Y~DI6%}!8nAQS!;Y;Lh)l3YNVH9$5sx?jDw_^J&6)Q97>woS;Fjs@Hw!W565h+ z2y@YA=B(UsF`JP+{i$aJU6djo0c;n6!AZ<0ALXI+%v6jSf>f`R#!F`Up*V!W3k87L zf_!X6&}MZV?Myz*{-g;oG{GN&Gl~i;(P&?2s+dwJ0{QD*Bz6g-4{1ab^$!y((b z#OgI{Rv4$Oc+5w6r>();C*eP5qrMT{v5gcl)W*_&hM-&arGJ zcO0?lIw3FIzB3?AQNK9D8y-L7!W+mq1ailyqU{fZgtC-8uv6Md$n1;Ev9 znphx@@UEDQQqobl+zE|d(qxz<70d*On>7YeJJ;L{i0`tYf6*e@m&B}p@8#wC*WP5owq>L#dqWDWe7Rq{dB80 z=PP&#C~bTj1m)N9EsV(n;T7;>S@HEPaGmz`dLxPp84%;kTD#?yORVDRNT=9YYosqe zx$m>6u2}IPIT9mEr#DQ!(Rn)PNgfgRs2~y5@@PdeI;)q~T8%JzNWNtS3|rax!@FJ}obSW7 zhHS~sc6rJ))uhX?VuLLN$AeBf9}Uv|yIX1d&Yg7JAN!*^2Al`??y+)>BwL@H+3@C%W4h3@@Y4pYtg6+k{z%T`HUwVdiYE++E0W)tREAuA zDmrYv&bDzq>ueakqytDUM?YI%Yr3p#vxZ@XS!2yc!^S_(Z5oc*x;!Z?3}fhgtaQUj za$kBD20x4d^wd-WRtvG` zMKLanoj==9HtO}Xz1dDRcvKy-WniDW5^i7Z^)J8vz0V!vyr^M+Ae|STPVZ;&Hm5O) zvE-*e`NAuVo;`b-zIpOgeT&JWtKys0*H>w0XDhYp4ePfrc6XI;S9;N$^4(D1xa%zf zIg9S_=*VeUdAF+m#}<<7Y6A>b=wPf6WF_MrrNda;5&ysX%~$ESUp~>3l0I8=o5CM$ zxxLX$pMSKYx~Rp9uVuDCl%Bb)KB4@5-n9AzHW+y8OQ%|vzP#3MtG=W^D&A+ctuA>5 zB3smRcGs{!Vm)1|cv5BZxmb(tXY#0>IZyxtB>Lx;+E>1Gr&l*e>_f4 z_Im00Vb^IfkI}yw7u0DO4(C*l;!9)oSkHiw#{Zn^l4s1Cw?kAPR(r7JKfM?O9`Bg= z_7FSs06h1mQUW!=_2UD-h2Dbon-eiUzz6uF1odrtD%ZOjzGBS3DZK5o0lDhiQofFM zDfR2%2a9OkUw~%@jIjZv%u!bOD@J9>V3YX-btO z)0vbBx59#=?z*|e;7t<-VZrqMUWkRkfZ~`yVO`}WF8P=~o z7Dxq>qa}P_ipOfRnYKT=pEh>xq*|+)t|TmvB{T;L^Ms%v;b~qPf-*y>W(FC8C}%vO zD4|4o`vB!{rO+Q@q7E_epp1A$k`$@2(xd#rsueB^xD_jA{=g%el&gDmoF4!FcYe@s zZf>RZjZF)kbqVPh!A7Ek@K=>!ez3Qfe*3FmrQb;iJ$iBY(z9@;I!YC(aAe2IuZ7fD ztEDX|ob7ea!l+s?L*eB>YGyll`wWbESaL)Rddw`N%#^`~FO?DDn1it~0x_!)qZjRp zam&UtrDuynj8ImvFjR>?IQ&5u9Ng3|hBXuq1aI8bJ-8UG*lq*E5QZZP6|*W)vhc_3 z%S#NH3PWL~ztBD?y7)i`hgEqPj^K;gtF#w+VaP;*$6!f5UY(_iwGmW`8vVfrJ87+q zTgr;kz-8kb^`vmx67cp9coc_0@m#ctw=%2zy)}y!@~8{XKy_o~7DHIiJ|A#Y&(cb9xPko`%n0WZEvIX%s?%6Sfz)V_#O5=tnoRc`*`mvjzS-6>Ql0Z(mOIm|?AX=BB6znmT zc`l_4PH{(AKyl?zl`mE{5fm{&o1XwbhZRR(pVARTCR30<-iZn%Jfj9$1Wc2JYs#rY zU64tXA+j!>9PJ;61Sr7rh0rYGr^_6MXYv~5FVo3%y}~KimGjNa<{OBnU8-{e4u}x&>?#f} zxn0+KSBC+P=Lkr-)%_zNsyIp@w5JhMP_X+?2C#VS_{l6!PHniB6pzz}*W@!4Jc4G^ zm}O`xQE7vc%yoDzp*)4>8JN_y;VM0O{(S0v|8Sj|f8}t!btD7LOI}!7No$gOws&?? zyS0nJ{cO~`I@%kfS7}mOI}pS5LpF7R=&P@Sc&5KC zU;mm7U#~0kJJ!dIzawEno&d6dV#YU?x zIg$_cj3D$4&YBu}o3+O;4$`lG_jRf@n(5E~&A&uYIzc9FV+aq4sj-d=AY`I^;{ z?PeowtTiR)BG;cMR&5MMXX!|?Bp>KmUBn6y3=iH~PV%|88C1TT8*6EMd&35k{r#hK z)EkNug|D?zySglXdg;a9Vd`{xi7nwO(tVnZT52ec_=oqm)BXE*B)g8%<0sEt#=3Yu zIloE=M_uuP@rzYORqIV>3g-hpALUu01x<7iR_Cy#9P<7-1`f3YwTm(4`Nc8yme(Fg+N7tnOF!GQu`D2`6g)8Thp)0Wx3j-g9FY74! z1DChhcr-{SgMqiWq<^$qRXUWnIBZmw)8G8{U#7*Cs#iPp2dXEPoym)>S|v4Vi)pP{ zbDgb7Ph%Avb$oJqp}IOv$HzxDG_hS{rB+MFs^_7NsEcWEa-sU~rrj4WT&F9Z1i0$$ z)|nLOE#Ai?wZoYWI;`&DY%z2gw$H=}13u>w4~JdrSM6rYI+n{T9nN~3+JRkD&_~%3 zggQa@;rYO7BXrh9)dy#N(f&#xz3$w`I@$%@^u@tZdis3VtDjJ(Fh(+2k+Z@6?9)f- z=bt}PdtG?N6X&uWA0DLpJ6q}D-EHgT`-eyAOwXeErB&C>_$;=)KiA-7@?hvu>=uHN z^1^W^>Ux*rx4LkVmKV;w^&fF^;-B?uUFEY^+wuWui4Ouyxvvc!qC`mG`uzAQCH6_ z-7(hh9(2>eanIw4tuvVf%US6d-!Y`NG@jVTa`&*8x~dOW<*{oE-v-#y(c71bah{L7 zW8w@rR)zBRx3H_wA_In0@M8qOh2Dbo4~DM~@S_0r?b1_UCqKUqNMBO&ZhNzyPs+E+ zS5Firdwt5+(T2-!<20UQAK?3eoBfNv@;U%N3||`?mM{xCWTr+JI$SigKU#o=myS3? zKR#0fqzIV0f_8|pz!YOjAHaorj8nf;v_c@j?%4n!kl`s}ZpIUSr7o8T5HC{E2#nyt zAGuwLA<)K;V1`V|He$$ShEF>brdt^7O4*{E0lNDoF35E8;h)xzP(VWp51(-n9N^zr zk>DkWHVTJ}ll=vC;?9oiaWC@`;M#FqVCmPMQh)L5Fl9JRAJnKu>d8qA#D~wW>~)pN zT^R^iylA;EjtA4+JH;3eX* zodvX5^>rcH{37xo7D3fH>sM)E>s;wkI1t{v_qmus=|W&+^$vM+pfr16AMNd@uYdbn z&lbec)t2B_Yqo8i^7a-gLrV%O`G5V}->3iifBYZm;LGRE@jHW9Q+8>&vZ#7!rA-O> zjh2+R+*cUXC>Iz__y}deUf^v#U|;-O(Prh9+@6i8wCs`3sxb>z6da?H{22F8?0A?! zw``q=v5>r=OM3GqKU;cYbRvNIN7=^B;nfJZs%|Mps%N420Tuu9NBwiKw3jI>kTS)L zFa5b(7oMp%kP;6*`^GR%Dn9Aw)6;BxU;F;2)@Sx<-{?LQBC^ZG*SL21gqIk*$-9;2F6m#l{I?{DI z=Ipss8@^7Yn6e$l@nJU&JNdjaXo}8CP0G?%E4A0!YFFBdwRfU@dX-Kve4U7YjMwC= z{5{%Wi1auW&B!9iBU%4qEFuY|{&TPaL^Tp@W(-4=p5J&L@Ed7BluJb78AS9UI;poDnCqi6*MhoP}tW5+3QMa6R_r_z2;*VDU@X%XEPp zLb)CGGVSO~3f2G3x-cl-RjD86L6p&iMZ*|X0lB`XH7bZKCU@#*QfEOl$LB!1!x`?J zz!eKuaW}f-_>T{_WlY$>1K6M4z6qa%yweK^*J+HI^O}G{g`abr{02}Dq>0pFpprAZ z*Fj|rJVgZ=<3KIS5pmPRM9OVk{bbq`8vYIJo8TlkNKTp@5Jo}xxDF=o=j1Fzo->Jc z%Q%iIbi|SU@CU93_k{Ie280|4$Q`)AY<>DM#IM~`nC4|N4w>F(A@Cx$#7)D3(rmh5 zNk5Z*q)X)vnF(C?cDbi1!&T@_;qkMlv)=a&F!KQ>p!baAsl}yAT3g>qckX_iTI-u> zYkMc{+`sQt)qWQtu<)+Zue+r#SEPTY%||PHf(`NRB-82+-w)Z;1sG#fK5hc#n=Qke zK|DWa%lZAmoAWhW&M4RI5R_lXw=gEpnl}Z}bkeu16D50Hd(jVH52XF>dA}+zLiy<3 zs5jH*)<&u|RxQ`E9rv7M$93r~^%{nP^E5h(NnF*%t2F3z(wAR7Nh8UEUFj|V=Rf>I z;+(Ai$N%&Ho__YTpCq3zG?eUmb|KkX^dytAeK+zR+sk>i$3n>eLP@9RS6;z2!kFPz zR;&_>Ek!X@Va!4}ymxmaHKd!c^&V$BVf?DEE~by~ZCP%8{CqDxdw!4x;}aXAt|T+B zt}LcU5ALQ%_czmetLoJoL($w-`mxk8w5h@H)aP3H3@p;Dat2l1MwU2Z>&z=emYGb* zijd{lsR9`u*_^zXc-ZUrrN{McV4%t^b8yMcgfa|VOlo9h9l94rD)%E@tZ*Z5R?^UK z2}aLg)mN+4NIQ2}nY3-1FLw7+w>yx&P_?1vxO=R23&YBT?e%nZPI*QyA1iriQ)r=k zpj$wLZ5&x06chi(p4divocmm~+&PpEUZ~?%m7Opyb+N78iO*o#*jN`|JMIU22M1#H zG_}=V>dTALW28e|o_hi&lM68Z&B;%Fbvkjb6~?rqqazzlh8K(JtNm^|><*RVymX}t zuZTkz*}1bRy@s~vSyy8P6RXG2`7l15pRwgSyOD@#i3sQ_v=1wYgd$w}6%z;1b(jcB zyGYL#ZFV4`fsj?Hb&O5u+~^{V8|s4X}{F&R76?F%_kyoj);tozQsW3K1XIJW1!!XJy zH=nnsvK>jE8uWWl{c29*_A>P~#{S{&{?6YpHn#7j zt-B9WTB(RX>9k^odg-W-9dsGD-SqUuk+*R~N3BTDtgSAk`pQCDYc8iRKE9jo-&qr_ zzS5p~b=!&5`~9PS8py#o?(|O6H&6G|^Sz!Y*s>b5Rt;k|XSg*~KI-^beUY=Z zlG%QhjPyFrc#jhAwAuY;K%Q??Z+fD9YqHnTj;GS=;ij(r0p0~}_AmO*>i~QVUkiwlXcn!*8jhQqS^a9=J_$ zQCh$u&Ws3FYSq+WpKb|OtoFj#LP88u;IIM+V*|n=+a1_YW2K0F>LH>uC?XO%O;$gA zprizT&g#eIu#k(WMIgdBE5R-#Ajj-J_P1X~$x*tI1nkbie(LNWq%#Ss-nLH4#BkV` z@^C7_FAO)V$YN#K)5qVW{U!1NCBn>>q`Vlsm_pEM?Id2P7yUaOK)e+n zI8(X!SV5l{seZwS(cp`;D1Qs8LkarSiQ-IG1R2UAVMUHMxsY;-62f8GtS~%by9g;q zRHMfjbSlfG2025e};Tk(>PB$!EM0hMUl!0lwoi zE^!gg9RL%Gfgd5pu&exqKjI>Mnj(0TkG$-fO)DH{#s^*EfmsY zmH~8mQjWtx@sBR$oP%9nc}kqqxQyV0-+#O!34?r&GfmTgXX0k-qogN<`pa}276~H{ z-6!cXR!&#)DQ)9#;#_uwbCSp84ug0p7pPDSJRBtDo!#yA|C54$DEQla|C0sk`1P=u z=9j8^AGOlj)=v85^Pi`m{QQ^cr@#2O=`a5BZ_;Of_Vcu^@P#F|^rhYT$gZ~Z`y%&` z(og&scYfVJ-1r3|JQT^<@b?Y8puZagyWqdg^*-U<>dfQp6)>e-TsJSE+}{+G?%R@1 z9w4u}fZM{$^(`<#n{A`nbb)|O2XJ?N>CT7sIb==6uU6}+!M17=FD4{_b$StKmN1QixoM` zOe&Ks%ZeG~QVapmC&gdPg46L||bB{4Lp4o7v6sfwrn6}pH>F)Mg zy0_Izch)4+&!4Hx9ktc6cL`}Uo8Ar<1KL>WSC?1Q-OY7f?bNQRex>)dTP@csJrUjx z4v*7ur<=~i12PXrOx~Fxpx{*!psBcUSe%N$agfYBkxuP_o8Qy52e4 z56-9O2i^4e`GIsl@v^vLqZa+JI~=Lc45gbddtxMYL)kDobB^Uog)Ik{%rAyoaQIe( z5ta65wHRfi?byP!s%Hp1%`2SMglw0}ia7L043!v$8OP|j7#rCxka3UB>3*PR$b)-3 zstffM`K$6%58yJ;S(V7vs+^_9>M>TavHc?3?_)e(Yv~!bsyfxU#c0{!8B!NNJmXX_ zmr>(!evZkVbFtl{$_`IHB0_x#<8T~@;(J$vZ#v zD(~Q;{=<f0{(%DmljMY&(ab%}dl*9V{t zz777%fBs+p)7;&y9lbGT2G&fvYfUK6l&BiHG_e~zLJ2n|`Ge#P1>N`{OiIAfIi8U4 z7wnu)MELmP4EVY`fymwb2o)bQK@g-#8My?0ag|(5Ih+o~fsioeEXRwQXO!dDi+0kX za~R+MEU4K(A!sW8Hb@EuhhoG%(i+F{l07mblV2l8oVm&6%Ri>a55B@%fFlZ8=3f+? zJeSLf94co<%*+KkcOy8wY=;O+0n<|;^%03?ppYagm$j6gb}{{2KA^1ph=7b}&ZhT_ z>O1-vXM8ocHqy=~4^ve_;Bs}<=U&mi2-BoP*krqf6NK>5Sd|>YGdW>shz~Gf_`+C% zpvVfLVzA*KqY8ZsOq3V)&PSm_=w`(fvlCHdm*(OS+rt;TY46$7)H^y#lGH4aTM1cN zO!f6vTHoAC^=3PiKnZ!fPadb;ub-x~A^X|C0$gbV*b+$I3*A81YJD}WZ>^KPX_#;EOH%q3Q&Gepltvm(W?X2lhQn$zkJ zlNd@2co^AeA%tO%%NPu&z@tiT<_P6hPF3aw zw%wp|;Y|twWa5LJ(km_X!&V+dFxwU5ApHk}-nsbV3;5I~g0nYlP`X zw9SVIPu?Lpy10P|n+>@M3NIBi15rl1bQQ`kaXI6^8AHfySmytRE8w~xUx}Ia4|{S% z!5}<`Q6Jpw)lW`xEw9|r)Azy*%y^@%qJ9HYkqkORAZAkG)>WFi(3ynE5$@bx4x9FX zGG1~i19x(F&bk-kKwy^qrX=N%LQh`^P@gevpxl9ySL70$5I@be05La;9a#E_dcF=0 z(~o5t5F0BSU@J#Y9Fq;8C9$hZ;q(}l%0kbIqaLl=xpo~+95|^jsY-~`O z)YGBwg5x`=A(Uo zc$!8hYyr+pspOSG$HyJf!H|Vqex9B^-%I;PN-w^v^_qGf>`lENdS@TLNy3na)>J3iP zll@*gRy^x=1=6mx8@5BHO+pQ)4V+Vjt(?c2t%VKAx*Rh=Uhe z3Bwz*`4Zc(B9lwEs4CyB&Gq!~?q<5P(J)=kE_$)oO;4Wgr^DlJ8V$!@p~QQN$%uIl(K4Nj!Ngki6*c2iZSUcZ|TcAwiw5e6^mqpCmnuZTv`i81Oh z?FGG(T{NgmbQ^=}5B<65Qq()T6K?_)$j=gX&WQIz$W-W+1;8gi>XG{N=o3zPpD+oD zzJR_*-$#GM07p7jKW%N_NuPc4sr!59_{fIGE$PO;{P}0;?shv3q)TB$i?PSHl4?Ko zi^J|XJ$`n91nV_vUrs~{pfDmQ2TK%-Pgk1KT>`6*g@vh#@M#% zyQZ;R5#5!=IUA8U4{v*WOKs5-k1(ITJ6`5oet>DvRmPdQ&`0U#u>v-z}!ijhde~ z9A|)WYb;*a>4onlXO|1lwwWucO{cdb-=y80f2w7t<&A*3-xL)~xHYwdKZI zH9gX}!JtOJpoQjDZm-M~UHa?kIrT6~Uq9JPhw5jG>PP7NolaNnxRN&Y%xl;6%u(7) zm9MLMdAfV#GuRdsZ$sG$D1VK%pU}Eb zfe-=l6M%Ck&{g_kky8kb^p;&TCIdHvoDn~p$M*xyMPz4ky9SJr5Ad%I-nFlhmVPta zcYgSO6z`HLyp99j8Slp7+t%65db$l>Py0qOZ@~Mk_mc73l>1*7{D1!6|F5~ZyLawN zgi~dyvrUwr(mr@`=R3lWSJ?34DM-Er(zP(*M6w9;%c;aWM!)h}*HC!G2TU-D=P%xB zB8i*3!Y9ZemDE9(kKO)wI~xifu4}Z25Xj-zqx?=0|4vs>3b=|KAG`$J2rCdPBC_W; zBETdZ2axN);iM;$Yf2!pin5j%|LT9Xj=1~b5y=FZ_B22!3X#_znE}02!v#ILR3T0! z;fe_2O4$P<_v_`)X}Qnj6=H9|ghWBhVI}<1b&4l=rY<3gc(NcRttFxI&c_eassvI# z$gmv(@h7Je1SJ@w>>ymTq6md$K}rvdBa|~Ut(^S@E`})Dof(5DTwckfjE1AZq^u}c zCm6mYXhH+Q80ClAn;0j0ole?+`ZVo6f1b{zs8Uk4vBLN@FF|!tN*mjIv^Tb-v{Xb( zO4iqp)A5V_bSZ)RB@ja>0tosD_HGC1R0zWuLFOf7v&~<<-Bh{5*o0Ar+Co{yn1W%4 zJ^KeLe<*>%VFp>PmR73uw6?zCL!&7VGr-si5QXbR^~1I!;L&_mK-@Sg4;M;@{A{m* zGDEz#`a=VQb@PHTG2+n9IFOoc1u>*@mYR)hLT9xYIN*{FLlknIx9*Sw1J}i=+Dr97 zUaa~Ws($GlUXiA7_RBX9QoNvtLcy~P#mjw8^jM);lv1`hBp=wtD8|cpjA71oL@_U1 zcN7vH!uTbcy1TFFPMf1#vn>hzi800MxLjeT>9WgD8v-cMd?+CgX8Of8AW|5mh>VzZ z$c$1cHiNE|(#|lQDC{zKjX5b6^%mPnHLSF+XbhmZc@>**&W5UgDYh2Sb{&ExKKJD^3#5cc}p<{Q%#E*cu z5}xk>Zjy&LB7+am@$(gyIgF#g zjB9>pc$_4dO=nPm(-TpmLCA>y&;C*&j^byw6K5z+P~$d%h$XDhw0zx*m4?(MnWzx?X=X?J%weewBc>8C&cndSPS^a!>X+}qo=%sIcv z`LoNZsd3tDuZ!iyw13p`&JSq1ozB3kp;*!J@ZKHCUYF_XZ=R;d&-VRsoWabl5$Hkd z(lfsJ?32`Jtx3jC;%PBeR~LM4(brG+gmdC;O<938FIlptviSqGzE zi_|^praKq~)}(_p#kX{oU;XZh&vD|3amvT|3-pk=G*Vu?CD6&%*4k-Z7w6mZZ1D;s z={lov7zBocv3K_oz20b~_4RhzSa14lBerX+t>}4q zHc~wt_?)qZ!XG|-lr9&RQ>Q;x`PKiVUtCC+U6sy)(XQX?r58^gr|pea`t*}W(#vETiIu))E&alL&y#LX|De7ZqpQ-v*=q1e^|pU_=zhoQ zEO>Mu9BF)GEEFH;)2&u3ee&p``g}|J+>vy-p7LyHOfIE;<+pbj=k5*0XWnj<=LIXm zd_J7=r){h1Lm1)cOBh(Y!;`dsa9{&tTjB6WzhlJ}df=+YTtzAR~N$Hr_z}1mpJR)_Q8H@2)OM_tiM}#BsIXNY4TrYuQ4vf0~{ib`>7qTXuI3RQ9gh zsx2NXl@*B@8i7&>*!qy|AemIm*<#e`?*6e2e&>8g5q%8w7>+Tt^K4vQk}j=h@THVs zCZi&YV*tb`rjDWh%v5QC`J-WZiT45IG|B!3 zd@y|dYlL^{YbD)mzi|%>=MMOErd+<(3&?b+-&3TnL zunTU%$zi3uVBsdh%j6{#Ri%hE+AX_DD+ISO2gkB39zzKqb`Z2h)vIHmj6jc&XrqIY zAz&_fr4GRMeXCML8s3K0<{my7W-$TIE)7a=P4Oj z4|ypIlFU|X9N5h2oY)r~H-@k7p#)+nYhuc|8(@SoOTb@J**FNgDh0CMuBVnR4#}=H zYc`@)p(RBNTn-Ax@Pbf0kYdx50MF_)3}2_LCX#YQ-5`82GaF@!m0#2oTUx*qw5WH^ zkBXUmJVGVz(H5#-&(hQ78F{Klwkhx|J%w4(6mDrJujW!Xht)C*4>}l=s2l3GR;k%I z=4}p4l;FKAK^bb*Ul>iu|FjP`sD6p#t{G#t!x5^8J#qBDfo%pWjzNJ4_`(Y>p z&$9(Z!?Qpobd%1rCoLpXhR74e5qykv`2ErrJ=cNa;Qd_vfYzgaY@AcyGS`w?y&VWN zoHn*t^p+>0<}Dj^_hHg!?4!>%Gm4kOz=}j0vd-zhPVVuJl451uZLWNvA>Oefu+<^o zYhv`krd+DiC=26=F*FlLIKDOb>QT+j!Hx(s}VWPa}Q z=dielocas?G>&UFUdhd0`O?pXMu{iv zT6n$`IO7K;<4tHALvHH842wq8N5SLH-{cvN&%xR6JE4(|;t~+$i7e3&<4f*<-D3M#orMBx`4ytBN-MdZ|- zLz0Ljx*XyX-oMW5%=IlZmJ8nQbc+4Uy0XkQuY$>@VJPi&L?3RCkXQt zC~+}POWT_za7((m*zU)8Wqb)qJ_5tfpVAOk-qn#GwDp_Q**%L-p8E4Y;krySmt8*7 z1HpHNkq2l%sjJ!k=}6~|GxEb9VG-^$x+eK?&vDMz=sZ7ic|kLVt_f|f`E=aveAw#n zI|B8_Z%7>By9VlOOp2+sHd1@@UV8M&&(cr+{FmwTpZzj@_LE>43Eix=CGElYl!w-E>f^PTO@^!Xy#Jbohnj+EVH zT9Zz}DlBAiK8zn7AE$%EL!Warl1|gNPSJPVx#aWtt5X}dI1kF(mx(|09pq}x{;4cs zG*P{X-k^7!wl-R6W4-MaMCeOQzq&X-NlSC*skXXogVCM!M*8f*R{CgXE#2L0`Qvu1 zG7TNahMe3MtXiAs3esONtgS*v`c{nK=`jzD{6Q2E$K1J3*$ty+4L$oCZut( zon(7WW!`8zfBFn(M6+F7=WstA@9(;9+HH7Tw?V{m|9I##nGSYeq{HWr)8fTAEnJ?a zk?QbdIId;5p! z+3ukYzMP}QmY2_-t8O*c!Z>qbgY{54JqDW|TU$zZ-rYY+PoKR=Uw`u?ef8B7r`gw7 zVP_Z4Qft*KX}#T0zl{}@qw!gKanRAFaWYUnDsR43z#IDbh3d9lTTJzpxl|Qz^i}Ka zYIjUGp)ZHL!-OhteW+@Hj_X!s=DP#s8>qdH)R)g4SNYgFb#QWKqhc6M&rA=aI9q`- zzA$1EkI{Ur=PSlS>bR%zz&4HUP2yRd-($e5(v^<;lAgKnZ&_D7m>+W*GLSz|(|`Ek zH@v>04@Q{tke~iIMRQ2wm4X$uuOud8SCF!4Kj90*2{Dkitq@kRokxg3wb!CQ<(3R?2h zwK*Kj*#Dh*eN@_+Gy+;S<4542cFakh+~?T@qv^WLqgv-1*75m4?2Q#bah< zNg&0D0W3>#S{1*GQj(S{tEtgyEAPuR6ph2Z-PCz;lrELtMYJ?e5!FW|tSwcR(ke3( zYn4=~uS&s4;^#uNB#=tTW#(e}7|C^|GWwh`3Hd!{ke#rt-=vbA2ZosywhgH_Q*&)S zRm2KLWE?5U~d!YrU=6sb;g#1+!2<&eG0WLBpYmK0}04WQh-rF z*zS;~q<&EvNk<*Bg$ON2J)dGgRNY-jp+orfiZbf={49if+8zm=@{0b|g;K(l2(xtz z0yo<&u*W|u#n@($z1(R&wt}Fo*>(kk(~=Ze#ycy$m@!KAd%VMq%0ju}N!}3TCD}8U zi!scY!lzsXCkz-WKXtDEFv_W)DPPLuRb&E;jGPUJQI(mb^cA)_JQ=Z4?<@_a*z}IZ z@}EQ*l^NSG)}_p>ZLCT0RiEeFh7~C%YR{|lxpY1{PtuPC@hozA#00BeA;1b!U4AlMdjoY^A3$M~Xo!wPNP zb1g@Z-O!}pfF@VLB^;U)x(-%&_;YALL?|!vw$pLkC;cD?lr%ZiFiYq9cpq!nfJRW!*81kQGKgoDL%SUn_;|LknGQQ+Rb}ZOjYot5v70GWy ze}rdy#0KXu30GoxT9v%d$YQ0?j&RxjjMX9EeDgT{%dh@fGJoGY5pWI=Mr&kJ8;UL$ z(%=8nZ__s~_R_}oowRfBzQ^+ZK_`9n)njjqhwo%T?m7ShwI()%i_($l0j zjD`d8(DnIQ{a#u9Q&0DIc2c|1G)?*!+ZUpb{PuTWrml3)Mr9>E*twIobg>%kQgyVr zv?|>}ZLq>NgwkE5y*pIKvA=Q^+4oDpaABo-lN9bRg@3=urwI zF5Vp&M|n%c`@?wxQ3>H-?BSQ&<1bJAakSFFALfff&*KxCx-+SjaR=W%Qb6tNT|?BD zeEyVmX3mUTO3h|NWn=ZF^w9+_#u?{?jZ~)t>xCFA$*-oiu^|?{Sbdz8jP$!Rm5psg zrI4xa(LIOOMK?F}?i6iSJvKE??rycx7Y{eRbt%2*RL>309UF`<(qM3w_Kte#+3rC) z>@w5yHAY6G@6?G8`VFF``s}0oHr5??JL$`>o~eG0{Cs8HVxXs=F}-wsyM(r#Fjm~*rKc2r)^_p7N!z5lqtTOB^UccEo+ zi~s=t^hrcPRR0>^c>EeuiOL6(C>bA#@RzVCvb!7-!UWKq}NM2?Nl z9PR>H$N_YV4|qV%U;mRVz|FtGL4guF^GiB^1r96}`xsiqPn=!TdLS-5LO_+dk4oc`y@Xq!(7PTNL)ng*Tfv#8!R6421849N*-^4+PvaQmnY62%@&G8eBy6roX=vTqOs$=*v@D^V zbE|ClQZ!rG0i3-R6ljAu{1?H0X&%E#tO(+=@k_!FZG|$*iXk5gt$bpuh$|am=oze_ zV#ZfrN(_n;0uw^;r36S6&2tH*eF(a;v6kjeXU3kMghK*(lM66$F?QM zFLr&FlUdcEKsZNze(o<~6cL*7437xKo*k(?0r;S7@Xj-{oKr?#v;)R8`VeOc zur(zH)A106beIO6k+(WTd4T>h%5Gyhwbz9mRy>c02f9aKcycsCCBB6ff=uKR-&k4629g&zXQJmS`(oNopfZ_6JN8mmqk9 zTgN!fY#e}Zrfl#akNZVVM?$+wMnW)MA{~_dID@Eh?9Q2**NB;+ZHHZf6X8=LG=kDW z3n;Vi zU5Sp%D7T+IC2rb4f=r3J%E82V=*pF2UjZdHXz}|pekM8tl<#^-z?53V#wVcgm(or1 zn9ZqByG|j-LHHwXT5}On=!L7GQvD8h$BT54K43Peq?rwH^Z8vD@s7R;IiY1ByGa)` z3P0hGFw>Y*jX3l0Px%LOn0PL-5q^`fDtDYjUBHfuS;HGHaZ_rd9N}qLvB@jblPziHe8 zvvuqz4Sqeyd3L#9s~*6xQA2V$;%-+m+URU99raJsi~Vjo?)D}BNj5#la3=kuvZC=- zvu@Grbp3%CKNFt#D9j2c-W3Ds3VdwcXvfxFXBTt+SdSbl4J6f9=6ycYf}W*|a~J8( zRy(y@O_hHx4Tel|J4i=+yQ!-D+G`tLJ<%Ty(#E#*qvm@0^>4pU|MdHB()rv%s@Izy z(}&UxIG4*SsZ_Fxc>CnRR{F^&+v4{mee+~5{pQQ3>6>SJdUwn#&utrbdOel1bDa3j z&ojY0MMyU0ZOxmH$#cl$&{%6X)7JXBbc6Xc==al5Y42=prcXY7j^!UYb`t_I3(>Kre#mm?e06kex>Dfi1*{a!i z#Km^t7!5eXY#{j>BgYnJsbMUVOg?5};ygOeTsmM?(6i@m7glb?>Y>Xt8kKF;S?v}2 zko87BpzERzViH@d3}dAi#wfPe!{EUdimbe2o5JJcqx9sPuhZfFZfdD+s4I5iSXq$X zg+3)+XM1x)Wm&M{Wo>iQtHxHA)vgL@~H|nik=UlhtbeHqSe)?&8 zxU;Ul$~Or5^tp|=7$q6^d&h(HWcN57_eU!0ocUraK#b#zf#s!`e9G3AY{N;qk)Ahf z6^bF0X9Gt0LAR4Q@%+Kv&GgZO9Z^z06tAq%tju9xI!z0!P35U)8s8dJp=jeg4=z=I z!|}Pd%{Q-k z_N8N=r#9OY*6N}=u;H{(t)$-gBz^h(C_Q`8u>n^_^I2%L($;z-eeua%8|>)cUq9Q| z*gy1nbr{gjQ~FCaM7LOSJO@NUV!?1$?KwX5Z}lRK}}s+ z_hu_wp7G)lU^W)_AGl9szHj3qMq3$k^kpt2CPGSiY^oN-Z@ew=75oT)bAU?Z{Azd? z`jq3<@Gi!6b8gn(p2q9oCT~1vcn|Y@agDr(XW{z-Z*|yiw*JMh`NheAW@iW zv$%7-Yd8ELaCVPB9=j5#e17=nXExly*&i=l0-_Xx{O1AAdSLNcL*aO z?z6a5OHNZRzgT9p!p(PmYO;?w&5OcOWWZO}QCH#@ni$X6&IE87 z^haG=`BNIwd9Qd&x^SyM#gi5uyrrOxSy5(Yi?U4!eFR*TJ^C+wk2K(xGreM4MpnM5 z-PAw4t)lCby7vfjpM(}?hB4WUnS3V_@>%)C3^;cS6>4EwijUfU6-7vW$ULb(PzQ5Y zQbf*3Z;Jl&7}K9v%pv+yeN!ebo@0P<{2P8s9WIqU-vOiRavb;Uc1rv6ov_@mxCor^ z!WeZp&TtpM@BBHfy!;V1p_Rk3p8)Qrqi|Jd;FK_e!OdwLNxc(p9Qw0L=znlXFAs6t z2sLgQClL<{L>xxqOgAU>PvCKPK)f?dO5qNH54jw!Khu)m87tQ5z}25(uKe!@3hpQCb6c=cm%4vRVo zztct|Mtbh5B=h00DNpeq?nxb(_LLvOz$x{3C4V$g$+O_hxLvPeg69=sPM>KSlUo!5 z{74+`F$G%)8{|?H|gj9=HI0+e)<>b;m4n+J9i(Z*4mcd zF?GME{4Q|&P|>-{CzW4-Ho{K_;(8U7bhByyG{9BzM+xs%-_h2$!@E)bc8H$zZT;!( zpvd}AxS0db9U3&K^X`^>#zd{9)g+^|ackdtw`_SQgl>Pw~}8Lu0!gD_at)qSz|E zYPp(^_xlI?o*@s{h^*M2-xl%*|?8UNBYX8-w&!6$<4>zUOL!6kgR_e zhOE`4w1TKF-YU|GHrLzcsU~@tiHWt^N?LEJ%va}WcW*zv*xhrz9?E?x9_CdZ3{q^@ zwxR}zNk%F42E+91>2vYbvq9mUNsKBVd|B6%{(x+S9_H0Or(>nPNEONBHLvJGZW1Mh zU7oW;13OAcFHmX5!(lo)>{!oOQQtvFp#D}@>&kDC_71v!CbLR!)$LJF8yg$x(MKPp z`wt$Z^|dvxuA@JS0bQ$JiN+R{zyI><^yN2CqW>Knrvvpt-wzJGYL6`}U%c2&d#VR^ z0U3_t95nP+woE)z`*@3a=^^OJtkzpqpP?^t{v0d5&{F`6U*5(M!-&$vP9MoSC?kk| z%w@SxX&7GCp%jKEhFj=U;Sv;&puA&9Ykf}_D=O)K^v{qpVoV}!7X941Ecs;`Za49O zjtVCI2z@?u%+T3FhD8Sq2GH@*CDEgq%-S0c{0#v^&2TtY`yHo_`Yh+WF~(V82cN9U zY&F|yO=FJLW!@Dg7mB>RC1Iv_q<+6IIv9a8RMPltE_KxB4?AOzZzjod{@k+kISep0 zjls1>#ajbzv>U12U?t?Ljj0%myj9}zlKL8}%~ba)3m+u;uJG{gR=Ts;LYkx9F?4x)=jFM^yPi)r7^%ip*Yt8$ z51yzmk;aCtD(8`5AeJsHB527N&e&eF+t;|CU$TzByfmkJThf?qriT1BNK%eVTA1$w z7v7HY@bJj1GdXXZ-CMj`R&=>&2l^lvTdgvOoxHhDG){S@@~jz3m+tBL!fH_rb)CW3 z&rl3}82T{Ku{w{*#f&%35ab)v;_|AWNhi|D{d}h%=5~&E2<;uuk!bnv51{uZH0jf? z1Vz0z{sa7YfuWe4z^$#!cnwFs1GxXdeIjQMcQ>zy(s;YZ$ma7v*pM5eDPL?A3u7;*ENq3WC9C@#h*LVEa*KqtpwxqgF7O4 zJvg2)IigGA0muqr#;zEb@iW14xPAi^!aw{F%1g(jba%cH=G1sG1n`xgJP^Q~82q>q z!oO(|V0!VgCy!FzC}Z$vJRqV1aytGdVFeTwuSn$w4!8!n3FL~*2_)1mX7(gyYFGT;0O~=v$SrUuG~v(waJx0)tG`pgyZ63cxJs?fjkLD2ovIscZ+nO_>|D4g zN#_zekxe+O3j-1cFzB#vH>+z9@~O@<338#7vXud|sU&DCA^ixY$HpZI|7?xNc6{bb zf;8Llp;#Op9;Q*R>sfnb$V?^_2G8(RICac6his`=Yc@S25XBhf0VCOo1mlC<=jq`2 zGu`*oxI47*0|7A7teOXeS5{Opn`v=XN&qvz79~8ch7gG0i9qjd0x)_>iRG+-L3iZY zSA5W>eq7DESY@;*fpY=cQZ7~{=rNORUJ4;wO3X{4<$&E9%Cq8pP_qqBVa%a9P)x2= zX14o4p<;GkMf6Z~P#7>wQHS2DPzg@Yq%@qbT{!LwPN(|cSQWFI5+tdxSTj5wA2MYE|e%>;s;$0)AJ8$9HVgVQ}DYe zBa^dvF_jFCgQLP%#0Bm0%p;cZOOGLpBvTsTGTsOY8iiKQtCSh90nFJpj1Wk2C!mA{ zM0!F{ajB0&E5eBp4o)h^Zt{z}yg7AHn&z8xH%`PFs3T=Si6S3Pf?W z1}6OA_MOC2+QlDn@l)Ir{L(LSiYa8Q!rLV8k{XEmi_{SoeN=aOEvxA6{ucju9G`vm zM_ENnL9C|sLp5h(5`+my58?>Z&!m4C%^{Ju!_@w`xkwPP?zMpfN~F!y^qbP}zxuKS z{t!Txf8-E#XP4fI4apyCYa6N3Xs6AM`)PaUQL4ArQl;MX%xqSs^Ffm&7aHhAHh20= zhYy)N(|Es4``a|1X|=qndJ1mA|1m-Cf3JY3tM98@Kx|6ub@_ffynTI>@6GqxER>j6 zV!UH@(BEE7)%o!bzA zEQlc~KFrRi)>_N=gS`Wv#lvbZR#b2n&z!~@1|tkZ!~RI}sK%C_YsmhsHs?aEiB8DF z^K*-mEs=wfIpO#!)kKFgxf-=qwUKxbePrfFeMNf6s^8UTr;O(XJ$@Ix6=Q!i_SrbB z_Uaz@r5i~0yp$}9ajHM?*;4oKY^0xl@hEMsSN(zipfgIly9dtm&gPm|aUDso`0B}l zWpmC8IzA4=0ER9Md~CDG$8&TPbS*wuqsJikBWtte7*CLz^p{5u?xoGGb#D)M+#5RG z#+sf|}R<8-X_toq<%J}bO_ z_ZUOgfQC+E=|du$nyQxv_qWsiyIbj_hYzJkE~T#8^7-CT+B-N_oh_vC=v4Ga{@{K@$6{(USQ*sNGrF4A)ut`=AtoWBqqLfJ)p)}LPR8s_mlNg#iRdWkfVLV$j4CzE26pNG!e#1Cyo)A zcYBS{8j=F?9eZKh9kL7(ReV*>SG%Ar@DRiroeyN61xQqHfWt3_5!uBaa{X;=EU z@)cqC6}CcTyHN~37?0S6Wr=>T@|^JOQ=^4<~vjyY(Cm-EQ z_jV-1tgiZ-M^|IMr#x6Shw+a#qpw-#*Z5mmSxPJFKNqS?CX<2z(5_zjr*iULty0lg zU#q9hcHM?-+S$fZXkF=cYeMHxGXu1!!j=NwQ#sEc)v!i&dvPFOoG1ea|q7cv!Xiy$d z1o&Wwf^jy+u+>RN`}?VTbnGqanEA+zN@h`txCL|Se5tbHnQ}h-T6C!&1X2X=Inf&Q zJ8A#<^Yr5BlhoNgN>>uHZ1`DSlz?PgvK_kOE(C0GB7SW6sxPJX28VvvMPJId+Gt5ii;aq76iv~)kU;Mo z)K*ju$>D_NW>66nY?<%LI8z|~(>%!?#v*(8bsM=nlWkuE2iq|NvaSA4$R zNNAV_>nGFUmR*xD;&Vw2gpw>ET;y58xPx;YPcR7xj0s-(Q2|A4zFVMUpR4C zAut->*<7oeNE}V#n!84_xM!#dN@+#U>2;O-@bm975GUX!HxnL=m2rZq z94;(jaerCp%5AE97;_>o_hq@S$2ls4JPL~OK-uvGHc^pV2J;r_2`l;JTi`{sZpLsp zZ4v!B(+2@?0zvlU#gHAC@l()4W{L!v6fXVam;_|Ve*H%Z(q=~vu}~}KuGdFSFiXl% z0`pyIa2Y1}ayZa6G{w%2$gYG25Ek`87#?U-U-%;^XiskGw_pCgIDZJpjJylnWcS-h z(q|$~^zm2Y&&@OYc_}rT8)ENyZQt3kdv&Fu_eL!(=)DoogP>guTdv+L zpXONKujg6ZH_P!|n&G?P{IP-hw(I?NC~foo0QpSc88_iIY}^9y_5SMn+bB<;FRy@? z5c0Fo!Tfx8-e1=~x4|s-q?SAmc&Mj z%_{sxqsI4Y%YdBAOB|~{E+vQCD4ou8eIr30n(`A0kHum1eA)NZ%Zu4K?X&WDl=zR|9ycC(uH4~OZ?XGh+x zf-M-4q4)O=<0EyipL+c`{}`Q!ae*F%;j1d$0={^jV`$^tD<*M${@Eus%rgn`WIS?N z>(W1tj*ruqUwuuJq`&&b7wKo8-IsobUWV~v)pRk|3{TJek(}+}SXpv#*hx>H@2Tt^ z)8m6RXHv6mBp>IuH`mi&{Nm5kot+)AGM6|ri8`V(_*g$2Nav9LhCYKqYF*DxR`(2~ zTd@L#GTNY{Iyo5)W8#|V^ZfKjaFzX3bxHg3aU7!oI;OW1RDZw_6EYBeP&$NkAPlBV zh+I({U#fk3y`FTOQyT?#?rf*6t*x{yz3fb~{a|#O_V*85KMP8Wad9A?Y>W~w^iA|0 z^eFhE&(O-`#f~2E=kt@LORegnufjK5#<3L~?FnGOjme+tlggvssHUcL+=1Gc`e7v> zbkXrV0dgpP6MY$72O6qWm(_mUp(n;iCin??fxhRk4D@?edtu-~KSbY)=W9HJucUin zV4_bFj-GE?q7f^WLN5-ztr)$?UwP|K8k%tc!i1WMQYQ^Db;PGvPqzGY<t(NPP ze$!WdvJ$J=YWtyqad|i%y1l6Xx^(29|JfHB?`zT%hiR;ShVj>Ze5>tkMe9}R^y2;W zbd-9Xp3|}-Ydlc@8unG!aXufX6l3tj;=SEO*Cg z|G1x??Hzl2!%lDHtz7Tl+xGU2829<6!-Rv=lQY#b1~86FkOC~;(CN9?ImY2i@p{g7 zb*YNdit<@gei)b+7uCY*my8j{ABIW3JMg{X#AAsw!mD0grw69`j@nV}iII`MGtXAu z@{jc_!=R7h+-H=jyz~R!AqJHZoyMyL?GLGnK17{6$iD%+7H9ppK_Ok>n&C^ag>L8q zf^sA8Nn+%@muXF8?>|{6WqVC6tKOoOZiA?w&|!hs(3!xu)#rDiaSMnnDPPO!w87;M z%qiz`LBkI@`b`Nh6sKt;ANp+8$8s9~(zn$Ixq?Q}imzOmN+xOd4CLVJ0D0Y}sk!K{ zgz&-+e<=_CDV=z313dE$jx2Nl0wTq{-T^?w#F)5F?=~oO-Udn@x5I?zw}9aJU3hyv zyhK@z9DOI?U2>j0vwk4(R)-sF>wn9$lS0IYQa*AcY$K58i!fq&c!Ebq=g)4X#ZMd! zn`sq1Ih>hq6TJMF-Tp9an&u$Vf}iszEic`;>oPCd?eIuL0D>#`_)s6=g}?Fvx?I=F zH;Lzhgzm7c0#5UG&N*GiC2iysc(BbcdFszY*7-w2cUKX_Ox$;9DbnGQKY@YoaOcMZ z#<>$T69+#M5;1BJWE#TB>HSCkx(a?=@|s8Rz|UdXEe3Rl4dS`aq{W@DQV-L*lbiIU zg_iuvME9T*{=jz`p<(=)^b;KFM-MZ_aqd;M)ku{_-G&*jM$?1P58??Re1yQwLlUD9 z!VH2Q1{dnYhfXU#W`{`t)tyyYWqSnxp_Q>{p5+gDAXe#&`Vuy!)H2gf+)9{TO3PC2 z*t>m20;kW(s5f+HMzsVd2~;+U=)x$2!Gz+X6ft8CC5_^GYeVkhk=a!!A2!}es7Hn= z#tH;;ggz8;X4Apb$q41~L}iN^NPPYm*D4(^qx^7JU0@($7L;c~Nk~Ls#PC9WvxSMb zF;P9S7e8f(mXnJd{eU__skcleH-;szwnMofl0f2csnW=k_OKG7c{C`*uoCfkgl^w5@60QCnQ=#C}$!hZ;?96B8{*J3-t;3xVNFG^@fp7am; z9SVtZH9sgNt0;WByP}l>We(aXag@t_lXNKJq8UcFC>Q;Se3iSaAj(b;qnAKU09`6n z;e>f+qIg0vMwvK~0PX$A6-EN`Lm*#Ti9X5)1n12q-WTS?E3`z1T%bu=Jytz-gNA-1 z>p;Nk@VH7?xZUTKF8o~bm%9j-=Zby;M}Ho#5G7yZ!hY0!;OJK3a{5A-c+$r61Mf6k zNy0s$Jrn0L;t!m-&*MIKU4sj4=jkcMzZ-(Fiyd2KI?#`2x z5qS;AXyDi#I3+yZN7?T*+!?W%4skdM#R0E!-1;}6Q~Wos*)V9>9WBe<`OMNbJ;M3R zWp|hZ4b%E4<-I+;rhbg!KfrZIemR708X-<)7ir^1AO`J< zK=+qG%0W1}=WyH(E^b#kEfN8f`pI!o=4fZ!het<0vaJp&-*<;7YrKbD=eg_wa`W+N zVJWrNx6;R-{h6+xrO$u*m+9w!@i*z?&wr72?thZn8+THz(N0UNRpCn>nW;k{?$jsm z%;{h7TCQ({oA|d~e|k{r?)$l-jc$i&FYp>tf=&Dg;p z#-uNH9~fhVk<7_tDda@Xi9I`&P9nE;Y{_y=_+qjfy9XfuF+R~(I6G%$nK8}^l#_J0 zzn`AJ*!Rchp;v#1f62z@r=zqWo;uxL`rYroPQTHG@oQme)z63F5ZUs?dGisQkF@~u zFT8d-$7#?zPRr69m>`I;%rdd`Ayz}IDF0r6kT^4o57vCJUzHBVsx#zwwv7*6fYoWy zN~{vWKs4<2T?ZkLGg*zT5&Jd{kUv|EHQ9M0*N0cC=)y3>c7_$@!|Ida3Hl1#fuDM! z93P-rok4wZZW+eCqrBpV{LpV;g}UU!b6+?e8?P=?wN~|N9agT{kRpA9ywJP4$A_NW zczk%6_ILNZat~uu=eXllWj)og^)B@X+&#{H9u89vc>3b$KMfGM?E!k`-R8e8gB~!=iYwUMBoNl@A8`(FrRT zFBK*o6r(75dJ>(1#@VQ+ezKez>MM-1eT|zhzy8|W3eGQLw8xOCXUFlbaQm)%Z~Lmg z%IY=72Jx%Q^QocdjL-I~S5m7{%PVD9Tz{+i8JI5F?le}*RhH({>Jlq3=bUb%Sxt3? zv*Hq3_qS^4?p7;pu4z29SZP*IE%55guDAQ!Z5zQT6O*64QcTZ;Rrz@?sJPx@b%is| zDvPPQD&G0dqi6Ce=fjb|(r_kfv)NWX)ckG3eNSVX=V44vqyF8?-2ZdeH8_~|wR`&e zCNMjOUWOc}n`OQU^;e{M9jQMlxL(kiCUJef+zL1R6YsZI*evba;LTfn3Z#5p>L^KI z-Rvd~M;X^MkmskL$?CesR=6G^8hha;OhdxYKb~Uq^Os58-#E~K3_m!fyHJ?TDO{0S*EB*9VNfX4Bc$*;MJ}?+_Yc!NZiC=r!u=av z?;Bpq^G1hyDgF(v_f^}k0=7C_*jQil8DAmv#0Lcg2D@RaxOI17!F3S$qCz--f#x8f zJV5v>kYF(xY-I%a;@{{+zbnWx)6%V$V##3u@8OBB0@mMkR~A;p&7-7mx_3^Qjp7pqJr=X z4U{|fAjbfNLW|;I!-(i0)3dD!c)kGL5csJ)Zz-rUpon4sqYi9rV>`m-Rr77bj{ayP z6mi;-ts*g?m2D`v0`e9UD8DK<EW0vSo*vQ(EZoLbC#-wuyYBkDasi zj1=UPF-pmax7763h2~3rS3)+1FV2eKnp6LvPn0v)FnU?oCW+`V6ezpL7R-?sx#OnY zbt4{!|1u7>5q^qZ+@g{1F}C9}#w?xLE0>vYQx#7oE}m%_Pk*k{;-9(nbL~F4+>}#4 zS$TYrm43`Cd_voJ5uX{#S8PApFx+f zxa;B%eE!5*q{R(VyrYWW$@o>pDadtZztht@qim59oQQ{ppZ%aZKIg|@4s@#(zMU6w z!3(U=4uPj|;uRNE6f7Kh?K5rg`73n%m+`oSlm90;Byw5#EBE3qmvhXtXTr^&?vAmW zdW-utTw~;m_#8K>V}(z~mfXewPZy=NpK>}ZXa~#hU=e}>4`U@SG zQg{9)b)vt5YuXMsro;S>C&Y1?7&!P9XKpDQcsV@EkkY}?;h+2&U-5CS)Vk_}vw9X* zQ@y#FKKcCT>5HHKrLUj<`Cq3`zxeaCbN^9lwl{rd3m-Vy)=EFF)7*1s>T!BS#lJ1Q zYx*B2ynDUf28HJIayD-SCG8&uzCGvZQ$!v7+B3z4E$rXCvMlj75P9e~Cl7LxZIQ7g zQ(i7CrOx;)?H={h-ciqIPw{b@kI5Ku;-d~Sy6`32BYPpYBY$HQTa^xge2ZL+%!*9L zoj7m(SE*WF#3(|(KBHC7G@t z2gaY#pr4M8_=rE2j4YaZ#xg0365uHsR)LLX+r}VPyJ9$FGFyeSwe)<%7{#g(R(ZfbD|rCUeA+)a zOndtWsUseVXVnzCBgO>ICt`&fll~|(?^q@xvVEitTH=*eAFN_Wcf#Pr-Fk!FA+yq- z&^y?51Dz}Sl`i4Z6)=#}Q_-2Yv$Z*TVCZ~dT%-Q1XR5u>-!Lq=K9v`Jtj0vlM#F|I z@}W;qS8Ue?|L6tO6}oG^(e(Lr%d7NB&RkwGT{;QdQgTihTjiaO`)SlaR(p=T8gP4i z(|EKiJYa;wh!DoP=+pFd#-OTPVGc6Pj_1&cvJsW7?!_Mlu(E2*+tfiv1ZXe%1G<%d zT&Lb8Mfuamz|m+GRi2+1sPhrGpHk+bHn}icemKBcYVuA^_7>hCZ)YNVmZ7#$UYVW!3)FrFU;2Y!q83Hwi zHicn~rw+#B)AZZlewDuZ=4&5+P**qWP&c^9itoPhVhMLNIzu775!Aa zFupPVzS!GO`+K`-(CenG}CwQ(xU$YY1mGHI=SWTlQILjT%O@W?FAIQf+xb z&$w>t9UrE;p0zuhjZ{&U!(Y9+lp2-gR9{_4YxR}XmVZg%=X{^IJhPFlF66qNM@x(G z?V*EldZ04tk#)JaqIRSWS>dW@z4Ud?R7>j1l#g#js&$t$0EgN?|EjgGxo(3=(i<>4 zeu4&=y4=5V82`8@{f_vEx_14mfl}Bad&IM80c70OWj9&!HaqZW^n}*X9+KDQCejB z2NbOL2k)2qj}@lv_rrh zTe$EPZgWCZToGVTcAK{T$vggXcqyZCgGMP6fs=5h z!;q+gBMzqWK=WM6PSv9F}@AW%{7D4RBhh)&Gz zQlBG@F5=0XuoEc{?C;LjddzMh4tx|D&Y1FcQ+lW~!|V9)AaxIqQlEXiCG>?*k8wgm zKC8y0Kzr*z-7)%D2~s}H1S3C;S_sW>jxxy1L~o5DJcL(P^_Xv67+A!HjdTdoo^d9@ z8DaZe%5WIKP7`O5q5M!5s)L*N@n=<+Z~@pPoVuV*=2cf#z7%o^9SN`SfPwD+V(-6} zWKEJhPt1acdpP%Chb61ZEIwV+J0l~q0B&~Y1!nOIfZzf477(ey1zrMgfd_!#61#xR zqNlfubyX!fB)EGx4IY92@2_U=eokgqlFH2P>Q0OJ{Ik!9nwgrKnX0J~j?oAKELN@| zc=Bx_NO)(b8_F!0)I#GN0mx)F_zt+-r521cc|{3?Af$qbfreR@aIFkEFA7iQxHAEq zfd^Kcfpb=qQYaApkl+9v z8eb~Eti}y#g9EQPlmo{QUL!;c26X{0$!n=gCI$5JH&`~V1;>4i(k4BG1K`2Ny%WLDzAM>#Fk!8J#DTu`@yC7BKUtgLg9Ig=_}x{FZ9v6#vSv`sz{3@M+LoRlZp zSd=|Xq-(;DbVakyi1WakiBbN`A28zE0f1NH;HqzZ$xCm;zz=tP!F%)tJUA9R;b&px zMgC-yp9?#OX?uwySO1eZurtHPxBO$WD8mbZg)48H*>~6(55N!Keo9y# zgPQ-9Kv9Rh-*k`fnZMIp$PeMdHB9~vSlM6yWjr$kfLy;0d}rMKRBKmG9ipQRuE_!sHNKmXhG-UmNRyN}*VwR+c+FN6(j zfg|WbcH3rVk7vRg9-Lhw zOi=sIB=LbUsm#%3;{EjI1PCU1*-?S4L4O8M%Z>&nOW|$rAK3NJ?y%rF>HoZ&3B}cD zk}fZ4>mb@9HEjo9(@;q!xZaMTlT&asI#^NPdKFdd&9dp8n%ID8^K z17*iBZg3PKN;DJ*Bk`XDrG>(dqu1asuazfwnr^%0-Cw>37hYXu6H>%Ciw6@_a6}rG zvy^%G-;ha!JAKI0{Z__`)%E9wj5tH01OldC@Y%HmhjzBf7nc|RwuPP-L&^;Kke?v(Sa?FFsyPkCCap*1{7e(Dl}(y zaMX$4Xr^kt;d_ragm>zT46?h13Hf@BNx`ZWnw;{141%JB9dpnWi{X$3%wr%E=wbIA zw1ENyS_D6ggO<1C26-Z@fGGTYnuQ+n$l&Wmo5DXdiJXhPf`2)J4cbF?uuN;k*p(Mh zB0F&Oex+LRQFe_+%}N#SRD-5GVPC<$ZlxD+Nn^@UZkJcy)x~js$nEROI{HB-_}4l9 zPI4Z~yQ*-;y>iey^o%S^9SfLcJ<8y*$bDuQ#g@B$OdHgO$0!yDdb}#ZjjY)lTICO# z0 z7m}6ZG?z%bqIyC+JU|hChN7Cg%9m18b=Ph-jWCpOAmC1MrW1B_4N||~Pv^staD~!t z)%45Vef6!ncXl10oT$!Y7b%J`jvqu|-=v?SyebRzPya=q#NBc0n-#ZDc19k)I&h!W zQ9pq=cYAg1-ILStNOTbM2wcH1nQ%<#t=lnk0@TN?`jGx$m<|pOl!q%TtS&A_;So($l?G+*zo8g0Z1aJ5&F}0&Ln2yXMw1?b4^XpTr1%vRq;c)+#ZB)K8F)%Z8d)NXC#TBd-6a7>4H^sH! zjGCH5`s!w$-q$n4`~0}YH$uGjC0tM%=KL8`8I#y`{piuI#!Plc))kJ@J&50E`KgQN zXt!&rixPR0xhE9Yt7&JuYXv`Zp^X3ZnX#}{*wTNbUeeY7%&lM(gFT+vF3Ic<%@!E1 z#{o{H!<<<7DWp4Zd&^||Vl;gh?~qE%AK$OT|K`msW8a$v^KE1OO=HE^PPh9j3vl@f z#u&yMCMDY;kZi{}-1R_|`7wdYG2+eL8I(Oyg(u$;bLJn+keo=xK^FbW;}~=M;#+@= zAJ}JPEC;g5PfQAtB))o_7u;~f-4N_f2>UrpB#^`9IKT>c226+uYd69OhQsH0d`F=& zJX^z0?o5b#qBQ5DOa?lN-T3DZc-gLZ=?t8v-av@-U(bjC^0)r;TVY6N(NBNm8Jsy> z`E%HaXN&Wf-PO5~PuxoxvHKN2{sw6I<{fuW@x-@Hc?%A!3Hh@d@%7^9J?^BcsDnkp z5wtF!DLwAkROT?n7wke9ts!lG}52rC@y(~ zfgF!Useg7R#z~Bln7Ie}b94|pkYL_exy741o`6qROr9*%XkY z8&BW@!33p`@~k)b^bR&LwVd}3XpHlN&?Tl`nKHu;vq!?fjiWRq7z-x(#K7!=0}{jC z$75z1N!W&9cL!dp?8xCZF! zZu${y+_FRXMMmN~V!6mTy=HLZMV|9V$$xz7*RT0|Ha5tgSpIfc2X`1OydqoJv4p>W zvRi!5!_8rQ)^|MoIK2Mi-ZJu&)3CR`U1hix{PK$LnH?YzA*Wyb;tdelWRC~Od3gw< zcTOYROqO<=|6&};{t$?A3O|)dFA$)Axkp(PmiB_1<6^j*=`z{_}hkukg@Fjcpi*U>7 zw0HJbrT8M>eycn#(`Opo;Tz)UBX)K@dHenJ{*Ql|-uvL^=?6dhMSAD`pQJ~R-%j;5 z%C1eJhRH0bgs31l;FxCo=KI?;Q6vBIOyDkP`_pCoEVsYRxZ=J6^G)aLn=|AJ9_h1< zd};W9#t@g-<@vIvr0cgHj^E}OL6pVE=NIXZFOSptfD;77$LfJU=TwF`=6cDzF!!x8 znGf#?zj=Lq>7%c9cDGZr*;LaDeiQ!Ai@wC)att~O9PaxXa~zrAGSR+K*|72fxbU7V zfb%`I$QAm#)th7cn3RUj>h*eh`eZNd@3m9Cx|UWR?!1G8$=BoFFrD>>Lfwk`i-wQ# zV^LjC@(OZ`Phn747K@?K@Zz(q7~u%Boi56vn$lr`7nAsLA5^DROZ8ect&7)W(wXA` zk-6A$G@4Em_gJm2am3zMC;&2Y;ZI|{in`=`Rk9aK3HRVkq-P}&JB_?ERpGfah}uQL zP?em=4mx<^lhdA${sZTndcb5dJ5iW`zqn#o5V8S861+ILYVU-!dzZ3SCeQ!5e1qk(tq zT;^l^7{Y6+k8Zn}*rCXdCMG>mwjjSOuSovoI9<^P@W6+6HBtte5OSIFgNz8BDLK;z zbb1M#g7G) z(X5eMLqSOagZ5&f6!E@-==C+gwW_!9nv6OLv4`@jGD^xNP5KAjz(rVX`ejws~FPx>G3v)WTX1}@oI zdU$l=g{5x)YFBHyE}%W`7f0d6d`eyI1X||4ZSKmd*XqtUbwzvQ4m2NcSmFAImfC(L zUEiyHRpN-u%d6XTaNJ9S;ncgh#wsrh1kTiVDT}G8a?($)viMp32(%rFRCb8oxQ{$K zI!!NL9jDX&NPen+r56i_k-2ZJtlp}s|4|=?avC~D;ScU#y*x-SU%gV;d(o2MD{T}4 z>af$j+WE@Ty^mUCmm3m2ecpJ?k)!Iz(~XZ>tg4x#EZbbUPtDp!+U+*2TyE+?xroxP zW2M1X+SPl%BllWGZHQfdLga(;sIrnz$OoE%hRoCPp*9k)pgH;kIbrj+4RLZjEdJ$N zbr0PUoHz3pcm!n-iWt20#OHTnT&^!^obRt|+~K#)cNPM{t<*jEmOi?F; z>uGn7V{uzvG_t+ZRr_2`ql>FFy%Zm^y6y!ajMXd*nqJ-e-an2gg^X&At<>$dy)z8{ zz%y# z$3df?{VW>3Uh@y^DT-2Z)P7iLh zGEWd=cZ^8IN88vfr{%cC7l-(cN1sk6@-usYy%5$hbADutyz*OSHg^1 zS%W|zW(lT=)eR^>V4mpQVn@=A^9n2r2w4ay3<3fpE3Ob)hn(j!#Wm{J@RWEP0@+>0wEyfExPb_~IA!@LLZfX~1{K*HgMzx|SM^Z5OSr}Bkfiq|(Xdska2BAOP zDR00e8}e0LvK6$B4<62C5ehJYv(^yY?hF5|BZiHW%$~{x;6A+RiK9 z0Vlo#uC1u?$uw4iyZeazsj4GPHVPHSVFPA-XS-qLIN7g!`^_(Yz{X7vG_GXi z7HLK_yEtrolQMR~hcQg>s6Xm1-ne1Qp%u;PWEWD3G^2jPHDJ&3!I#4XY=8SLH@U~x zf=?upcN6K+kK0oC+5wzK1j6$~80=(zUTzuO953wg8Ez%d@eNSQQ@+bf?y@+q`R#NZ z-=Svtp_Jgv*@ceqjuaGD-x19&h7n$~?}C4OW{JmXIhjJt7aMWLh?=L;GyvQEJp3@3C#(}&A>>Q3?zO%cH^A5@76zu0x%jhG+ z=H<9{21dY%DESYE2oQM5;S5^HVMnoAkpEev#gO??-9((c7uf?rMDA@-7v|LU12ogcBoCHjN#o zFZ{wKzrQU5{BJvre=1YT_UZDO9>1}2LlBE;z4?3<^L65USB7$$_&>wY4-|S zCt1ZuUZ5mXTFpi?b=vICP(D^4($#d5dcE`1A5GHv_{x*Um)CcmVCHTdc-r&xo|P6L zjJ}hFW+=VL8~iYeFTPPAF|pfiw^OUtH4G-CnSk2eX{RTTc0EB$e2$1i$wj$FlemA1 z;~+8M6~3CX!E?Irh96V@8JLz=+09Z*%?{~wQoGwtjaDl)B-5cZtm|E=Zm4gQ+$3H% zlrmM}^Ddp7oTZm9kJ8EMsd@fJgWXEpMV8W~%EAt{TV#nF$tOzlPH{*ZT!!4Y>hRP* z@_;AVs4wCQS19y4otBkAC~JK5;XM=P;?Ge~2{y+`f=I$sw{dS5i{UuF65gGKYr?7O zka{F|S!}0>`X;v_Lm)@_#0m`pC_vaX=2I>dmU!L?r@V)vNck6?pd>_j<8i#;mG*&M zPsm{6#Yj*8YwMv{q&(!4BjGqQo?S#JL)po9aXB?zGLb*@9cJfgG8vghQ8gi#VW6YQ zXkc7ycROjj(_*#i z9Mhh{AwPo~^A?m%Z^}k@V7^oa{JKsBCyo?kF2If6<12O)VML-#DDcPwCxQ^K^atQC z7MvDbD&MLjpQfRBw8dC(DxfmHCV=*o>l$P*NlRRekGogB0Vj_8**F{;?kOTVe#BZ zu4Gpf3aXCU8b=uVbP}b7lAWDckRs;l(X8l@#YVAfaaHYk;>QYa)fsg7AV0Sw zwH+qxIUbQ`S$W~Ww`N25Q=O{ntt5vKSv0V|zLY8(N?&6>&*xFpo7H-kM5K84X$XpgbA#ZIeq0k62&cB7W)Vw zG75IE>#(Aa;Klh4nHcxd&tTktIeZxNIwg^>VIqakGwQ=gPi?#8(|KQA@q!uiAZo9i z@N@xRAU77K+^G*a8(gHxwc6OS+Lma3pt1hr!_#y&x>6YwpIyc3!F*HgP$OC5zFe5YMck9IZ2=*{#acki(S zoNjz|mAO;(1FAR1@y!hu9W14tZqrBZvLmy*-PBk>pT#(od^9ol_OUx{73G-n8@tND zP_7N?NZ2uL;O{!4F8%)vnr{}`zZ3&jKJR(c*xmK@+5TU~p!iz)>5qO4s}Ke%cH4D$0@7`<^)nCN!0|15#>p4$p+1{XRs8cu|m$G}!%@x7P@aOC@%{4U{T?5Xgx zuqB7D8@%VP`Kth#!3YQYx(?@Qm7;<6l2(owRvFv$Q*z+W0Y_kC$-!O9Hv!_O9>uQN z2~)mNb~;LSvwL~t?=Knp9Yv;dvakN{^xQMyFJ__pcrVq|LEeB%^=dH21oBEaGX$(I zh-3L+0${=sMoZJOqN-BO$T+snV>c{kPvrPu_jU!l+kI=<)H0nF;o)E8!4I zF>|kc5Z|lxfTKjN#CRfD6UU6F$_Ar>VheomAh=NVijwms=1k#X`YAR$;$UJqVj)&~ zZmK*e`4A>pF?sD>awscf<=mC(J>nx&A)p{=aMS}wS#n%QLrgt_lvmIRXI^b5KcoQU z7MMm_PaJQ-L_`Q(-j%0#4Di$eJL>3}7=T?@-~@asE;unT<(pM}J{m)Uo&{5t5t=}7 zLOSDE%Ik~kbbflC&d-MFYI5m2zPPxX!G5zYrdUs{UbP^*EM~zI3@RV=;CtNI1*Zn~ zaIZSjJ3G$&72f@+UHDZvz71UUKp=VHYyYqmFmjTO4^YKt zIL0r7pCc#@v{4G{Fhs#waSA*v*zuqJ%sj~t?}E9UM}ONJFaGsVhk6s;e#H`DZOu?h z#BiH|nI-FQf5;a9kq~32!p>6U$3{7&Uz!2oH{11JvW*MI5U6|m z8+dl(Q?{Hj$8qEWB%t2QUNGj6_9iq&K5_`(Foxsz+$C)B8!-dgqCHG;A#{OV;OU($ z5h@H#UFe7~`iXM!5#ea@yeS)b$G8k(bsDViehm-yiTH+>-Iob#eBhDsf!!vT$$6fa zX_hD1v&+ne)sTr(;AT5M@$G-7hhU(b>d&zZmq6@REOp{v{RD(;fG4>5<5OYDvtc^j za4&740I^R7Q^5V^_rHq>-;K#R`TAy|I5PUuShlJ$X=9_7DqFR*z4OR-bhTUT8tA0D zc#G9_j?L1ztA`yOj+yb~KGyi46AQ@T62~P8sNj>D;_oj*RKSeqvy9UJ3sd;sd>(GY zM7_dad>KPs{L|IPn)?q6i!*(#fyU=ZzulNv6?W4$~) zO`p6vNz>~G@mMWSLJ!Udsdw7*;4+|krb2J+`Cgr94p4Ijo>p^(iN+rr_-3Y zMz*-Pw1TN99yoIFT=D}vFL|k1+0*a@H%h3{U|?kgd}5^zwY&g$xhc-Cra zY^|qF@qV}W9L;{2Ml6)NyjFT;2g1FTc0y1(@1GeayeB-Td2gW&+`*e7A9;}+iU56s zmYtn$>Td5@W`WKg#A83&ZKn_3eU_TyKarJ~@TyhW)$@=(`uJ7)(}yp_J2MG(pDvVF zlrijN<2W)_g)^DY*a%;aGKpO{?4oMa^+=9uHEOB4vF7xvRVII9*VP3R%gT4NzLjnj z_xbae>E)|KmzSfM-hTEdJ>J{)B1mw`&O4Nj1Mb|pyiM1V_t1eM_n~lLhZA)L4w#%{ zV$90P;aKEwm$o??P3~5liT>cv*H<2rLP-YU*f-%A<>ZxQ2FVIc{*T93mOD5e5R&Ei z`=MkyFM1Ol!$Sgxz8ZcBT*qQX(Lb^QSk`!o!Uo0H1_}-RAzOL!eQni~{V1J~O_9Zr z3%M8B3OB(8K4s#bVB9~ z4p|FaP#26x)D7ub;Y3+Pt0)gC2X=4@o{*_xfgq=|#Br32dp?;%@>wXOnG0Z-SM0JQ zo|S#_hvta`?%_K&H)yw8Zp+}V^pdyA3wWYEBFp(i71^!K)SHo%@_?J*<>Ku=OL?Fi z&;zn1N;dpZB2&Lab3LOpRy_I&@`$2{`2!TOmfh9nnAAnyrQcc6*v}3o>ZDRxPrKVK z?}U7~yG|APx73Hw-hg#|O`B6cbb%sVv^eNX=D$c=n=5X^KY07G@BbRApBY(+)fZi> zk5aqX63ogPO5qjn41~{Ma-2589+4_af6>alm3VrTN7_1l56G=^ENHFfatF#yJa^QeOCW`lnxG$+-B=;^O9>TTj^T#7k3ZddXkzu{(k!YJL$c*_tVYg zNOi1q*qx|)hTc&6a~va*1@-*=<#9SyAB*y+Az67}{TaIvpt8C-9(jr41h+ zous4FGvV{W_=Jv7PPLoWba&11h$-#ubkq-Ry8W>u6~d%$O>^p3Dd%ZF+7NA+9dOG_ zcb+#28Wye44~izBd=@p3C-97-m!Xh)o9Lk&J9?TEMB4qk!`UzEqyzVS?(7))V$GbK4 zO@D#(V|V%&ML@ZHuYTUAwHUr$GVGKD9yGh8G>J(*_?s)<^aZSWw6A6qmw5Drq=kbQ zS7X!Le3bIZ4zBCmP8ml~c-@E|>6@08R?|Sd!==Uyjx_Zm2DPsv^$kbIJ&oHakHE#P zXiK!Ga_y<#f9LUT(y;ACIP@>@C0_VV-z7R@Aq{;B{1mxlGXRT;P?pjD*et-wM(_pX zle!>(l!?0Felg}ZPt`WTFJ)j#hPH8hawdKOrSF!NY3y91A7vhno#LJgR6F4Q(8~*s z1HQK#{WI-nG`aFF+L79ekF*wQ+^@qI(wnF*8C$wmTK}pT z`@jBQ{*OybKmYMhRnJ8<=2!2P6om?Sdr*Fy8wBX?|` zNYZ=eg^?W?M8z58I>$LL5f)E-UXJ_DwssynfB2|W+PZ+u~7v!j0O z7#$*F#J%2|4GDky+i62WAnXnuo{z>*aF|q9^l;Y~N*Io_F!LZr{aOqMj5GI8v6}`# zfG`~E0CNoUO@auG4G9Z$pfIMKa}5)55A!RbZ_qza=f@{$;4`DS--~1H5ab%EF2SkF zg~zP+fw59Y8|R60_f+g`LfAyHg%EKIlP~78e|D12j*in%ZxmCkx;Wh5#jSj46qx5%J0Enb_NNUuc4Sd46D&VF-#_%zL_2dbHQ8{ zBfS0iQF`>21YQk3pG9zHASYianyhS681m;GQ}Td01a=4%3@kA~ zdj*~bKf*X}G*s6I49SDwUsoYkPVW3iL!f z5W@fyK=~IHhA>|6LVHpbW3T%@K2(z(J-2)epgd zkpJ!B@`P3I$cIfh%>3T`=50G=C3AWkcK+pEaI}C7f7@T*kr!KL?h(hfaQElJH&*=w z9%c^lDxU%pn98Mb9jgd#ZVmBpe+e4;AZfw_ONkdjt>foR`@zZw$W0 zlzad{pT(=#an?KF>7D)Yj^s0aD-ivM%L)#2r~sia9C#U){^)ca2cuuy@szy?K;gTP zpsc`(P?76MTi+D7%uoPu?g?|=%?_IbNJyNAO2EU1kk9%@W3l#xn6Uc zGrtVWMzChE{gcwKfA`y&_jh0lD!!)4nHC06W^Gn$X{+8&dyk){r%&Ea&30G(LnCd~ zn1HV+w8j^Z!T+q3VF71821G>QRjZg8&E!zv%Wm;E1M#&CkiV$-)a+-OFN?OnEQkNH zjcU+s=*!{~^G}D*H**-i!;-NtKbV=o-c7ei}Bj->muZbsQ5!6V0 zKa+`P{Yg3oe-fvJhGD6Y}s{wcvw8k6xj9UUH8Syr!A(%#;7YIa)U zOPL^#Bg58K9#T!bAK|Z%9j;KmjMHc|Qc>Yy;YXR+QW+(i49?Hp(S@_7Yy6$Q+OrowIdh{a}g)02-J2gxe$jm=f_>nJr) z^WWWY+QvmXI_Z02czb6%J>Ko6hVYLPg|z_4AWW_u9{19#!;^G*BVJqGBJvRRM_GB8 zoZ~(c?l(d~bSYYpxRyH2y5xcl?_?pLC?YtHtWjC^_wC(^C-d1M!h$sL-xvM3yvhg1 z#36tAXv*oOcaxwvp#Ec*(~9y4Ns9khJ)i_(Ap`Y69hBoUkxk&An50K(3LOp3`+DDc zR~*MtVvq>EyGS&P{KgTP-fg9PS+S-12A?Q+TD^^CGo}5_u@px}1z4c@-)$5`WrL$hCnl@e@oTQVJp7G;d zSSka@Ml$hg#TR82oq;!$Nlg4xW|T|hZ8~9>C5o@uX^Dcs@|O&K28u7}0-29GM|Pu~ zA^$OnyS`D4aw|Wp>#N2Iiyo1`QRE_GfY;5<>P!x#Jt8l11Q&`o9>N2cHVfWpo0gT8 zZ+IXkn`u|(heUUbuSA$Fj8t6k&crWySzeK>CORN(A1Nw-a7{TlX6(_UJuA|2hxRYk z?zszVqA*N8)0;rM?2zDosLjo_)UMTiR2gabh<%N}<7rInLdVFoYCLIk?ICp=mGpFf z+saC45QXubWJQ!v)CJ1TP0_qS8=e5F9z?6^KiF-t#C$`pmrKz%h(uvWufvWhlv~Tt zH1jdbtLc1nkzTwwG%cXC*--xr&qEu5{!qMKTuj{e#ICI^_tVe{?S$Tl@1^>1l&{PIaVI1M=J7=BoAyKA zPFawlHwrdruP5n3iZU(j@X%giiT6g~r!S^-o*o6TmYQ zMqC%eysPKyP^_y>fHSV8p*}bPYp6C!d+4eSv6Bm0W&sJ;+<<$=sPk-uoQJpcM`-``HN;O9yehCw< z@ugq)I^ke9d+W#btnen9Xz(^}xY1yXTXb%YB_fY^F%cV=9A75fa=7dTg8;+=D<>O9 zcDv{A$P>;vfAWiRk)ue>U$cDa&EyWza(Dx!?D{q|St&B!v;GSYV4FFU-QV_!5B<|A zgQYR}iUxlxk^)g;ia25;c6nK-6FeAY7(Jict$__D5*mQngPA3L7+2C}fW6bZSUYt#5ZztJ5}9Nm)6j0s-?{3^VZ9{_9I_ z!54W_KF6bB>Yp5^!P!~5QF;ur>#GQ)>Uh1Qiw;;}^)N;nXJJvEm4+Bp{s3tvNiZ24 zZY7K=su`+#1{gjRrgRckGU)$Kg9G^H10@QOm&9B*w%ciY|8d%3hh4j228*970B45iSJ=0c0oOqMPg`*F2Hiuw{fq2;1dm?`)r0GYkihIQGug zut)fLYD$T|%kdPDEaMizK#YycCGQ;Fc1!_1H{gKW6Ih=HOa0=mZ#VJ9SlQ9!~anido{9c*Wv6%pNm8nK#q&H*mmtMvC42V~^MH

    6h zU%ZSbxkVV26}#T?D@VhQ;22{2V+JCABMh---Zr+s;ovOH9OkA3v%fz0w#nZ%vWI_3 zYay@L?9UH@ z9{pX?h@;Il*yvt%)W=8(2 z60~cLRBv|D_RfBK{N$a~-rh@%R>zZdOvGvQa#$XNStyz!E{;$1-E1=wkXoYCFx zc$G4f+b^EKw4#cgNRRfqzQc>j^TG7mI{`RSYw7Mr{P1ns*sMyPNS?4nQNZFXCiCE* z$uo>5%8%)EBG?n*ktw<`?w^nckavVrWD_e8;Ik!bkf!h2f`?N)_}+G_ox0st+TZP@ zo!wpIc9|8~mGzJ{By&u}yPoz3l2w*`ToNgwOrVyKvsSqqNH|7;fD(e!KS&n^)H_d~ zq)k=BxnwIG%8TH^2RD8Vp8~%NokdigCq)xxKwz@zRpbR6fFkFZgD5n6c;%+3`wz_i6v!yXBtl zchV2v*|(f#WtRAB-+LmOnOxm^_X_1?2M$Lf-ip5;4moD+I^CXA<-QXfBgqH(R^-A3HE^vXMWt|hOmr%jG9T;KG4Y=eF;U0qBpd!t-wHCt9B zke-iO6y35j4dQ_wE24LB5?uqd8!{n%1@ansq+LPV?lFX8=o)--bRun;wtxbeqvvP~ zD7mUzH6P^<9T1kCQ*E_vlskRVBD+4}p{}Us(O7ul9_~0I)H1Kq2j}!tMRo)iWIXOL zW8z#bL3Khom{>;PLEfs>s&{lF8)BdvcFna!*Bldu9Dj4c-GC^|mYx3T*_jnQ+_{Ew zhj|s0n(RE~C_ofy(87)SAx;EfAt|(j@~Bo>Nwv*YD|@-mi~IvO6pE5{m4C_$J)$h4 ze?l?M3P?Sye1P1hf;@hN9QBcyHD9s9_aho{X)A%p^g%e zy5V65*Sg%cYN|W#2}Dr{E(LF(wuH!!xXPH*YE)8VYs2>rtqT9N&+F@Z_m$)aIwc=! ztm$To(rxPg2UxU0>Y$^x2EN#3OFzsw)gMmM!NFnBx9S^ZHcAP0AaiFUl6ioPFQ9@;T89PDahVMoEEM_KX%0;xN}W3CQ= zc0Yxj!J{B5)-}4DRX%Bb$ zxVXAYQ;o~)K1SI%nX;%L6x8(h+_A^F9rJX6it(-~+H5sBK9q5qwnY5P^q@L-U!w4g z3y_A(2X2%Hc{o4D2zfM6@NS#jG%g6f=hgJAtyg>u`dEF)%d>&Ik1rW@eu_%c$vXgOrJ+2~&MG!1T z4?YF{YCN3!7-Y)D{2qKkT+O0yrOVtayP!uJk6GmOp!oEco-Y%Qm{-MpEFNomp>#FA zKd1q0tciD#2*!Nr_>vvuEF_6t+4TLiBk#Wavj+dq3zO^YbIlj||2f#-n=fmA^?&|9 zEG_-wXFsFQ5z5`|821)N;y)XZO{c<}1{TP7M?@g~5Iei#pwM#wxw*!#2-}K{;+c)V zW{tUg`^zR$4ojpN!QC&&V&;clL!D*Gmvcp0v|{2IeniI4U37uRx4p<8rNJfV)Be12 zDV=D>NBoDuIfun9LWjc~AGrA|`^d!^&L0>7G4u?q{020>a^PZBULwc&)3)qM-3Wg8 z%8h@0h%X2i$`ZDCxolW+O8y~C`18AnlY);ZXa3cX2O;ATfB)NfcV7-`u=;WR;fVp3 zK42QX3rXL15^^f7dTMf(z9gkfF{miOPyzspL2uP7D>NX82I#PXNvFxSUc*#JcqQf) z1_b62CIf#uK^Os6)WIl_E(`=6F-i%}!yc8U`k> znvjwFnbuW?rUcz5?>tNGoozB}22Rxxc>$j=_WUUy+!Mg6F9sHvGIrnHi^$kcZ(Qs*mq^uNSpyi0eDKKPUOkf;fb}63~j;ep?118)%&6JLX9{G7< zSwy-F`h*k5ReHFQ7K{voH9|h+@WhAm61(3ZZgMQf0=$bZFU2^G#fT3i+)u=S+=y8L zPfLPRsja7)mvxFxvLw};@#;k_x#7kKKSP?)cD|rAte;gui+!x7sFxkcMeAQ z*ZgH>-?CtL22(^N=}w zd52TrvUtow6q7yUUtduNJd2_5<2U>jPPmSK2Im}K_J8=zZx*9{+a|L0nTDJ~^Uk2Z z8Aw+(7S`$w3Es8TXtvYSXYZ!{M^EL}Qa@go&{x zoFn(t`J}atHSfl1)hmf3@EVP+^yu+pw_PT_IA-cx{97Ldka*LWG{5wOIg`BfvE;3x zeCFDsl@&l7#EM8dMl$^M-mb#s8stR8$u!IIU(hquJhYJ(vDAHm# z027+x4)jnz(1aDLR%UVEPt9_Wk0X=}#C^n!*LBG|+&jjRO%vtQM@BOF=Y?@G@yvn= zPAehr$biVIO!#s9846X7Y-fj1OY$w_5VFWXv^p9OO$$ssmPLBBHRy%%Fo8*276&57 z?n)lysJWZVYwwg`(!JmBS((;o*3;hOeJgWO7M-4POcshWCYd+VR=sHj&e7p3(E@i` zUpp<|?WG6WBws8NMScqT>Rx^*%}_ANPi04$L|7(W!4+;rCbN7de+=!3^3dk&r!sMz z9UTcf5Kw+?iPkBX`wW$(tv20lx9D)Jzzn6OXjig1%4^C=-n=7CX<9zi!}qo7gq?O? zjH&q1ry(ahJIXV=l{jKivZuhtT1{ zK^ln;M4pCC-q|^dqJ(zHPKeQ1?L_?tv{4gXG}UKurw$4g%FFyi47KpS!n4vpJUmJt zee~RP-)uF~QuO;9JJZflb&$}PPzB*;}@^e%R{w4 z;f~2^j&r3xrt$-i?5Oo_G!=j{vw)Ml!-lf3m3|0C9t)qTyH2~NesSN*cII8K1c%+M z%ni`LktVR7?YGmD$9t)@y`AdqwyJu?b>>rGln&zqWv0L9ItCQ}?!V;bUBSW+$1T!^ znP2hlT9iH-7mO|$`V`MG$PEPs{60I_s2>(BbDUsX_^8)YJM*A56koOaminA}IzBsBzjl(^z87)J{8*fFqrOVt93M+L z86TlZXai+F^e|NaO1kWHTTutjA`0f9!1ZX1Vt3-UR;|?CUx5d91W||F%hkvyCw?(s5{odHTZ*>J0%z`8 z)3@3x-_$!w6rXUQZ*ax9$f6VPgcBWb2NgS2sWXlVeYm?x9GADd-PU-vo*Eig=mY7G zP)ea3R-&qd2iGHh^n+_c3T49kN_{iCCr4a8p?J_Sryel|&<==CnN)m@&0LwG{!%nN zL7}C5QLpq5)9HnbdA6B`Vd!P(08*C2IUuuJd|waON2{$1Lkq`ue>d* zy|FV*Sx{5g;&{kD6)2eNyz3pb&-)^KwyDcxqVQ~n%=(t;}UfWP!*$t|;sXVa2 zpDRe$zsG$Li$Yk?@E|#yom~@+R~L+z!cRr{S`q#!7rVdU-B<|KI~T7d z`rhd@(+}R>Pum&?j{C#(;?mjNlTkt2M`$jPyRH@%Nz5i8^S*}?4nD%L@!rj$VN|L6AXe^X6wuG`JVX& zBwQRK&eDsJB~#frmiz#1XW$S&cb@U!7LoF+IM3c#)z>KRktW}UEt4TQP^3c$=gdBY zh)JVxDdD3WIOE6nVjPUVG4QLf#D#(7EMgcLXr}C7BX0;czyJrFGi>39e5hVoC8r=}>d6a+V=GAy zLB{bEfOfztBb2SId_nl7tdqgm_k4}dv*JsC(9A|nj2ZVki1Fgs1Xhv3PlGuq=y4{x}g2zX%$i0>W!%3|n-r;$@JLzKRH)*^~%)EEt>}J;#}u9Nzx?K?_dT zko}JE3xLDxQ)wEu{USiXv~{6O*;{6YM!UraAPMHO=Qt&N!JTz15lGKG&@8w5jJ!qO z?dqtG6jkYH{MaQN{L&Bq_OhqLEoFq`;xP#0m)roD;gs=vRye}QTB6JxOpiRuUG^)u zUc~yRO-^G552Fvc71|_e{6iO|ADX~x5$qAh1tkFX{3$EJqfX}Wg6@GBxW?|h;_Ni^ z_$TsD9XNIYAus0#*mev^yk8sFDMQXkIAsrq_iJWKw1TsF_(j+Y?S(f%7GU5&8GtaW z7G9>oNE5#Z7%vRthu?Z|iWDPc(63y=V`g&HnJHe2!GK%JV;{d}rLj|~Cw^To`v3di z{_|0M#iKrbZ6np2-PCMvr|sSS^yJxFsk^=F$rV;Lv-pLHSC?1=9r$O+9zborjDA8xY zi#lJDF-VV{I2@ZuKf%r>m<{5MC>v2cu?Ybd@rs{QojD7||5Jbm)V|HZFNRN><7IcD!FjfCT^t-A5bD*j59+UebQ zf9P^DS?E>%EILyj5W8;R1w@ySGWE$MJoU}Q8H?h)2u^=Y6hjjnTZi0=yvo8rXk=}5 zNpvBascv~vkljV3&(Taw%(AG`?pLf_zp!!vdDTbW%Mbct*W8_CF(&(2l!@HT4oB`z zW(STZRyEF`7(fZJxw)=tVsRqMFXcsT1x}RvuXnoJma)JsJHb#2^}SPT>VPqsU=Gmv%-!g=_~6aKxq} zSb>Q`gPl4)K2mJ}`IbAdwuC?KuNhB9%ExWcmuL!wi|?gVK9MPD+uk8|a^i_y%fbw+ z$^iWk?HicBNJHFFo8`SL%ZDf z_4Lthda}Q5B?db)P!OT$U?(ODcNW2_#@zmCn>(UG79>+2C`Z7v7mA_)laN52LK`fm zjon+ZOAnlpKa^IF_O^u&%602qG0Y`$#~(WaY0KQ7SKHcf_~YJr8mhkrN9(Ew?_Awc ze=a!dE22MW_3~PM0?H@RC4GcwhB*Q6u2NmJ1rHhjg83=6OOCPSgqL==ZM?9<2-<0= zT%joMBUO(!8Pz{AMCKCu36APTW9Aa?IPyRVh0{GCqk2G zGwzr}vCDi6%1n;Hg+`gf@eWM^pIqFeD>Vm{h2V!YfQ?K*pTfPCD4cv0B|RVQ2*AQC zX`=X|&RJjqo`zH5UihhQq7-Ej^mS@&t*6}KaG3HJ+}izNvHQk2Xo)sRrP3DSKYbQP+5>Pql{_?@14uo=&gRp?C*&+tDuAmFa$4 zfl-pt<~aJ5vZ8E*rY;qagOE4kF<7{i9f5q-C7 z8)>&wQy;E=LhTWHgul9{uT#4Y1r}o?RlE3AOoC5Ml^I<)@7k%_#}orPQE zE6i*)aekGke#6AP;e;s@M8#yV*z~6l*`x7BEFbX@-Y%Ove}~my4(t2_hnG1Pz2$~8 zkpj}(&365QL;K?{Yq%Hl`d2Y?xc-#!R~YKBxMvH$3n6TZo81fYhxCoRZGQ^N59`uMnup_2@t6uj2%nBGY$YOl3v%Q|nr~9X8X{12~VIX!9DxV5h z(Lm7x`P=F$o7JuAhO50q?|lQ_5kTAePPI7}yu zEleflgE8@TUh*b*K*6ABK$xXG2owlIC{%pkm&!+|`^Xq8kj{76yg; zdsb4xJS@9xhO7Kpa1ksn7oSeYrjd%^z!Z746+(%^383qnx@UzV^yA49g`o{pH&~Up zW;}U!mj*_JPVUJfFBlkcm>dKd24k2N@B;G)^Nx}cSmet%1is$ng+Fl2H$pc|4}vL7 zIp7g4VpXZ~t#pA25R|hBK5ME&5C+VfO9=<(!_+(Or*U5lj06h$v^CNC+NPKSJ)0F6 zA_>;YC-h34Ahftw5hEl1T8xEggHBHA3vKpu9m6sBJL=lCt#7YHbZ_&sr+N8U~PtMSQ*RA^zewKV=*!20!<;AY1|R%O-*bg%((!HW4A`IDhe1g6H21 zpeP#nnwyAaQ#>M?&0;=^dnrZ+XZP@TZ!Z%8$QOtKHMpRpK>@j#4)JF2um>Q+c0hj< zMs9YL0}*&-n)YW7mjNhdD5+7Tg$rY8xDjiP>%bT9z#|6FOdN(C?j(;Z!xU*69`F2Z zki`MJto)GgP`c_!Xw2sI!uT5(+7&L|QK)zDYXPdz8>WPf27#+x z?4KcrT^|`e_Ap(_fjs~HZ+=~Zeix?XLZ&23iB{68#u_F zM?cMq@8IX6FdnP;QXfHCXj2%*#YKaEF~Li|Zh-M-Kl*h|sm{+crJBFGaW3=oStjFU zhSTrOXPKzyuU!e>sQD&nuD~d?UyR3wSy|OKvK&+vsJOe}p}!F?w8^dzjxJgk?;{`h zQAlab1ncn9$K;KtH;H?q*vY{pIlLG=9K5Ml#*24@SA>VV@X=@!^Pn8P#gTBVIKR3W zr<0>k($01#{p4pq6A#u*&tD$;4i)Z_V6q-Q?^e7qaeX|F>?oe#D>*_8B^6}@J`-_X z8Lhm-dosbx>SreUm?T88advu|jt^d02?xtd!8k&kg;h)z)|+)tE-~@OPKq+Q%rSzP z;qcr$bda&=KZ;yb417F_FEEOXN@A2dG|e)GHEr@co{(%<~@Z+*Xzh)AeGHo5n% z5tO1n>QCu#G6^(6Js^X)9)(NDoQX|j6qKLTJM_i`dXL>y7n9WOG}GSBwpY+Yt1Mc) zx+RTE$)pqCA$NFqkj~C}R(iy}C?T5_#mB8rI=Qx7iee#@KTI6Q-E`0Z^b3u!3xtVB z+8A--bPn#&URND9QoGsIyRPCcSuqOj_XmSC5Z)Et3bIH0kJ9$;uH~P&E1UMlLcv?n z^2oahz&mYWL->iET^nxC7!($SL2hFR^eG~OMW#6MgNc6QLh!unM=~?JGvhd{nE0pt zvFMUE9rB*~54|W83ni}=o|8(D|Da>ypzN({%x34KWm=^{omn1Ky@I#66Ko^!s=CxG zaqlv+-&kcsX$~U57wwvQCLHxbT5e+==gE`Cb>$B}q3h!$+e)8ZVbtB4l>o@h+)smI z5gJCOW}=+>1Gmrt$9DNBOoavh$;pZOO7&lAhseg~{l1mI&LK zSDujqMjAs-P8C=EL{)tx{T<4U%Uk9*P(*ROtz>xhyBxP$S6{v^MtDvA=JE4>gN5*>B-ukL1`JpM=vfGgQGh}?`U6{!C zq6pCs^vZqg%n4D)j4zxNM7^Rkf(zw@A^K&?O?!&@m}T#xVY0uj_Rh{A=>M#LE|^QA zQFe!^O+p8%8|GjxZ`9^EidVP^UJ->8b5@d6lsEbYc4cy8EMuFG307WLb6fE}o60XZ zJUu(txIOVVw2B+_z0;|sXS>3a$`<{>z3_FJhN7>j(q)GlyGhx3$4=sUMYtOFJ;w%~ znA2gLSXVx2-_#v=;)qIL{~?UHKTvw$i?W>d28knX_a5!KFD4ATu^6L>!ab49`EWch zJMWOO?^RyfwUSK3^HDlGK1+SIJrwI(^sn?EB3RlS_kgk38U;B0ANfQ1M$1DHH6E*< zSNWLx>$EwVcFT%EluR2N;$0MIYPA7Wu=gbW~PwL;s7CkNds2_l{$II~qsX zLAKke8^??dqQ4Gp;;*+`DI`doZH5agbI2p8@=t9Ctmzn{KD8htYHWv2P?1? zFJfW>_B=EJNlVu374hOdizY*uaEidZ`Q~AIcMd==8~oo)Ie(ESSxY>J;y;7H%<@1? z@;LLrk2u9Y8++@AhOuBbqvI5mnmgBs=lFUI$seU;eCRWW#Sk~=GMgxS`L&B)5i?wz zhAn!s$IL&6b^h(oPZ-Kpz9K4ED!G~){CLb$Dh{s*iM#&PVa6nOhAEGdjN$5oNii5J z{G$9h5bm-vhQ@d+X6G0E5c-12}KF5xKdsjw3UDgiSp|v-DvQ<)If;feJy4l#++mR=)e(n7-(TK z8R$qim}hVf)`e{0EmrA)vDnhhx#nITCUXZI<%4{IR~Q}Br2eAzvMv`4cOJWB0 z-hP%Izx7OvxddrYsDv5xeO9mRFyQ3J_3vcJjl6_=>K}s;2BXDjR@2}E?Xh|XI2%d} zCICmu%D}s%ft6iK3qUYSCfm7apg2xBTQ$~!Cnlqbq>CRL0a zN6jESl)Jc0qY6a*=@G7Ht_@FhyYdSGepJ~IwG z$7KFXJTCa+LiE?O{DkD8~Q&?f&Zy=M2Hb0I*_1$+Kw1X@n;Wu7-cw0blJRg zD6hO2>`uHdlUriwSS>vmU-@pRiQe$^-i?3DBv|l!R(y$fV{#2nnAP#qi?R5&rPOAp zjrjSkjrFvoI3IoZ`@~%#zxX$Qlh!I*>E)}VbaplrAIn4{Clp-xf#+u;7JiQjG_OG3 zWLE<_J+eHI-Qf?hv*QH$g;nZ%J9WtqHQz6B$mR1K8z&irNkSi6C^Uc(CZU<2V&d_< zf9{C??Kh0h<+H3P8RIW4T5J;uHg~*cLv))!w7M zw7<9KNmLdOQcEZS*hN4(r>DoBEZ^ohdZo=o<#2GGM*Y)-!s*?2pT%)c%G;wSPtt~P z$O1MLJ%nZF8@TWUtP05SX_fVrw9{^QrTp`cK2HDh|M$P7^YecC`H$X9zx>6IQngx7 z%yzkgdY&^vEE^-i;E(Z_Fp`~Z?Zk3R5GV=t9v zUo@0fH?2J5h`(-U+qASHd5RrbUUVti1b=0h*;(&g@?q>qK-NP(<*ps>K&eZXWY-!; zd{GaaFv7S(I20ey^l*qw%g&Ce6-u0HVg-WhT!ni;DI0PP$_G#2sd<5aCZ%a>$aK^_ z{x#*x6Z^tDN+@Ux8Jk6$9Lf3a+ixlFn^ssNXCm94_4;Wz8v33W+GDfTl1#mu;YhYp zTSNB6lu2dA!)Svjhi+Xy+671AajevcV-Y0-QWoz-S&t*>8ud7)5ZWtB7zzr_kY8}Z zq%v_(D1rkf#8D7KtN2}CajYD?RVd5ug=-oDN)D8_HPszy(Pp4aeaSI%$n@;) z>h%Y%zv*~nMIF~jP)8^!!4pR_BD13mV8 zGo>$X33osF@dxQ|e)gmE^(oID@3_8BRIX2+ zze+D(9H{M#Q&Vl_ttY$b?I(LyTtVZs3y%}RHg_XJE9)K~$kIc)Rbu4({^3Ub&Q{tG zzX^_+mtsdBM+xq#uZ5PDyl|Jfi#scT-1gPR0mgBiK5|vCfY0t6`ZTWap!}puJ3{HU zzJ}7%6Fu&y=&#uQ?Snk~AXTFBLti))t)f_D2RA#J*{Q}Ii0}&34fx?IiH7K* zt+At~ItDM$5O^h@9Hq;+zPsJAVukypmP8LIuRs!4q=;Zue;WIgXK>-g7D^wyfp3(E zR>~@C7jlDlq0XSK35!|O_B!p3?-xZ;<`b)wK8v`aCH`oiVskVOj?#zEkJ3laUsxgf zp^rCYH`Dz?DC(#W<_|qK)v9W@HKo}|?fRyk4e#(; zTfR%1qLZC&+q4Q_LffL9L3iXE8lVq87VmXD5MRXF8s(4Ox+qzpA7}&F4&^R$o+wGV zk4?^|d+71$qaBTXb?^B8^>2Rf#U0z~``&rF=bdJCj-GZs-FhtE5Z|`l+EV+iSb_KI z;5a>h@gnypE%ztYjTP0?hU%!2CfA|^(J=fF^#F|_SEA%)LC3+-S^D_psdvUfKa8i0 zS&KYtS)5qrW1+`*zN#SwQ|X^EUl;cGX3?PdT6w&`|0_2gsMxqyBcL(qjhi3)&nuaL z#Z9jTlN}saFZ(UPF~Fb~7lP&VF}yrUoS$$hcH3l+hz{e(va1mRTaLka5v{A~3FuIsG z;wn4w4L6MzEF}uGeMUz;Q(V! z9#CXbSr)3q+_A#(3N9hXB@SETgU*OAJb>Sf4+eb{TI7%84C5}Z`8U}&&FaBk+5!{G zb|-A{qkP#O{X%Y=xg9&6{Ro3!(2UI+{;o${W-uaZZ3kNF$_9BOWN*zD>+ z6e3WwfP}Xp#vVr(+_`P!p>L3)x(=Vqa@T|Ob5Ogv-WCEy zoNNz>{MbAEBXYcWV_T@K@>;Nlk|W~sP>1t;hFeBSxMQDtJAl)1UD&~H<(bpt{5!1k zFyS6=hZcd&yqv_`-y~?OAx4Y9?mXg_zstj)oLndP5sG>OEx4J+B4$|l&f#p&?+6}# zcIPQ&acDnwH|)TN%b)Yi&pd1xxy)?wMVRbHc)biRKKr^A!u|C}Aab+f#>`K$HKdfMH8mVWTT&(k|U{Biop zPk)(y{>y)#-v80h)AsI@v{`LP7_FoS_0b+53_3E}_14 z^I4f#Fkj&P7Z@Oy=X>*6243Skq=bJ$BO1tb&*(|Hk#Cp)6G!UR;7)(ww&7SMyl5~EvLLXI7x%SDELOjA#WkCAPcORFGrac zll&~?gTH62Qs1g{z#o(SKGnkb3_2n|(GQ8uyt@-_g)GG>EAuh%&vetC%u$?MrOQqo z@MJ}T_)zl5M6wskN#0Qh>77VS;v$A8i zYPaet&w9GJyh**mB=v{F6RXdaE{ZKCUriTE^YG|6?kZBAIkM}lH%N!d+wtkCl~U)! zp?8Tmobtpml-wc2t`qLydh4yHs=H=7Iy_3h``zz-#~4afaL(i-6VB{fnU05v`^1HF12jTTyt)3pt!Thca@kJWFyGjZ(+-J>YGt%5Kt4wPBT0^^R-@ z9#G724B$xdxQmT?Mv-(PT703pM_Ggn8oNcsYbZ}BXi?m-yN3)=ze`K%ldjnTD%x5B zC+sS$rft>Rd+)ug{%u<&SQ4KS`9i@#J}47PJ$BNf0ByF~;%jPZ-DVL& z!^&ip#tH`}y1CB|*%^foeJJvOxn=+v+5MdGGnrnf{hXwaKYpG*`s77={^FI7c04{g zO~=Ql>Ex{MT{HKhV`!QFhokdO!Mpl}BlS-MwP!#tQ|GEH+P}W6$nnvlN_%zb-eW+8 zW9-=dByyn7VTVquqdrLw_o99L@;DtH_pBsmr-`dgdFB2=?)>v^s5{{rnV$6MPX&z0 zc~UR*2EZS52hEYEd-0h;o*E~VPw1F%94E>B>D<@F4kFquZI=26SJYA5e@Hy8 zQ>eJkFtp{q`eAUtN*XR?OD0?(Es=cUM ztQ=#Z0{tL6gg8bL#S-~v{)Po3KH0|QK#`Bp=E{9q zU%5-2W+m-toU`Izc?S1Wc3UO!3(Cih>W#6VesgbU$MjC!uxy-u+kJz|NZTe)vY8H{ zZFY%qU+2RL3iK846zhxsVXVElMtKV#vuuU^c9+csDwpUTC47H0O$SG(Zo{-Y#!dQ= zxL;B@RK2s4c13;RZKhA?1e)=}bFuwoJf;SfOJX_{Y9#LL>WmcM+>7kW%ooF zLhH+k1_YeK7NIi4H;f}FPZ7o@XM|s@q(9GexW~%>_;z09ZJf^H;t;iLCs%Cv&&%(~ z!KmY>PI|3gO9VCpi1}2y@1WJxXL7?S0IaW-;Omim{=P$$5;m2K8xG{*5eHb3Lg*Vu? zu7Qv+;28#=^1-mf^!d_H1Odgrg<%#W;N4m%K49j=__A`&coaPbvfzzE$yF3W>a+FM zK&j%B7OT(vh5^yw$We!8R5iFT*jPALJjzmzd;<=y#uW9SH+8mFT~9mDo}~S^o~5>! zWEgXHE z{SGEL6paYuF!`)-(Kq$E6gtIINADo|0ICgy@$e`Ff z9|ZGO%HTRvUSVh`qd=)lDD}jMX8MNiz=O-HZ|c%YIl=bv9107=g+M_5StUiCK<>n+ zjarF@qDp?;$#yZiN@rru&wC@~IoiXT2IEQ%MhPJ-CTh4hjN=bsE?CiaFUDg@3?Q)9 z#WaXDjWRq)aVBDgBavu{+a*r%q%iBjH(G^*euK_+2bFa9->0aF73N=CLDGhUui{ z@gjT)Rbnr~)z@PFiJiTp7$uGj9@(wX_ou?x%wYhOFtcx0icH1}F#|{890AM6q5)96 zidift);Spc=Df}@tZ#?r2Zz}QFZ>kF?$itYncn)IA0ez?9I(a97T01XG)JF>k7UZn zERKxhIDEWm8KBdC3KtMEJRJ2i!y)kT5K+=@31nCfm<@J01ikaEK>m;PB0zre`G!&V z!msTS;B|Y@iy#TE^I{m}_sy^}3hQw*ySQvQKQ;tcUR?(Lnyd^TLpaB9TE)(f$7tLA zk>BBmdjVhE@{di}7IXU=Ru(~hrin6O@sA!tFQxzGfBmmmz7z8||KY!T*xG8Q-My#j z$y@JQDCYD;Xt`{Xpg zDKpE$=NPj4^$Zcq^I3+3%k#bYJX89B@5+3mwDqN7(Z@gs3ZHpZ+6WUOtYp8uQ5#$3 zc&BBb-oV7RckGMzVh2d8#qOAx5E%@{K1PZQ%-Lb$zfH!_)FR(lY}Uu=r5Ug zE0b^Br-HJLNpiw4$xVJJ?fUvs+TLb&P}3Ob_Xa-hiMUKqjfVO@J~a=(PE$|FtDMLY z{j)Pq7Ggj%@ZcNaW!Wjgg9np`7%Sj2KW(`H-d1uG{HyU!Sml@ghfufT#la1HBrrJ+ z$af*rg{f|kbJ%%?GJ}=u$W|!*z$^SJ6MNtWej2%fRoP6aZd5kK6W^r~yM(SUQ>WER z>wf)y5{IH?)>@X&)-i!czaLv$^AEX>3npV4$sD(P<*o6 z@+k>SUj6CgSLve{N2;SM<&mAZ@bRK8!DaW^v&WAtdvO$;C;U~%OvbT$kFroE?%OJg z62?mMgA#!i{?ylwWYf1LD>1QoaD*c7)O5)tGLxI$og{gvCAqNG?tnPOLixJk^0HG4 z#e#R}h$g`~cXo{iL(4f#)NxV?G{M9i3OWq*#NA*!J00($q4H6*^c0RAH?E5*N7!Au z%+!M?{FpFTeUc83nH%K@r5iFNhKbG(J@xoU zTN_W6<` zX)9S9We<~{$mqy{q=oSg6XDxOj(P&~$~#tqe(yrQLm8+vp-&WQ6b!kTT{Gp*C6BwR z9~2Jk$Yb&rdbNxynBbTG1X^Ne*k%RgA9Nho6o6yOjl2imnB+$Jz|m~H@8dVv-xV znNvW>Gn3z>OC5L@lyJ|EJro-#cqtoYt%z>HCuQ(r0==m-XodD6fm86+o<+k0*&9iUp1eY_-{?hk}9rorR$&E9pBXzJu}As{`*IDRU38D;EU?J8)NwXYO8d z`@i7$TG6`dV5dtSw)E7!>xNw??(|3J!A)gkd+> zd4G`BHKuUH9!I~iyA9aQMosmyVVsQACvaRPr`9m9#au@0go>*#Sft9Xr-pY6G1s6z ze`PIQpqw^siMGZC8FT2KlzZY|v^g+-bZAh7y_1`}f+ zi^(OoP(N~`5B5D;8b|x1i*$I}_i?FbCr26|chg%>_C#MSVrh600LsTp^|Ksr$?=-> zivWU_NVg`sX4e(tJx3fK_Xg?J$x!fPr#oXf^+x+)vCO%~56U+c9ay=lyitG95j$4d z5yzcg?7SpD+`*^XRGqR@Tzv-k5`8j8RMlSI+HG2q$FYpT6ls(ey)NIgpybv&0O>bk zQO>6PRqx7|NK51HeL6Vqr;nZ=idNL0yP87jN~1B)20W0sU}$IIk2^K|RSh-4^XCk3 zzYgs0&7$#9hyUT<{w+00%?YO&sj~A)Mc~43G|xqsxxq*6)xvSO+a<>cKPKBu8o=hQ zr})QLHui^r@~0l+V+*_9nfPXIcxMy&mXYIY?*1yF^^WKPr-bDj`{FwXwt+l%>fTPlWTAbCd0JNF{1C%WUNBiE-yK zyW34L992I!8aHnFddq>l;9cPJa^!6E?Yw610+{H0M2A73{H=#y2h0=ovxy#@dBjMq zim9q}8fjI6%AGnub~nME1D6Mem3+cjdBu%7T$nxzVPgo;ZsuD~VYgYtDPW`q@hR~Hgcln%!oqV)2r2qP{ij(@)BqKt_7DJV9L$P}?;iKOGTpS$AcvIe-y<83lSjd|VPQ0i)I}le75vc?F^Q}*C zNC-Z2dCU0XPr?$wCi04#BW0J_M=_2^S;;GYQEtaoB}5GU<*2;kH^T9bvSABY&{8;L zxcZBC&P)N8GZ)Yb)cn>D<0oI(9bXpw_`zqfa0aPQ6sHas&NIWeL%WQ!>y@MUx7eM6 z0{eRoe(s;$BA$clQ695<4(%I-u^8V;=goQD9a06BhkB|x#*YD^P1fY~QZ!LCC( zJu6;I5C<<Uo==}kjGdL6y_FYy-) z@o?fXIJtz|Jm7!%uYdPOtZ&c!pZ>@H+XF{yt*jy_WkINvJzI@u8C)W_xVd-rU(~ZI zDCaubqI?Q+a~#YJR)+tk!TmsYY3of`e12ASyKfbC?j+%Ejdr)|dnr(C zaU>4M1QL#w#_;#>m`pxFBth4o_G-$FXVL|0`ZfydmSYkNlAVKKvr(h8N~;7AEm-#RnpLFj>R|2`GSX1%9hl z6JNreQx^$E2wg0b+bCt8fBaDz^ao=7S(LZw%i5WIWI^8f*_rv$GN}$sCd4Q+{wTgY ziK%jX7p_9kcN9e!d_Tfer6JG8-g1U-^} z(&0{K;33l>LsHj`X3M*6n6&5kDHOUa61=-biMZ^0(YVjc?Ns?BUrdrSaZh?y2q=H+ zC?Z4$$j~SoNY{%q1q-E7EE1GVqkK_zj#gupK8ixz$M3I=p-rG(mN zCGVW*^@r(L{U$qatf*Jn=p)!wNV^za2%jn=aj83wMq{3&vcX;2;AkZ^=tJ3Ap>k73 zD^itj<{wBml zK4^wwbCM%878f zB$z1GIZhEJ4dWI&)JPxYiFY0ew~STnutT|EdRH6dzNL1P`G)A9x#NpnRSY2P%wn#B z`e3dAVmQ`(csx7)dR9JciP7(K|z0vV=Qc@KVS#%Kz%3+FHjaRE-)<`j}JS=;6?u)}yxibc` zb57$XyK_}n^nV;RNPhq=u``tUK9qkbz^WClk_Z_jb`o(ikopVdIh1U%gOstBqlGut zV{r-e!?*%&*BK|}?*#**!Mb3xNP_Y6;_|_D2^_BFQ1i1w1v*|*8^6~$d8M(4{)hCy zDf4B%6HWP&lllS1e`qk2;T(hLeoKANjq-gyzDg(O8rvt==~(Zh-pI-}+GSHb0gFxO zr%<*Z9G+;5J5D{}>{hrl4J!;|(RQbvTDA4`)_x~F+HR_xjC;a~@aP37)r!i$=0zX> z_^0RTLMS~r8>Byc^ul+Bazx^P_;-Js_V;%^_s7wyS8C6fS9fVdAFm3c?K9WPosU)Z zbKnyE(J$3lpsoI#-Dks#Ti^L50#M$W;JOz+IObM-is*nHl|8l3P)x_2mn;sTZ)TA~ zRc(WNy`JoKRYz){qAwP)cvrMwa2)hN?FMCav$m1;x=rucCx46=^gJsn`@QOl@tk|# zP`=UD>8C~PZm&nDlk|rVxf_gmL6HH>k?1T8{E^y*+EN)Oiuqpg_19xU@%7*QJB~!B z=AcCpW+0!AuT+F>SY<(2k1AF}SBJ$%C^K?};FiM{H(PltF7L9Mm=EH5g+T;xXeL%7 zj6N|D)CA{G`Qa^kb{t2OSqN_Me#_CIR5psoM3o5_yHXAt2DY|9z)vpnGCk)K<7#-= z@Wd6^vJ$)a<7i064X&7+Qhbyz+w7FxZ2_KuGFaJeSN-ZcLi0p^!-jmduMhoj7TC?`L&Q2LH?hhgBw6qg9aZ%%g>KirKQeZ)Ir!TdP{ zl`GE&b#C18wJyPsw|Ywrt9jKCaTGaLSFuV%jGP8I7*bYO&<6#hC}C0^Yrl8y^Xa)m zi}I|Ai6HEzxAu#{6zy}r6?b&Otixc!ShM1h-B=9t{92+R(KzQ zp}~hi2*nyoHJAt#H5U?yh|8${picdg6*Yr?nhXZ%GOwtkY7o?c2R6)@sI1_L6?QO5 zFe7|Z5Z*9i(tk8!S z=!&!Q+0rjzO>UtK1FvH81rLEB@U48BQO|f+AQW!6BM9jw+(L&8rV60EQhu27Zl`Oe zhBN9%65eTRFjl|-j6ie0<+uUpmm>?^j#Pj5FvViv`^UZ16XS7vfsms#g`4#X0>*}! z9Rwi;@l7$<2yqxNvnpn5O@Av~QVR2^UzAUjSF#bQ_=mQNa*Mp<$8WS{+~i_Medo4_ zVV4^u#q#Hm{1deRp?w790#0t^O93KT?2#wp*dG8gc5#>}XZ%K9fb2mgYUVQ#N?HXajUR;xqgI4$0X5N{^gm0l|17= zvlCoD4rj2$#hPL3cNSK^#%(TQ;5XviL=+qH1S*`xY+S|#Xapu*zGn5KAJPbW2`7U! z!?IOBF@}Ys+n)?yVasC|4m{wz*oiBL=uslP@n>7kpZ*DYM;bU|WN`=zrN_>)Vskl( zraU`u;o&$AzhE3D5|oLE^vlklzrxiZGA!o}k7DE(BpLb0xxv|BL0txy{o`HiSQha- zXXeAr*(-U^z#QIIAUI~!^9&ayJnn)?od^(R2sh%XoceQkjKdj7B1#g699J%y*ggYiVUVEiF9!zy)7&qdlpe(O>u&DY5o9;%Hb2eXYJ? zIGT78m)KSDR1NN*XmKQ4O}yblI_nM7;lYt7g*++AZN$zTTjw( z2|g3R$QwQuO%J$W@`-fO4ZxowdvJmR_Zq=hqo69gCcp*!DSQPJNQ{T%he@8*l?};0 zafb_w!@RpjZxmSY#;oo~&hpV>Di1s~fl+25OTjb4Q(K{?u-td+1!W3{LX3rdR5tLq z*M$3lP<&YwQRZ$X8!-XQ4h|Lx_0G=H!SPAz3FjyUd<>rAFiFYIyk=!3z4v50J$|&C z4$j8u!{-N~ONfu;sZhyOFC1+JKCA9a4KYo}_dwn0F z1s%a3fKSR{`qZEC%p|4Cg?m{T2LSTVBpYR_)hos+G>F`VBB#-;r%k2B&Lk%F*4Bh8 zChR0rBKvTxrFS9;$IvZ`mYr_fxZvAIf%VyWF|uMScGPf`-<9zEVES(~TBbK9@{tG0 zGkHh$qE4VYCc}||tPq11CAW|!ld;e=ZtTFqptPyg8dlt3yt_)w3+;)q9C%*nDH=g$ zhHsuu$1abRmB>b_L(6cYSFhw(7%xOb4z|)k@}&M)012%z+3877$>d(Vs5tC0Asx6j z%ae)=&QS>Q<`fndc#;N3T_QU}D@>|G|LlsStpE%9v{FX+p*=vOu_%(fsQmXVQdGLj zp(LmNP@0iP@1#Vgw|rl>lBC`3xc^~y!Bq7(QGdZM4C;%8rzn?L1nGOLg%5V^P=1tv zz=xmr5ot=(JFw(WouE7gr?eB_-K26*b`)r|Zzk?8Za<3jbsNg^B%#_rhj(S`btrQ9|*tyG}R)2BW^JWeO4 z=Uxne(%SbQs{G&|SzN-n!;?2?j6M$vWKy4wl2)m=s9W7imp0NN)s z$HY6=4AAztn-1kOi(oyEq#SXKBYC8bXnWM}E=S*~P4YcazNRRk)u%&C^~P5E#ZNy- zAH4f4)izdzkBN^_AD z=2y5!epPkOQFBlBcT=ZbPdgpaU}Y^esvDxks4phqna4n0q%Lo6RX?IPcvX5e@E=ME z#ygHLB`x(0^m(Eq=60x4(zF4d{7|Y)E^pIde3?$p$LW>mf!%H$^=sShhTz0b!Y7Y+ zQ+0jW_q(CEWTA6QVOU5)zezjyIOKMR!kJx8D`}!(gyZediEvCH%AT=scX_G)Q8Y(e zVvJ#KV5IT?RDCP+TjZNEk+ydf=kZ3tJYNMqX)CmwRpo`S?Be4HLk(kYLuKA-OMN%H zS+|6nSOl|_RGq2Ys(VKx<7j_)DV~5u7`JL?8!CTA;gkoZ32Y@k>pwYqxjzUR2R7}F z9bd$yXQuBVUnrl}g&!84->NN4MJq#gl}&~3>2(?kIUH{&@^Jsfj)*tVzFswdDDDdxZj&a<2%0Idh+B~G(Z>eyK3_48W!VDoykSb}g zs)3akFq`BRhL$*7oJgLQl{U;Dt89pY8;m%NTjWQ~hVtWGXv)t(O!=jlsB76-#TSYj zI#XlA3K9k>>+s4AMR=hW&+6XEd#z71&+jcPzO#q%9+~?^5DtBF5CeI zL?|veFHSHCt=(?g-q}mlTFnEl8BhhFPCdDqJN+`~Q->(oyt+{CtctR5q7O3zDm!=v zmZIyE6@PM5JmP~lgl>c-(t>b|d+I?jEzBu>@W|sj2adv1c2H%eZt`nKJ?9Bc5`@DwbQbDNhj?5Kx0lH z$k{y}+4-BnBwgNu?Qa8i9NzgAVfANR>M#G#!|@kZ!HGOOjQtEb{B!&FztVELwgW5h z!T0Ow&-2K4(!a2TgqU}GbmJxGyU0XOKO#Nl1aWGC#|+e(ofCepzgVeRHPgt3eL zaaXBaN8uIWiXU#I7h{H;oM+{eH{be;@)4Y`j1OG(4eY=T{^1sBMS}iYh)Wyg8-gI- ztbPlD1|caw@mb>AD~EL%6+Y@zZX_kR_ERwDf6>lwLYsR= zp5O5}Yfdh^>)Wn561WUg@G*lri$ej!9#8q3e>-@%>f7xVciZD_yq7qj!R|Q8FT49Y z;~aTW6V-;H2~9>65g(v!id68ceXuQ!r3w4F)mEYo&(r0FR1N ziSC0**jTthpSq&->-Oi~9+Y0(7sU!~i6I{9UdLIj*pLzQoq;tPDT_*D8Y~+sKK9{v6F{4`J=p)j~zhWPD|~4D{XC6tYAhti!uf!5el{jI}UT5(oUF^XGhEC zrot)A=6W2{h_ZQ|JShx(BXS>k!>}8N`_H(`kyWJhse*AZ+oXJw;d~4 z*%?aSXv3B?Aw)fdrT^myPL8L$xtgYm>}}zQ<6^-J6U|ND>J!-!%dwiBPCM=Iam?it z^}TJyiCq;;LdU!b?Grq5)Lk4aw!C!j{+dOtDCoH(h*MWM-VYcJ^}#4eP)>1oABvKy zaD>7gI6_d+r*O@J0(Ldg-+(vIB|uwx^ME(s(<6V}nFrxsJ@OGdO$1K#!D8n|z2UlN zyzru7g}1^-b?9A?f&qP@kb?%T5Es2dzgt_}ImXU2=4LcbQOERoqCdu*NBjG(7k21C z4;+=sm~tgNUth;=HeYSQ+?4t^?x^JcL3XB&-FK?4lwJC+q56b@Xr4ZdCdz!)>Dj68 z96UZcOTGTceG7R(sqOJWZ3!h+f2clrEErSLUDkd0xNZeV)PAcfx^9RNQ zeS7SrW1yq2hGsYp^XTL(y?Aw$PEPxYqcx-7Tuo!a=O|znsi5HSot#R7#TxY4v`daW zq(7$(QO3aQlJ9&(v44DerZm_Ujk1R$5Y_Kpaql5YBeet3G=1zfw8f4trGKrmGHpf} z?o1;O>?XUAo!wd7*~Yz&9DRGz8z_yQkJlScE{*e({@BmUqtiGt@a17TJn0M0T^fs) z&dw)(4o-*Z)#*6BI-8`P@CuKzw5q;-c|F}}?7S5YSggZiMUUc6*kOk9QDwZ;aHwjK zTS}*cE5kePDPJh~t{;3~)`jxR&T{a%B)AXahqzOe9Z1|Y$IeXdp7YKqm7OuU-EO5v zdpqgz{*LePW4A2IuQ;lCqPKV^)hBaD>^k$EW#U_?W9nd2{ZOmfaUVgy%Y(9y#UYJG z>{l8i>GQ9QV`ztCMb`uy+Thq=+VJ`LAiX*` z@ZuTLV$4N}N}r09>3a*+AK%_BnO@jw$nJ1pt1+oL!3n)-7#Cw~3={bH-u(3#?)X}H z>*=#!sYlW$40Cw!O($hH{o2`X;XNz@#``O{x%5(Rd^D`7MkWWwwLrW+^7XTG-5mz#{NzRYcLDp z$A9=0yhoD!2nPP~Ln5=Z{BO5#&rb8VVdOu@*T3>p-r=N9kg&Gpw8Q2&vv@ccgS%d4 z+|~Ikt3zECQ@OmZj#?fFR6$!9b;TM?VW1hL5vXA9W8l_+D52(xl~|Lh8Ojh^V-*cy zP-5|*WMD<5g#rtP!Y;zEI%#%)VMq}s*jsy*H^R_4vZ|3mnbln|M!+S12uI)_VUJZz zadd@*7BRusFdGtXM;gpfeBs9G9ylB77(;v*W$<9ZT{wmDkyT;h&)+H|VJ$UeL`L4l zR484PD;T`k9$YY|u~=oWkDvHcI?8`V%xG84TSEfns_=>e1^_6Gd|aDA5}NWe*icTG zP78X1VSJEp1q>yXqdOkV4hlJPj+17_9b5e(o! z+cN~H})C1jt?`5SIXP85a2rf!n zao9lzY^7j2Buik(>DVrJEP4c5FWduf(GDXVK}p|#b|yd3ugv`Y#y^KyjH5psqc4au zhZCVx*7%H{+=m$F{)7TCxXPwD(0>HZF{ul^XSB;ZKTe&u;zS!2L`63a0F!axdvn12*a=sB^y|-TUwD&K$MeIhym_L0JdWY~kS2Bl&Fc$X&hlLz z{_?wo(@%uQYCEr>g$NmL1%_S2lYhQEK_B+`o}+}Y+3ts*Oc(htd(57wO$W#(VDL6x zD04VO{bYNIKpii_jlAL#u9$ceIcO+{w3F?Q6CTA*8BITY&%*K6UoNlR2y#)aQ-ZL{AzS+ExH$m}M74P}y&$wT;QCe@gfW2O7q*||@Q zVCM+%Si#POP^;DQBxj>uw-N#c7k9V}h67K$aL>}M_(4lcO#Z@4t_tp!?`Gj1 zq*ddD6A)rySX2o7HoPXVyjweSp~_Y6ewldJQ5?BPn&1t7jY%s` zDPRJw+))GH=0%5kGttFyY8)*k2H2C;EO4Vd+^aU3j6Ct);;5^eTTgDWdfy6*+Lq)z zrJ=g#VaFKv^H6@22h^c7-Svf5yH4`6c2@m@0fxnBrCD&3mE}rhj+!1uF#AuitJ)pO}OGn z$B`9XqcojPEK{K5uzbO+w{VI)i(-v|mHgB6s3%X#>4WiyyrHCv9a?G|DCk5h4x^+( z*10wAp)V#7kx{89Y9D%VdlanFKIh{aauG5bi~VBpBZgBmP!6Fu;FODIt7+v1atD*C zB*YPk;D!lNy` z4+t6#*$^B;|KJdLi6cbYZ4_P{t66t`C_gl`-D#&zr{UcgE8gW8^CL`#q6GHoDk`(( zd+K$oZek~PDK~oKg8}1@Zia1l^aDC6W3NY zyWP^CaRg#j>9Et1d=YQeN}~PUt|z3+eN)X=!#jX>nSky#y)%hBp=gWj(ji~8HQE+C zEXI?#ONm{q&=K^)gfxm^cDbPV;s`Y6J6Na*$B2B(Jya|RXgBMr(Wto{&{wTP7s3}x z9h5#C{Yu*a@9exoX-&IF$wRr^E}%c*f%bv|%vVgnL_XXa{?0baGM4JXVw0RcI#`qx^qCaSoaK1`G6c@)Gs*h7$qR=_-kGvD=_~guOttxyr zYwLP8QoB)A*;=XD+_IA5y?39bx8HhVGONu(f9w*XkMNFSr9+=c9fn*FT{DJN zm0t4Er^lxwD`D6z#eHq`5%BLQ^Lyvx^y26|ee&`o9h~-6X7%BsT@2-@=T3GMVE1~jt}af%?^KocD6*lDY6h)xAv^+Rc( zA6W#zN=*7XInftTM$fy+AKb72+b0(ZE(#PBixcV|1*a8Mp}1oA&lrW7@`qyT;AALV z4$?_q{m|sbNB8x{+$%Xu2fcAR0p`$<7?l|HNMigCURoO-}vew4KD7}tCLCk z_-LH|`070U@#R_iP!Go$4pcW2g%5?H#twC}9M#KRqQ|7cj;oQz9F1-CNnUW%Z1_0B z$NSr9NBtN)4ebjhE;yi%q(3DrBLGVU{2umEUz=}uvnd|Y5h zW8|iI75au1wNn&l?6ltRs%>tmUR4i_!6?34KhduJItvS=&hZ*v2_Nss8x z^QwXwb8E_w=~j3{2@D-xXe?L#soK@fH+(cDyxCP&X78JSBKv8sQFBV-?BM>#rD+c^=87l&u5*W+FRZPYs90nLUf2 zUo#llPGnqiIDcpNPd@|&%h>hK?w;)B&9^%x+<9Zm-}*CLJ>=i}WhURA z=vSw?sg8R^9VfecENBr!kzwyp9K=@TxTq3FF*X@_#kT775Fm)h z;7_NBuu#qprvoJ~WGCzzL^asMR64ggubu?(zuZ*>4YBUXDGtmDel8VKz=(;Mxej*Uwk{t%wGI4R^Y*~5I4KUF1`rox7wEf9A7!7oW#-F`5=&uY-AD} zae2pw9&kn+?DlfKx`c98E*#FV1lM-L;p|ZEk>XDt%97ojAW;YmY~z3@!t!<+@t7h87Ydj>Q902KZp20P`zt}g>K;vI$`a2;g};~@C~ zbc6v0Cc`OT3xRmC(FtQ0`T379*(`>Syhm7m@QVBy%VEHgU*XPQc5rx)rHl2U$8U_o zDBu2$xHFszp3}!Kzj+MLalu&FWeo#7Cp8ZrkG&k$arhuOKX%WhaX{Yw@HbB0;a<@Z-HUorSsHQzG$@6Gq- z>zgv}Wox`SMrp|_!&&KkDIVrdBQ2}M#bLRhtW_)d?hYnCHa+oG=OTNt8Eeb;R)jU= z$A#zYVDK?t^_nMpkT&4keB2EaFRUmQAH_r-d?QDgUvejp_)d~e-$@$^HG6y^&lcL-Y)@m_<8*$)0eVm!{ z#ERw(CIl50rP=ApSvoyENrUr2O!_EK9KGeqa`Akmhw_O#Rg{2G8jJqCvnKPl#w>k5 zUkYEX)lg_g}laC18>icl2)tX z5^#(kuo}XdES|V$f)pII+fBJwQd9NaYH+Omn$l*G-F+Gi*d1|UnnGS;!g|b#aK(+h zk0fhcnO54Jh9|^gM?okUQ8byqN9Is@Cs#vf)1sbk2ka;jN|jvMua;uj#7yo3mj+1 zn;nJZ$2$Q;)07i~QiS`3T2_8=H%vu%i6al84Hgh`gd3EJObHAWRM0@#WdOb?rzg!V zuNkzm0Y+S{&KKoG@qhx2yrYcqt}Wq*;}+q4p~K_j<8*XK?Ra!KmBA-&k8tHTC)IOnbDylb$`V*E3d!N|3NWX>h8v0;I9PI}8vZFHSR2WuU3`Hn&N+^F-AB-KsA-FdGF2tkM z=I%yzYjT&^iTd!DuMX1T;j#Lzsrs|&_m=8B_}(a4vvn~X|Ly_SBEUj7_ex8 zI~O0+2Gm|Q*W8bBvd^X)z3L$nPDjU(u=GGDRV-A->keWdX=j-Z2P zp;yK>(l}Gv>{jBKL@FDFH)D$NsWFSb(7QiAZ6l{AaudOIkVCo7wTeD&&`a^KYc;lXswyH8R$KXD^iek5^azIC2wZB+E zKwrg?k=!#Hiz(PycAL&s*X+bPJk^-pS9#Bc+u?=WFH?VfAsk+%;Y2hcJ_2RgQGb#? zIqIiR4$jicQ@o!#Z46FGSYAc`Lpt&9QSjW&cbxb5;QkHU9TeFWFK zplD@$hBx4DGL%%bk*3DSj-EzkHPzOaQez{Ix>OUQ5>rp@cs!iAtngLvSm|ElvbvYu zuExhpwQaRo?!>&g7^ijdT%Cr-UMr#C*6w{Iq?KQ)`$l!m^c1^E>F*dH=yxJ4JlmSS zw-jbi@E`4}9BRk0^M1{9q_j~rSMvwA>R(otZmnc%*W(!1E%pD5M~thqLHN0?%DNSA zlx^wZ#&>vm*T3p=OL%4B2D|scExhJ3JN49VCYLC_?$Qt?r|6%BD)2wh9r=FUg!}jA zuiIGh_3pE`EzlRmiH%;^<8hA{ethfC6Fz)LpC3Q@;pGVXU!qG2V@zhB|B%ZVdJ?Z!l1#4YLU>xB_-k!Ms_hpg70x6oxM!vlh&9USrnBV~cA10Ezj8%1_E#aCK zOVmC0IKb3UdKg_`kQaVPgS=8ka#k2lyn$^7Sl?D?DN&R&ghR3DRh`0@1!>X{P2O?= zs_G8fCLiDlhK=;1K7}*Yo0WPuDzktx8N(40Fuu;a{$Spy58s_Yii%I&JcxeS@x@9# zE4`FZ^bPS2{E|`s#&=lan?HLmv|HYGkB5MU#h=3vF<`q7R305nZ!E?Oxs*Nf5RVN( z02t8XZwAW=g&kOwU5t~D<^-stXSj~1;5n~Ok-88pw?)1QfX!gBj8-TD#9?K}Pd@&`oww@*TlR5W*)x0~&%(+tr}R2La3c@caVOmz z(q32`Ry5>rd`8%OnP;RE!EB2#0U(YJ<~tnYFT#aC;jqOof54+pDd8M9yaO*-ag$v| z&E?IxF6AYh(~Ec|ZTn#-BHywEJ_w?p63^c}1|DFIZ#@QA0{8={;g!8;_JWt@BY)TNW0V{_OEOx(6?y5W$@pd?@b<4zk*Tl5{DMe zgp>bh!W!36Pz~J8wL>v642|mQsClHFZ#S$-O2w zCSp*2#Y8cD<&EFoX(0ZIJ0O;sd{JH)ci@?)lekw&th?edxwo7K;?0kHqcoh}q)Yf~ z@#8B??9yOI2a|wI*jLS?dMAK*_+##%>h(N14}Xko!h|>vcUbt&8KsK?h)Lq>o6E#~ zEbPF7cN+`_R(PGC4}By%3O4vwx;YkPu`^?1qhkJdIu7L%yb$9^EM(FfK3jYbJTPOeiv04-d%%BNM(XvO^|_-8wOmzqS@fi=iY#CSsD(e5PQs+w1xg1tE(DnG}xQ zL!8h+y6l#5pDdVVF`SQh?473G*>M^QH^XzuJJ-k$H)-tM7XweW!uN9Q5xhE++B=dx z*d4&Cf5tC%jWM|!M@LuK z_2AzMIB-aoMGLUsmgzE;#==UzKUvdgY>`8FI0Dh-(*4a;g4b?mqp7Q9o9}yAMdH(VDcHonEET_1zNaOpTT4{ z?UAGM=xdP2Jx3tAfWA<8`A9|VdPDc@KswF4eN-^hOB^etduqE@Mhh3YW^lUIqVRoVMF- zg$bn*0a5U?8;@NiE8cmcIufo>n)AL84wvq)(^f@&e{(DC314qN-A|7n?|R~%1qm#Y zpx=eIY=nQ(K=}&&xL;JerheU~^jP`TjNM`)Ww#CbHE5ka6uLCM%Z;|cZodoRp8MQT z_MxDNyTf7^9g047IZZCFy#uH}zDlD@jW-%gZtj*;U$<7!qhMkI0`1k;aHt;XU!YDF zTJlGpQS_1r-&LeO8rmi;Xc>3UrO4r7N%X>a;c)cf^g%1B)?k-0yX8WuZ>5U*McOX+ zWbU-LeE$>WL;j=t>nY!_PE=odvp9fJ6D3Y>Fj3pS5e+eavX<(?d8e_Fw&{zzEiXjj z$Y76mqRr{my~@sUbb%-LJAxH+D9diE^o!i}OFLmFFFUqTi~xtZ8~P_JuoZyz$#`9> z%HRDhiYR3msQM1xTy~WkWhO_QdgpMft};R+6}4gT$xhUaBee-uVMhAg6UZW(YHEr1 zXtS#g7|IhghBB5p856hbM|~w@1GrPIF;1}?i6bW2i3I+r|GwTwr-O8K*7vdO;G4F~B53nN!V&!%xTKFn=I7{A-|yE_or)i7 zZEb|oOUyA{>w-F5o-Pk&6m`^|4PE-OFctG1ONde4gN4|4nH4}VDg zvlAwnQvc*A-CYe+m;1sr{#M0XZ76+|k=#GGsrqUNKKIU{sHg4Gr$VgMin8sywI0-e zsX;5;a@z0K)sE|mhtlg>?P+ZOgtBe7Yw8o5-p$rlA5#&201KR=Xsau&R!w8?!&O>V z-+(f$y1|&C{!Xci8%b-bSZHIS_IJ`7t6s#1<@R{mpQug-ZpWkxkEJY{j)-4)*YC~0 z9Am}T+iyLa9pU1Zugd0aH$8Mxo>*Z3hJbPyUiRb5cHZF^cH#vbhst&{9fXU2e}^A0 z5t`mHSw#GB!{Uim{%j97UKq6nyD?$KMTS;b5jLmA=j?H+cw-A#cC)9_5HQE#Pj7XH zh7*%v#3Ns_Gom|M2p~=?$B8ExOx#JsjGyBX39Ccnl*7*-MTmGx&T%7x{yl2wjSGMN zoZE>@j!8o1TWEm;DlLdQG1>6zW#rjB(PK|sRoy}aW-FTs{Oom5fyFfeZA!HmRXbx#NlFcvV$ zFu*W`cY4#gag+cT)e;xRrXnT>;e~Xq#1dTP#0m+YTduSb_?YzbU0dpftsGGY%uyr^ z1LfpFXw#Lb(*ed4LHfECPX7%nCn-DO}*;Gum;}A0&dXh@uIh7NHFR2*HFE8Yt#q zILuU1zXC)4nK*zU^V#}KvD1nNfebg8B!Ra8jXP<@%AQbQQ4Z(`r4jWN^+q|vkX7nr z&h((%3Z{xJ@PwuQV^y#T+-XEvd4R%?1VZYC^fJAWf9Ndmt}vouATan-$3%-VXympJ zxK|qmoZ|Z~ItdgU-yxtX6U;ZvtI9@ORy1f0nnOULeUWYm>ga`0@SzX{ezbkHpxpNK zk-zpb$?L6#)={^KEoD?p+ zf?+0%%1&8J-}G9)!k^sY{yCN3ZnLEPL#|7i^rIKwIbROQKNaF+?B<}^pYbWeU?+a| z$L@>;UTkn9pZe1)oUlZM=vR3YEz;Kmy_(sEw;Fb;5oX2Xr|k^tezb+J1(aU+o9cx=Ka zg6YvWupEXrX_qh&AJ0$#&fVsZz2Eo-$07XljXhAE!_4ya>2Die`LR=R=ADTm>Ob7( z_?p84m$R|4xKpQ&7XD$^JJ;b%p^5`xO#5%Zz@1DuT=~v+to-E1ehR7-=6?>3jbGBi zSN2i|di-)8f<6oE`LpnCC{Qfrb;R(O6=NDF4cthBKl}5Ja=bkF?i64DoB#el{fakv zz>qsnWCO6gV`)DXGjYo09y&;#}S;7%}${&0l3!0eVoKB`*)jvd0brJV$ zVVL|!mSD1ywCTU#2id7Y9OMvW1da=1XAAPk(cwutJ2~?tHh%EF>~w*b05|Z=J`PMc zj9ph#+u?Wd*N@*JUn)L$63@sHjMd6k;NN|ykOvc`Z^9M@0{8c#d?0NmOPSQ)WYxFw z9x_xM?G-#WtLAfB(1YOO=DUwnUKZ9du@Anlt<1WxlIiA#yQtzWG8B1)fmg;LV^OBj zh#hXXmY;w{Z)S>9nZPT%i=Y$YF(F!!JjfAB?4sk|W$K5C)-quYEOzO|*ckUL!Na4} zL2f`P!)p2~!DJ$zJaIf5c^nQ0&M(SICeSTEP+lf$H5PG1)9ph{Hkz-Ozm*A!4^1=a z=1FX1Nrgx0G_^vC$;^-~z?GFz!m$-YDxVkc3AgOxs;pB7k};H5-ve|(e&dcWCh0it z59J3F<~-92=ow{2K8j6s0}VnC(Co||c~tlUPZSm$8T|L9!d|6%M95_AA*a#wPrcSr&y?tX{*!)6OwQN;Fx+b zPQkbE!*PFBd@4N0A|j8nLy~ylVl+{kh92aP5&(IUGBc@7J-Mw4FU$i#P0SCFU+8MA zI)3%ydHTcef1UpHhu^2;lfyI|^xZE!sQ&J*C+YTToR)4c)z{pmR=b{_K6#Y(cDGY= zcHG~l<=MaiBqF&_`KQfse4v$@(5{+GQ7VvECcL*Q8|l$**NQGC`#DCAJFeKZgmU)m z^h9~M5{_we!jbZHF&U?Rua|ngzWWp(?In6ySDS)vQF^gEuCIQnKNzIp2nF0tS{FTW z)G50@frVm=d69v_G6{d$i?Hl!xp4m(v_$G{XMPrvzJ|9|Pl^N-WZ7ax0v%P)TVBk%HhthCwvNxjFtKWY!^XKBye zGe}<=y8~HBcw}z!V!IIE23}kc{xq154YZ>q7Fed$Q|-(pUfwz zo_uwN(&k<~%RqW)JB%?9G3jEFGsNe%6AEtT31VRd$8$EDEh}lc3#!|NemN3Tw5zmy zMBV0!m6kCV6UsFDt}!$sx_R!X-P}s= zJljiev$%YV@hcXkKu0XtSI=*{qy5u2GiL>oZc)w)7JUs0ojCHBI%MGwM`~`R#@0sK z6#kY)TMz2LmTuKvMYrsPV&|LZPE|%00)anvsH0rwUOg1~@B#E|#=X*mUQi5kKi$0^ zc9Ee-XY`wj;~GO znWGl>yRGzOe>>Hc7a>=55Lc9Gi>^4flkt2njWZgAETlbY_`6QKrX7ILXN&Z6}<* zvwu8%lMeqdWN%KO#CvffO|Sfr=LkQC7yfe9AMOeh7W*-kY&Y2*j~-fW!r!vb@|@#2 zU5AsqAgXu~){gOxAn^y#Y|C-<=K%A#L~sZKIX{FUy~tO=6^|!LNyY9tjQm|X-VUoT z-X)&i01p_l;-0@1aAA^F@#zl;r$0e<_!2fAbs&V}S#Xa!BrgFg9(^0E>={-#h=rtc zRVTNk!RA4g5JH>-sIx>M)qtYBF&J%V07Ho7+p82cczH#Qg$8y0>NpuR<9G@&jOysk zm}ubQ9fMym8NgK%76xwADYA>mxKhd%RP@BkseIf4gQp&LLRAEBQ$hnu2v!_$cFR3N zn+CusXS$04n6Rx@`GRpruxBNuS8i$0w7>u-Pz;|M$gK#IpO3*n`K5Rk%JtwLelbx1 z3=3?=V}@and|=U2l91Di1j)u;Cp~)WS=xL0I5os1Y-qq?khF3|<-aAb8swmH@)OJl z15t#r(npC{_!Qn?JQxs(OWG)X5Q0b+ff|O16=UE@xixGUKqe!|HuVdBpcz)fc$bsx z2%FauRACTcRH=7>GEiGtsXUvB5iIXCqb`*JCSW3e&=`3JN3p67y5a~*3^09GJK>cj z47BOVALR=n5Js3g5S(Y3fW@SO!s#2v3z`WNgDGhOz-?0wdPTmdH^oQs1tUV4sjnq5 zNj~CG0awg0uUf#2^1+C)di37$E%b@nd^S7jkO`$l>jR;YzMbZ8{kd-;C||TgZ22ep zk76evzl6gH5B&HKH=)rE_VeQq`P)4Y3#%eL`OEFeSyY&UpD-nU^vxbyooM5Z$joD+%l%Zjqvu;xBdbLB!dl@q!!^FpFh2U;W&8N zt}Hl+9U@##+j;R{WSjT=(Xaob97M-GJLVTZ@ohLxgSTGBNB9Nqu*)yw-7fl$I?;~| z?heBrKxTH_BfQ=8DlzO7R+|Vd!!LhcAI^bn$X)o;&bMY-PYnVx7$DG9}JN`AGpoK$Da*u z_ScW{S0);wyfWk&2Y&@*`^$ayheK4x{M-NW7azb0x8m~}P2z7$@s$OK49j(Ie}6bU zRxePIi+`1X+YkS8pYaGhB}{(ol3~Pm_`K#u5Nysz*zNDKr}X0B)jz4?i+Tw>#6#Zx ztoZ`(ztnuo;J-KjO3c?)a=m5@LO<>U^shDy|5wR71eoOQwBr~oc4e_LoBMb;?griq z{uN~fCmL`c$L-y`)AD1|3Sp~3%lu)ndQDmJuBn89&pVLl-->@Pr6%CrZ7yxGg(g^urQBFS(I<^ zk|-Q5E+-m$9#TVjL)ie2Jsq>li~G?~l(CzJqo05QZxzaq4Y@I~E=Jh=FtAX3-Kxyy z&&8)INtFpcIr!t?PpKc-n72RRL1AIMl0gmwZ6V(Ab?O5f{ab3uY$cY>wh^%*u+=HB{6gg1@ zC5z<+=b?tUl}1hG)#Sy1~QZv zMIz$~m*g2)kI7NOf>Ll-?i-UNfgobqhdw;vFS?9fc%l!%rOrGdE;*HS@PqcCVUCAu zwmUJAYlUW2ZX7>Ymz%;XF0d&}Ot6Q1gM5WNM_#}^3tpKV zCyk?{Ln~A07p%mpZn_?cb8~Yc+CNLDhaab-mw!s5!Kw1UnVvp+l=gSGg%9OJ9SDjW zcoFIcnUV?ioo&g`dpka&kBRY64pvizqwT6FV7Mo&>b~Hex1XkGPo9`2YxRa`cGG>v zS+Adl%9ro)+3s2)%MqN^7fc&UhDM{6+AZ$&swIy8Lhhxlq9A3W{Yv;`vUg21O#RW; ziI0MPFdV9{>!qXPGapIU>yOg;=pu2i&RKtuPL)1%NuT1oc$79uPmX>)RlJw4j(lep zM~k6Q09in$zW_Hvxk9k(gUM~xoBHa9TXv@2`gp^$lVkO}*J-EQasScp_tN3P%k=Sw z>?k=@8|jm*rl0=g1MifnRyW*_ zpy=ukMpn+mae*j`QG{^JEwoc{JE&-k0SC}<$o9+$pfE%cejROF{mC*j_)3rd>{{at zN64{b52crPy{a6gozW>EyPN(514Vy~4bUP>J#N)Mt^1BNb}`i}tKOYl5srLB+*(Ro zwl7-&vb)nxbENw(>&xg+^%?w82Z_Uof}By@a>E3+a!a9Hb9l9H-|8 zr|G0W5xuD`3kQcsz4YqnRQSIT-7H(dOS|gz2I-_XN+)N-^h$Jha;7#edb+&2RoH9S z8_G&{6*7!%k{|UQv@0^ryx5h((%(`h>I(xc6{Rf7CikJrhm}{kk7D;X3uV}KNSmUp z)E~GAg_d{@l^uD9ewhCCQhgC`c2Cqt>tiCBC!&r#hNw-ko2n^V;D|=(i!n?u0|Pg}^iFW$ zmwu?quJ@{*%9`j(aa48`IU0o1!}Vp_l+%iM3dVJgR0Nmi3q;?vNBA%lTf2MvR`f={ z!9s$y)b4iE?*6{~#V^o@TPeozwX3QFl+9y}%Qr$DJGz9+j3XAiOgPS1eXfX6`DUlK z+JJW!s$RvL#QbY4l%NfP*Q&lZAwsn~c5`u@Bm4rp1v$QzaK-_=pvttWHs(b(!r%7p zp8CU<#sqjs@&{j|aS7f;^+9``Uf+pc$LUz~$C1d?7ktl_aLE0zj2o|;T#+{Tz3KnG z`D-&)e7*D5Te0Jde?KtNbm-w=;a-$Rb;smVanr*eb~=Sc_iU%L;0-bP&+c|M9D>9< z?D1BZ0(bF`Zz8Mnjc^9yMy3zh=pe$)@n>m}x3D{Z{E;vITrT}NQ@HacV#L9hR_5q# zZN$QjutX_wc+)`ic2c~t*~vd8EV(1R8<^hlIE4TBp2JmYgu|!2b9wmopg@k)0dv$I zZjMJt4&oBoA@YkiZu}AkYt(;C5{7>XJ98&J{ei9UoWCQTVsjMP^cR+} z+dbUarDxZO*1h!O0_KOH2DH6cBa z<&`-wE-(@7WMU^7Ti;m$XC)OYIvhWyJ`qHD5ZXY$cL6D_4KW)iTZmH=Gh2}WjgW#c zqhI|=Xys46?S+Kqvy+q5V^yaZGdL3zEF5_l!eJ;bP}=aojPbnQ;l5$)t)E#qF>s8v zj!U`aW}M<>Ob3(Zu<>nU>r&bf}XJuKq0)t2vRLm;SFZS zN*0&}Xio0jdzQfnN7SM4C!{l(4)aCbctxoON?-JBrDNb2W|38|P=j%r(<&>MZdEAK zs!QlbxTS0er7$=5)sfx^OoaZG{T^_U)17oMCD zBL#c}HQHt{B9u$81QePh&3IHe7g7aRAPbxdM;Qns3RDNSP{t1w-E4v3zKc- znm(+sQ&AEA@d+%f0WWO8!H-Ph z?||8@SR+hvaBO?z@Z_JeI}bTu5nw&UU*?|6z^xR)pLL>3rg{BnbTQc7=`0vfX026%RmoNldASfn2 zi$igqy8t&}^QKksFjmk{1BwX|jtkj@Jm{tg^SlM{bsHay`MfqG;e) z#1UQrZ$Vg&d(~8_t&@kb7G2z&*EAz%{@C#I^(&s2B z(#MpAX;x-1ai}s_VWpy8Nj|e5eX8oviWDnUI8rheDl+bLaR31S^hrcPR6-)a06dEf z!w8nrpj^(ka7Ue)kM|BW>K!?TW0ICVc}H04h;qSK1E0EOr0H~2mnx(E6%SfsqS>ci z2r#>RPzJH^(F!l~-^eT>i*mOVibv8w-l0vPxIhMCtV1p!9Q8*%V31X9RG-C=H`2#I zFP>Oe*_mhs-{2_Z(^w2h9>6Phlw(W~LmS8=O!#xB5cEpD$1#E^#Mm)$?Oig^3FX@9 zZkvvfzfr8x#$p#<95?34UX=lPi^)^&fAeIs+6rw3Tv9%;Qtl{b$0D#>?69bZEXTyD zie;LQiDIQF*u0U;kP~@KGbj**Bjk9LqwM-1o#@LbISN3@)e3`R3)zh~`9l6$U*B|| zjb`;n;D*UxcC|EHo%H0bchl2%ewf8QC%)A;K_BeQ@I6Ip>%>P{Z21%=hH)wU372G>$$ReHOG~S1sy;{A@$QiRVCbXh z2m|io7|}Ssjy4Q^?(A%*ZS^H6bF7S*UMkL|;-m10_QixUeI#w1yn>5f?<~FinSPQB}F^d^LvW3)scV8)cU0nz;wny%$N-7s`Z^1w~hke)QGs zn&U1;;6lGK2Ng#vGH#&=X2Az-isSRPyA2;T$8J{g0VMh-A8{yuj>Gegoh8NbrqTfC>;ODGI#rz>rcYkHO0N!%U(2a1x4g=!A0BWZzH***S!=hy^0CLoJly^dpp+{t~dX zbNY*^=x;a@9VpKtGKGb1S$s{Ob(yAmplKE+c-}^3rC()H4!jCG8*3t*rASb<3W*!@(V>Y_Xb)KqzAa(bC6rla#G`%`LPiOs+z8}0h zu3blYtTw44hBUfp_*#6vjCnK8;`6=vr#4o6z4!Lpzk*29W9}!91Fw(wpik zc78(f5Dk$Z$QKxnX@3X^CQNVr1WfE1c7gBk{FZpxy|^hE>~0W-C|ALYc=#`-sm_qF zddCDFcHr?14BWyl=N#s<9v98!6ac^UoBz~&j3@caO85Y#ZyBep#~S*a2Oi*%Pygk# z?M7a5oRXhNQ#d8heB-CTS-BJ+w}K<5N8$v{-(<(Z^hdaW!OMXnjGw?ChIdTYM%YLu z(k2WhN__jI7n zS_35l?3D&i^6$K}H5%bud1N55@(Zr=FE#Y^e!F7gp-|K;mFq%2q>2W`$M3(Je(^Jj0~ih|z@U-&hmO9Nx+>)jNX~bOpR%HaUY_jDhmS3RCJCss@K1 zOv#J#;8j5?0}L+kC=2jlXgygWM%hdVdBwOG`cXJP`a;3>|7Y*dnxsv#`#$jGzD35C zd%j!k)zw|Spg{tZfglJ_MiVt8F{1Pl^cAGJ(M8YA=!58TY|LaM8=H$UQ8G%L5daMc zGd~=V8jL3b}|Mx%sL}nFg>!k`Xpgi-5#~X{5tri2LL9pn7!C2C{)k7~6%ND!SmK^#!i~OC(j*)f;zGQd;NwZy zW;ud=HGF6W&`&PB*ZEAUBdTl_O@AA)A^J8|=&oOa6s z+wOAnhkJR3{it%+->`qA2bTQzOFxD=>lKQXt$DB>dYUIgm(J;)Rl=Tb_-0tXO9Av@)KTJ8;q2!=oPOy#@-+*-{>_glK#mrfEZE15ygto& zXg=3d-X;ELJ^Az5<_o;PF@Fz@X@pwH5eGlHS@T?U3xXV& zMN>1=c4zlC+BD6^ycv1Se;1;YPC3Hc8?{35Mq+MqG-fA8Vj6_O@m`06I1$av{Sh3e z)lz&ID3g=3D#N&s74jXpq9@Vp1xcE*A`+UN{2YM9m?7Rm{4i*0*B@i=6UZ5YXWbI6U7L92%XG&!JEAV$JB6x&J(OzkBB}*s{}f6 zzFrG1sUIJ^G2;)09s)ed!~>&VOBOS*V7Q`<0mBcNwilLE=9*yuJvy%S7U_HAn#u^% z%t8oFYOGM8VWFux(&$KS1QQyjF3eJ3=Ki1uHyC0to?%Qvn_EC8cXpMtNrJdM?puP% zrSgK7hn_~GiT=VGgE#3ycVl-CRM`-`0M^-Bp147e1kU8i(ODeB$1FtJFdcbQCK#3U z8<*?)GB`F7#v=K%!ykBihrHH}Fs-4z8%?xL=Dc2HO#q{hywFZ#9fweBM(aw-e{_80 zHPqz9l;cwF6!x%2D#9=7q=&UAW#c`seurjY9+jurR{r!8=q}as&OB>Sz}+E(H;o%`nF~(vvP}4NUbT`pK!%$UCxN>S`^eB?ydW z+AdF2DW_8?9RxaF2T>m-f}1qwJ(zX*seU z;y6d{RO0BY!#?-i9a~t6FpM=M{QyCmI+Xj2g=F;qQv?ub3!KCun8S@PU z(T%toofIBXoo>cCU@S(}R$p5Sb{Xk+2ujelp>7Da&~#%C8ZDukP8#O>_&e3WlbeT@wsQ=ZE-FDUO^cO_4X&IJzv z_@Y^a5D1(|e*%v-nPb#Py`fiQ93j?#F)Ca_TcJe+eD>6@IX;+s7kzz$dK`QbZ~?+6 z1}*r^JPvS#%6xS*>WwHzCkS!D67X>}uPV&^tmf8f1bzsH(B8{A1OZ?jVW`GmZpzM$ z&a@qLitklax@ZkC4#4H`qQDs%!p6N`)9B53sTtP5wr)Fl6YxS~AO(JUG)5}TI`BV7 z2SY1xH)*>*t2V0XL9>0{cTu8^g+>v51rX=mdTjPUAUqi@$D5Aktj51+AdcMwK#)Ob zc1_ET`HFFkkcJ05P#u$saQ3j@i_Xq=boO@RRQU3Yety{3TJ0hhTJw5eTJv)A`KC4M zxTEXz=+I+;V=1{Kaa8FET?tkfYERWyZ40E(nmWH!d4%8T|DKbW`}78cv=#V`8JRJN z5EMFWLimdLgbfJBS;~ufg^fQ5(XXx)R(N^P=MGS`p;PDvXGYCo8jvzS{pfLAsgK{N zo+H9t9IrT{F?T9Fa|S^(J}nqP*A3$7iyieLmHq58I>N8qwI|RSj^L$(BeV<8+}_Qa z#+~||Q@$BAze_X|+i7uBy&OXJA#20+b9#JG7To+47&ssDEP?PW?lyKy52q>Qfo2vS zx4%PQhj$WAP9N!gYf4%+w%+;1RN)<8MuRrPWf&$mFAgamVR(_5{>>aMX;B^)2@Yzz z6UlGqN!)xB1Azf~sCqVd`JN$1%WyXSP7ANfhs6|oO0iKs{J78SM#z4QMVBW3n4O9n zAui6GMVJLq!lcR06?XJYY4T_{nhYRTtv#bjg+&bnt+1wbxxD+Q5a}F=!8e2wZ+4bIkW)4)lE)5;pa4M& zu_M?3R-Cb$f-d3}LRk-Pzbv!jmooG}x1A1c5P!NEeub<$)ms5v``7HY!+*b5Z8iu|Z6i<1e(Q zH+FWgz@cxkh@h10vVy=NK7uOBV&Y7x@J&^`09D?HWfF%Na$d5N7c>N_>+JB#9X3fA zaUQhG%OXH^s&)$dh{nzzEJ`UK?ZzLIEBy~`E$#y#EDLi8 zT_$tVgb=I*hY%0cfrZSVa}e9xJF4fU84tcxS&Q+JafMTuDUF5kDV1L^VT>_u+1-YC zadvV}M3ekSR0k0dh7f92%3VK6j>%Ww85FlP z)SGx|DpwgN%v)}icd?{XhRt%_re_z&Wf7&fh#dNyld^xt^lyn&#m%DQUZqYrf7hK*fhCx9aj112u{IJ_tsL)c#qUdo^UGL$>#1j>(FX2Cc1DpaP%e-+t2>1}6g z{glkWqqkLeOa)Ch$H5P4Nk5J3WLnuBSTCGyEBV~DkPbm{lW`612KKis{NM4)`99r; zj#xhVZIkVrHn|dPSdsj#(!PbhU5BrHD;4FLpEzLjuB;e734qnG$?%x`(y#JPuo=PH zq+c4_i^E-am_(Ji4J$Wg$lKTgk17~-EKV4lDbw8`X(2Z0*u}3j9ZZ{i_*D~@4y z5>?vJ-q75>7fG}@`M_Lb7xVze`4P-y(P^p$46r;QVbsifA3LTs1iQ##`f)-84$rm>T|~ zwN>8>ttU7F{YG%eV+d0l0frJn1)o$QI*|GzxU$e|dOF{tH#u5tf9IL#$0N~>^P-W% zaqd5O6!VRi>vEwsWaqwCH_`9)yhES05)58zC+ST+q5Yv<5qz-I`daH380(y@Kv_>t zQ&R}0Ic)-il(@djM*YESi0cd45e!`#_P~I;rdENndfe1~%*lxu_b6$C9?bknwz5SkQc@x|bMcI3ULo=|UMYwz9 zh{wWF?hYGsTr_0Z%}@V>VTZ6}XJ^mlr;jf#E?6_J(oCZtaAe#-aX1EzKD3~9CBmiZ zE-v6PfiO&U@x3Ejiy%~EO~85y;hKeUg3H8I3fGpFmORYpD=_mBO!(9c<;hWQ^hb=> zSOrEFIKp_8KgZRPAG_#*BU%%zwdx4J8uN~8!9b_0elc*Hudc4f%Ib=I)Hk$N?i~z# z+6QYUGrraLX>7Eh`UuRF2W>SqGiO0J0*GpSP$nMAKv}P@&b0tQ`Ku5|OrQI5IH@pP@eY0ZxdjvYNw z9~p^OqhY}{_X>i4fKwi`#t9&&hPkzD)NjvEIeM`Z2i;vg`&uhrcswJ7V60E-Sy{Uu zZ-4){V{v&^>(@LMm9-qW7`HU=#l^My&$-7Wf*Fp(17|EWThVScRXnZn&knVYKaI}bP8{|2?`ph1d$FtcQ4EewtwD64{sphWn>7S9@D*!xHM8r? zcu`f1XDQf>`UT}T-$roaUTp+ljDhSUxp|hW27nt>DL4om!`)GJkFl9(qUkfwH5yuv zD=vl&4B&hEE*eJ@qt{Uv4x5_Nyf{Yh&kYuvJNvP*bD-t!bc|2e)#ltAg~n29BO#3O zW&yP&d;!{acW+l?x#zy$tRsM9vqj=hj!;F*ZEt_yf-vyRqxF?|`^`u3#!D;Fn5A)Y z-tl~{F+@BB9w%2Lad^tHtXJw|xxPSf1AI64@@T`Y-F?lg$AMPXYcD^HNB7s&FOK8+ zi|sf*r=03Zf-lGDfr}Wk7N)xQ>+b9sEF`VeCfe1Hbp4D^EfJ%Y5^Sv1*3V@hp< zU<3iwv0<5lUKPoL4vtYAXpX0iReWnKa(^A^G8U{Ms5YYyQLw~96Dl11` zPT~h3fxOC-dI|9EuRZ6PKM4L&Tfw{I=u67#JJAGZ<~izXEzCpaOtn4mQ(ZU`wYR@* z{5UZ&<9-EA$MKD=`mEZSyI1!$A1(`Cn*RkK1f(Y#t~lZ_fPazxgjmM*irZ{8P2A|J~?x5;r~$d|>pVAMoX!0rZj*9t-cv=7!Y^O&A|< zV>H1#lOy`ajKbL0Vbjp*`~~vhTThin^_9tF-sx85q|WJ}>27~{+f8qKVF9_6FaPSN z%EMElJAQ$O?YNf^{5U*ml>A7Wax;lm;VM)7LBjI(Cy2j_=Ld5ql2fSs4I{IKR4m+O zyA#Jd=ImB-*8i{!<%jUpi|8P&Dte}!4q2NtZfB%V7_>z)q4bv(Z`Z+&PC3g~wZHx# z4v3jyGCp4>R^{lbI3A&>A4!=cvk((O*EmF!7LOq$c&)kFS~^U23TFhU$zh;LAL69d zZhAKm1QUx1CR!7kngsKFeioX8I1zDrDZl2zvd=WP8nq@r@+BS@S8^N#XC7ZbxGFqn zz+a1arQGboI@Lq^2-UoBB`+ad)VSHD#|}y+N)R#daZQCZA;K?3BwjG_X;PK5iBWb! zK%6l-B*1mcS*a{f4njG0x!wwmCs}UYGXyzpPOSMbT3uh&X5Q(;7(d0a2Sa<+m3+-gssRd($ zF9;hJG-wQRTp@16Po}I&!UV7Id0Yy@J++nU;$1_f4wTPYXZrN+Q^iME27zg2hw99N zj~#53*8(_%kc!~`uZbL3ABi~K+1iQIBX*9Ci6|?_j8HbgWn4rS0yT&>@0t>EM|xv7 zV^N!~iC`5GHL5rWo+%8K0h-Fnlep?bd!#!i%TF0#9uT%f$@s+Muf)L*D+cd0imPA1 zMQDE!PcKF`LaRz(K8#`?!s1@RKvq8Wl&tabpOJ-JTso}GFGf#Q+6t8&qD026GMP5P zG9&~};!{kfssP3SN&MtD&uuzxYdhVB$V7>!_b2?a4#lnlSdb)pWwI=pgi}xi;@AUY zyW9%wNAZ{alWA1O!K*~87yX@ox!+CJb3g&Oe@PoZ^~(x&e=Y6uwvnYONtTbY@um7x zi4wTV7boBcbZwVomVqd031wT=E#Z7y4jbG^TTU*iB35<_jtJ_+h?n+KBPEYR@s^Y0 z;gz2bP8rhRS(5N~rb2{aSQ*kH$}rq*1exliDqBedcPzuaWMr-2VYuCmTWtK`>gd=% znM~y_D^4CuwkvP_R$)EwmVQ4B%NLeA#>D{sGRa)JO`E*I&1t88gu2ZmE&0j~3YaQ^ z^c=!NKUE0{Nf6xJ{v;;HEOXX}5RO;O|M$=SB%Qwo^Nrx^8}pkrjGeE(!9FXG&&*rS zjBmPHj?&w36;>ex>kR}5&?W4+uFd4pJM4l!I7y~HyQN`19iPE$6}}f815*u+Fp-0z zVMcw=2^ZOO(fWnxH)!H>ks&84!?9?r8__ka>(D?sQ`#q|2wX1AbccxrEsk&q#v%;( z>V6gkEzsK3(|4h&07nC~Mh=}8G^UTA6CDeK1V%IWU$CPenhi|DX1V_0z|3awAao$} zBg{tVN$7o;J>(5zG>>MQ@y>7VNSR{?|J0;t+bat@V7Ms(zqvc?;NU>(0CpoQZNY%k zC|Fl8jwz3|gP1=A@uWZVWD3eb9rJFqnvW5pj;F^5vH9e~*m(M$@5)$OT8r_i*;ra# z4~_wXX~|J);98Epqn>QAg0^RkM4e$ma#S14)l1Q^90P@Lh|B3=bU`Ou>qc;a!B1S; z2WB{0bs|R9a$))$8dWi@Ex@`8*dHAo3Uw||4X=t!;>>do~m4$}V9gD%qnYA1^3Xb&{415^j=NDIA-*J>z zPi?TX*KvPYUTDTbv+niSUgsdT_V(SUU<~#T4r6b3Uw!b{ba=hdRNlE^k2XCR9JxJD zQa3>Oi&g?gA zuCzv!)|Cir%#2lEpr6xTXg#52Nv}a@N!`7!gtV7I@PlxLyXFvnv5w6$^*d=gAu(6n&nt33Hb<6?esOCs&R&1QQ7OQtJjSHry<@mOH1Ez+k1# zXiqeRSQ{~(I7-cHPW4v$F`EffU|dcr5gbf^mNhTq-D@uH%n@wqvy6ebK8>@(ZtU-F zSi=G)>%#JC{NC^XQM~c3?*zwcF~)!!u%|C`KRIpegyE4I9^fC1PmNv1EpSHob;%gTU2fy57wz0? zw_{~x)q-FIiwcWikv2R*2&cX?=yv0c#hK7r9AOOt4DjZh=0P-gW)O<0uT4)2M++x; z?XCP+VbbCFwD*_dSUuf6?PsTmCV|%X~onGG?Vb|5S-g;>%UU{&f zHbDzi<5y6f(ipzEW{$gzvyq87znM@wa76D#@@iCwt82km@H$YLHn#RGaOCJe1TNot z<$l~>TlBGW&o=jCzjtVX3Y{s1yBu>orhbXg|03qtP|&W$+EUAPOWqy0OK;(8`a1%q zg;p(=g`?3{;)qbRBpKTba*nw~5Crb#E;0+p1((x{ydRA5!JT4g`ygxu#>_p&M;;gI zv(|o7<%BaBThJE=8b=5gp-rsWs(Hj(xwU!UvB%My+?6(`elV-{3&HJJ>7Sh(Tktin z_FuA4Z_0BEg?3Xe(0JB91;+?9XzF&m zhr%=T^%;+qapiw_(DD3X0A-livEb zpT8AeZ^GaD$3Z^S6X| z+3$Qi4d?2Kk$RDDRSwtH-zuO6n4>rx3n|`&p-$L&Ic2Bge4Tz)fdJJX#!lt8GQcAf z$~;T-l8!>_oz~m*AqIeKWw*D(Wn_Zl=wETE zoIK2g8hVirwscFl%gyjn%{1ZIE;om);ttE_R1}TE-`cCNqCMhDdEW?O-e`in5%Ls1 zEhdpFnl3B`K+bsv`FQEO1O!PXydjQ#iLekmJ2(+$kpZgJ)0zYzf)QGEDzlr%->itJR!kDxu|rw62@uxJ8@H1 zqg@x#J@mX-RFCm&UL(jTXi*YI1v?!U!Ov@G^8 z5Waj@dEKV%myN^dFKrpN^0bTXyzP1WE`I!ZC}X!jZx_wq>E?fjwde4amIPa6FL7|= z+s^s`VcJft62`XjTe<76noDuR%do-fzIw&Vk^BvPJHdTlEb8?3Mnu5SDT%T|P5#madc;xBTNf!(*y^ zd1IVjsjuz0;WYfpvR81&*v}Qr=hhE<$-i>flm0kiuip4!P5W&L(mg%%HFVPNZT#x( z7`JYOv5QhPNNGoX^I!Sfp6$d(m4;)g{B#%F366WQun_>qDr}~!d`K%D|J8xN z2IHd+zl5P^pJ_hV^9#Ly{rKOQui4zB*#7VLHvQvsrLKIOJXF zHIBY(xQ@_*Fw_tNahKQJ++>`e^ke(^lj!&MqrJEoFTeIyEU!O^m3t3-%osR-e{VZB zH=ag^J3fvE%vP%ZWD0?lE&{65%wesfy2;P@R&`-#Hap2V0t#joZZH-tyb?`K8)lyo zMXQIo8o@<%+?0@@3?(cm~GnAvEw0N6anek2BJQy7OZU}0#pu@5F?OK@0SYMYTw zdvhcm3{UP^f+@;SVGTk5fFVm=s2dDQgo?Sbj$<4}%d4E#+LQ{@ZxG&DGfDL#9KtaA zBje3!Q$GQOc;w5`ab8OmW?RC1RPdhkW=%Hg0XMYZI1UZXg*=LFGUnLv&*n|_OValy z%~LjMs!XiSTuzNg^;sV?rnZIwtV|Rd4LLObwD!6@)wG+N8=fvC~Sop6xKZ7nse zqd5kbFm7Xw8-!{cngg!}M*ZIIPHbc{IV+74A1V6_oSFzt2#9nV;Hw2X&0l2$&;JYP_H`JHu+u&fdzp&@#)-m@vBv;DbZiPY}k#Pf39x z$L=AdrylTQpjmu0rqV#0D)9?K8U#3r|BU0=ysh~1wmb6~?ar~2Y?NW5C85YO)h4`X+G(;N9|$F-HEc;nTVJC~puDtf2+ygKW&iO~jqb369ZR zB0Mu9d@-$d@)4}6J9vh%$HsEn3c(l}q0obzq=jZ2aH46cE9oOp)ZkXX8i`Adbp+=3 zAFRbftFAFH;?3{06`R|8-2=~`2naa>vQh3wYxusdnOJT$d`B901 zj`T{V=GLLJC#m9 zx}Mp={sM{O=9Gs8(c`?bqhfHT+~;-arp^xj%WfLofTm%B9eAs2PMdhg#*V>fM}UqXE^pk zZzf}qE_F*JcNhm+EOUN!mj$SZ4;EchBFKE!w}`nUfFRzv7wj}fH4&Xc%!jHS8?NAjIf*5Gd4- za^@m|9XBaBf|#b!QMLCmfaIl#hJ_6T1aW~Mf;EVcs$a2-1tAjgXup~WY!)#o5Yz+< zqe1b#2$UQB$HcoH(oR8~%Byl#T6VyeNg99hV|NTNr=BdLD2wlfU?HTmStPIsqZR&)UVy1iS)bh92!V{i>C$Nl9`d8_5j7X`NnA16vvY|&NylSFFkt5leaE|_ zwZLI#&+$?2j-t;%Q2E{j*#+iYAc#P=@DC6wJB~K2jyj|)eBTPYXf5zaj!XI~Er@$| z4&2o4f*;{M4k?&@6iU`xJk1B)N%hkon3|Mw+~R-R(F{MO!yCU0EmO(_t|Dy$q^6NQ zWhcc9M?9C=IESaaaMCLmMd_3iC?(U|jC023PWQw^b}AMEVE9m}9gaZM zla~UNxDMld86Uh8)@jd|;bZsA!@)5QmU!PrAmA>xj4IE{T`#9lzB6@xF|rY*Buogx zI=`xpdhG4+#p1LwCCXrD+JLw?mC*cxyRhNwIZ*GU6@(X9VCWlH%0wGyOiae}H|5Ar zXP0xSocMOg{J@SOxaZ{b$+$8On-MasezLF1;yj86b>|QKhZkW>8qQPxgm53^PkzqH z0r4lE+&>wSP|l|ZP_!uD3b1*xglh}QKDH@D^e0a)58l5XK;H%655qW@Z#jD0crtf1+gpqnMq;&}ay)C=bkb=yjNa^YeKu z8%Lu-8!Bm+3)&Y!4U8BJbR=402n!4r!vigTgf!z`W8{WAv>{T%0Xh!`9?WzY>(Kh- zPgL&MB5ec#9Dm1{L+i|11j+$iSet<%mq)On(Zl>Tt#1Sw2q;K@Oz?wA$5E0aBK|g? zKaQ=9r^dba?mdi!)dw*#HRladbG3QXmfg;N>})=d-R&1~ba0?DPsQ4UN3nAMfnZnn zItr~Xj_cz{Ei@<^^EJbidc(+_p5zED=xMdHVA(xD3yPiEeZ$vl7}W_n8BIR!Vad4? zx|j`W376D93BxdHPBxdp*k)5)b>vjS7$H%0F@C0jwwV0Y-)IMpg0f9CZ7!zuz@&-fTBi-b=Z4qptFZ#w&>p+O^Fs0$IVfR)D&O`e)jt-t%bY+Q+|wrTsx_i^k%)pI+OlNT@kDT z4|oOiY1UX^4B(%zM9Trqw)qrJs(di7=|?axfdlbbbHc2L@ts-?9EqkmRr#_O;Ydw1 z3|R*=CZ;B*V_~5cEy1l`ubGhx6WtFCSkl> z1iA=Wc-S1udQMI3GJpqJ!=d$6-3vxvr+ufVxSKAuu1JsdUaq0g{6j#R0)eCf%hBjwhB6LN= z5TSsX`Wg?c4KL46H5P=AG%hZVdvS8urSrwS@DRt{Arz%QG@A?2US83f5kUj%RPsf@ z1=CyUDPPvggwG?+LSyOFf-W@i=xg8*pGczq4*uXo5j2+&AXpfKaFaf!`XbzK7b?*y|5sXJ=pU zLu=a1*ISwcX5(CKf^dYnpyFYe4Je$Hh&IT*chXxZ1mJ z%@j1zy8ROiWR8zDkEm?Sdo|$}@DqKv-{)?l1GVW$ENHxO7gTeeO%!8pFC`*4PAZ+_ z*y$X_uJBf`&ylLkuV;b}!qd9v9?HU;h7b-g_Xo$mca44o-UBBgXhA^39gqk%&`#Xh z=_uTe=9KIB_N(jh4}b8jxVO@d(W^796PQ0Wp9+tSPjO%6LYxWhZSVChprAeotJWW$yS!Q=dAAW*6E+d&c5KUxCeqieGvg)Tkt{vjIiF?c1jZg#{H#+ zH66i!^qpPd>ut?79Iv^y(u{lZo1UGrplh#t6um?63c_FEVZj^z8~Dn6A>$795xGrR z=%lfsbSZ!0Jo+u|OMh3%1wim7eTO#i<_)>iN12yBPfei>DmqAGa$2xWxnp~$n)Q@FG|`QZ_Cs3_p|uJbb@ii~`oPg(5RX6nNPdU0 zwzlRn@9*we1D7+Fz(3Y5M3~vu{HJnxQ!5%_YNrGBy;HSuU-;xuaT=PdmNZu9XUBcK zChI>mtDu#RMUQQ6?Zm3!`h#!37OnYNwVUQz#<1!%7_d=6bcbkw!=r(P?`UDosZV*s zfXa$rVMD7YPZEHo^9+ZEaO@Q5+pF$OFrMwKQW(9+vE8~seD?zzu(4m^&R8+{3|p*>hPcc z;XgCa%q_})>6k-ioQ$o*!oZI3YuL>80gK?LSH&o^v!1MoZ25t+O|_7yT!uEiu#=Ms zoJ`7w=uU>@N^p`Lez$BXy{Dy^?fak^AkrZC3=-cU5Nn@(`PAkjoe?3`dTk_lR zC?&&7#)J=+k~XEXLj}9aUx*(kr&wT;{vw(jOR>qs&icddOw*6FlR2um{NwG=DMZ4~ z?w?DQ?~;=Wz9LSr|DcZ6s%=2!s;ZKV6h z1tE4caiGOTX(u2KwJ>CNr57ZcfGH5dv7W;1Z*NDx)78Yr1SjG`^V^#y9<|bRf|LK4P=)CDrmlK?EP#lKY5@na%h}65i}q8I=`U|Q7Sj5uh9eGN|L)uI z@|&;4j0h!;hw*VR@?)nf3wQT1!5P9KnUg9%RnZSSY&jl=z6eu*$&Ljcs^+vG#PkJ( zykG=z0D)#AQenNL1;{8Mf*XLsM0%`=A6P*Ya6UB)TQA}S7vN}SgbIOB5;w|$uoI$> ziPc(l5bWv;5G*VZA;h6#=!3blO-aa&MFbNsb#h$AAt+_V&BT(!t3Q$iuCiO`rnJ~W zN_`bsgkSEQgYX1Oq*W2k*IEeC+f&Po^Psu#nneJ4i&z%SO(+2y5oIuDxYQQnh6N-* z@(wWdQ`Eva`=29mz=<$$eD|0BSa>3Us740{rvUDhY zRCb5`*l+pKN514v<%_A399984fr*^9Dtht9FUyQ^9|M;9PT29IAbKZMOHI;R(jW=y zY9E<&&9=aj0qMIr-`aN=heeU`1m)0QddoHptLS{o$Dg-98Lq^|#T!@jS-kkwQzgRB zokS~RCw>S^K6a{N`GeF+n?8i!Z2*35+sh$crs7iS1X(1sqwl-*z~4>|gJYFW@%or? zy+{|h86!HCG?|F2R;A%@+x%5b=6&meO)i902F}BFxw->n2&aPucU!5~b^QB3`QJ$H zYcbylzP>TPtocpRb6>{focHBT&fywIdVee~Ry}!t6j~H8c~TQZl#e>fSg=dj3|G-h z-~t#P;21XcK+{5BLFaNbQGIUKbThmCd!lL1FRm>BL-571IULIdb5kUfXuI<`lLbZ_ z+EE;72%RRfNM+4UPCh14w4fQ9mlrN43_XMbFnx}QCpsUY1E)N|Aco;WU7@9F^D}1n zLuW$H5uQ7)pvS2X+6xHAnAg~l##+G}q4Z7qY&e1u3%$oTS~q-CZ-i_dErvE1+GuFL zak>Qf3Pvo#3pQT$d)?>{`lbu(&4w8_9ErzzWlrz_(lCD!CQ&BtdqVgFy-OVg@aT26 z<9Kiodpj@Uy?1^hIGx4!e)v1_o$vpy(wg-yZkW~3x9pJSctV5^A~NI5Oz2s71#KV0lv=4L3nAR1vFYshdM*c9zQ>d6!6#W3Y8RjJY%#35L zV;-!vW3g3pe?aSmqu}qcO8dA#Nt9LB!diQVKJ)ycdGlXp!1FwADPCglF1 z$4@tWe+@GZ$A!U6M-z)9rcO@i_bRj2H^B3Vb&wgllS*^mYXIt-8WPo-B9u0ob9KYY zno-J^_45R4Ox4{Q12F1XFKJD~I*Iz{IwJe%;=-by1q)*?wVuEaCL{feGWcE^#b>?D zy4NS3sEn*N@{Sy>>*6A{b<__$tE+66*P{*(=Hh6qxH>m89ZfHUY-l8r_vG}Pg@5D? z6aKJ2@a9sEP~*O-yju?;aiuMXK={mSK;V*n0){D@2RUwR+Ayea5<;syQ6rh9v^~dk z@viWdna8p!iebyq_NGUbCc;+WYb_`F8_&57SbyT4_>VkUYoaAY2l2h$>Jtd35QdFS zOuNpU+5vMOfsTcl%9p#U(A*jyxzM<{@DXkI*VkkH-b(h*bB-3%TG6mY1BbQ0#+X9G zP!{OSzks2Oz>2;I^PaUI`~Ywu0&)bF;8ciX)_&9l20V4AZU|xM7p##vuCVGe^x;Yq z3t=>P5vDwKN3eom9lXcME5MjO4h^1t8r-jO#}T0jkyLNez<`U;j$-2j%y*6#YpU+n z?f_PT3j#ClGDGl89b;tNIH}t^@ERAvfI#PQFjv!9xDw72jzX&mMn83AJr0gQ@L-J( zMW7E|UY=U8J~cTK(@JBpsqr*D5+{RR90->ql&#I9X{3IqzX^mKH)GM&nCE!AQ{gF2 zkb#%eT38aUn2!r!sp?HkPOJSH0|;?BVMc3t!<)^_XiEZHV4?X-@VmMYOoflH)%RX~ z`K5T}wb!lbhQI+~On-3d4FcW_g0NKcDS~>mguq{^iFXmLxd{s!)E(Wn93jfsV!lN% z0sNUKX@9im5Zib9Zk)_V@Qy)?<$ifl|0|+?yKa=bIi= z)V1I53HM#ay_HtH`SSgEX?-CcENkAGnTXv^&)U}W&4rkoZ%6L{As*vKupQ^FMbQMp z;oG}iYiAGW-p{doWV4`M@e4Vq*xKU|B|wPlT$>-gx|rux=Rw3==8!I?Nwe?zkl{LNa3 zd4zFD4|o05e&A@|Izea8|GxQJNKN7TJStJ`tWc`1aVhi{_nrZ3$|=kjI|pYLKw=gISD}R1)I2>9jz+_(F*g~n zsf{^)u%o`YwbxhpzHrld+*@0W@4fYUEUDc%+LiHxPO=PL6J5{%0c*aE6{c=pCs)X#P9DvS77A`)RJ95k9GD zJS@~EH7+LO?066xPoJvK?7LkU!wZXxQE${tm!$Sx!)>@Pc>Uz3ztCLNi?`o?D_+r< zgdRcocPSjy?VrVmk6&m^9tkelCoteXkRZRGXH+$tZvvrUwh@1 zA2ImIoXMPt6a#|5R82|QybIZdWH^*J@%&a~*&*676ut7JJK=+W`eNrd{i|4nG7w66 zAlmu!KXD0U7duq8633oHdzE(n>yNi9mvPcP%aI`qqnBUuw>?wI@|QSD=^f%FGIj#GM@hoWPq+5WKCxE$CDsjmWvOiLU6wF(_skUba~rBj}{)-aVMCyJ@CR{ z@wfblr%%GV*8a8w0c~fofIolfpW*rUH-F__eA17X>S*Xy@$$z3@bh=pDE-Ty&)gQ0 z1<{UblJYSIYOYEMLoDL)4N(F?>_ssIf+iaTA1qFpTrY%JSxm5yU_qRBa*5#9q5)!- zNfE+3&xJkr!gTZ5v)J3(ic5u8s!oeH1Tk>V2~Y*16iV9*KD{q5Ij2|1ScHXVQI!#b zR8yfQX%R>TVN&L5N9vg-7=$*zssR?11h`;s;qxg*xPIyWTHJr-B`vy}nsCq}%6g>0 zM{S{oU;zbeAv8I+JOE^8uT;Z#V$mMZH|$^Zown{R{b5oAuuD2nQ@LI zfGNX{Q_2r<#yiKa{}rCHWB-_;@N!gWSqmPz6DDyNA=1&zbrLG>n9PIkd{>6=9Osq4 zBc`2qv12lF~JZ!%WQ~6b49qdk+Tf9ygu~Wx<M{& zf*YF*pMmqqS6YaVaTSSI-1GJEKLR^H>@t}yZj}q~>W@!;bB?U~2gd%@w;q?C3KaKJ zV!rf?opRlpyK&3U$BmqDH3%H8f`>o+ch}^X3!t!4}h=8&|+WIYIpss@ESiV7IX*<(>!)6=@;xi zHgIw(YPFeYHS5vl-rUB#nf_=2;pd&j!i5Mr_PV{;-Rs5HUN;U7Pb_TU9#iN*n5Qt5 z2gj$e)9J^~!EyACui`+@$)#}21V?6#`)H!U5zNR7?>vU-2LqV0ikvdt1%nobDcU65 z1%Y4)p#hhwbDTJgc4&R*Ni<%d<1sL}>Wz9V_^y+h>NBs06CNfUhfQa!3!pK%BbYiv zRdI<7eDzx~HQzQIITDIv#JjzY?_CjD852`8YG2XmV``VN$v``U9&ex;`8RCOc~aA1el}uQ2o<1Q*tb zqWtPt9M8u(mhC492J&v@T*o3D;CMZ>EpcNF=40DbKgRIA)nyB4wzr?h){CcV%YN+d z?L>EfSAbXB7hFKzz#m+Jz_!(BcwE3Nh4~LWNE;?H0#WkBZg{YXPxWD)WPz{ZHX1GA z5AKztZc~D{U?Vs}sQ?qNp#@aN8-0N?P#+#>Ew8_2_u8w1qt|j;%WLg?ae)x$R4`OO z5e`T}5i|(vxlG&N>SkV(seVuqtlRbPcFXk{>sm?$GaUbLe>ghko-)>&TCaj%6rRnR zo$j6)vIhus)URQtUS4ags4eNs^h0nU8i-TVa~exyaU^_)2Fu2at=QPuh-XhficP&Y zUu?$4^NrZr-i*%fj>a0}vadeNajP6tsqx7`mZ1-`5t6kq?Z*0#Iw8myYFerA2%s2y z-XJRYv2IMQO2%5**eU=}cZ7}PXmm`^plPbHp)`RN>u=+B<;&egj317jL+Hib zPV|pSrHz)a`-j?*zD!?*@qVlQie?;IikxPGaFO+|Jk&t+5t!M`H}q%PA8i-F;{OzZNB9@#Fmy8jAPk|z(#;)&!5IePaek$!FF$VFSzTBI&j?NVyhnYIRtlX zoX{Mhw3#E&5aIYbwD&kJQ(0@2v-W3$F9OI@Gx3qnoDBBku(#*Cm8kp5>RK!=titUh^3+p=|au4`)Pp zcUp7VyxW}3nx{RLatr(p! zywE&lo?w3O9bZ}lude>EywFg3^cCh*m0RNx-sHoF4?KQP&aZ;Qh0d>qYc-x`=ITN& zQ_(*ZZO}W4{r+iecMjv}i*9_h)rrS1@_Di)I%My_8=AO7?cn5E^xb)Mjz{A7a$M<- z#KF;pweb!_+nryDuF-QaIE|jh#Nny><;{4UUX4fh=rZ~$vr!wk3}mK;gU)lbDNBpi195YXx08X?z0=3|;^ zCZ@FrU^j!p5{ez9q>D*n8Nn9&szxk;;TRScvI=V95=Zf|s7OKpAr&!M__I4H7f>wn zNS0lXCL9j5col&_e}quvuBmZNG7x;!hjZ2;CJ|Wq{AnR(;`^9DrH)X-b|!TZ80;2- z$VA|V9m7Nf5e)$k@%d#;HSSD37L$-DZCaksG$I7n9^H?1O?*?D5ZT@2g6p3J0RkTg z0EB>~!=k|gBh{0g6Q>BI5bEfUMUr>UC_al(@0igai!}t5w5um}!4x}-YJ@bouxA$} zJ7rQZ=rey+HsTWYQm{k#W!NZhmk+`n0g+$;K?j3_osq7VCP*(vMBMqPL)C%ZBlH7y z7m_EFs{4f!tJ;G)vp{A6NWj_l-aANon&5s>+(Ad1D8f~cH!(>Lk4UV4*`g;h$I zM!D8Pkg`!GFDeCd;Ki;tFIM%qUmAw$uYxm+PTiyMC6zVJIZX$JN?n= zIKGC*Fm#Ds4L#XcQutjxxa$vG##7vk_mqdfiR}TZe@Dn~{bqWVdj$(T?3UlW`QbhE zqm#Xi%YDgZC1UgcTr zRLc4IaRoEHvrYGWr(ez)Rk#X%d}i4E#;*i%nBor`Np|B#y)#V0GsEPQ=@vNY4?HMSedwv#sruH%{#71BA%+8_ql1*N*&aNV z_icC!XR$kcy5o`cDt$pegve00eRB9t=b`a8zG)en%nRq+v>ZlH_DAf_ET3ZB4R9EG zXPeu##LriLXa69q!a0TX=O@FFNc!C7mvIdjrn5pWofkE zg!%luKG|Y-!=^p8vr9NRF*Zq(w}_4ypXUCO*_f`)``D+6$r;laFcT0S;t+YU26av7UXKZqay`JcqQKmCi?dj2#HyL%45ytW>%z4hH#d-#ghO_LTLB8WL; zXZGQt%U&_BeWHV4$1!E>H22X&YCbc=?dQrZXsQ+Sbd zG)Go32f^fCSy@nCXgH+cf)hMAiu_D)Aq=!R^_bE6j{9>t;;^SSqfjv3n{~mKGOFC% zpL23@8-Ww$fI-d7 z3@lhnd0nW=qBX&hcfh3@^OK6h*rZ=`pOOVnZS^0$5oWOtK==UjdZ@KSzKWac1M(6? z1P`yFF3#d`(2d=#r_tGc5qsOuqkq`*SO@0szWej|#XCRs9aV?@ZVV1OaeUY}n#t?-n_LSr7W}O|xC7|?^hAB-#F~BJs=fVA?CkF9-HrXOaKmoT zT5t%v&dx72=8lV2TtB*!n8u@z15{gCyNk7@!m)0h^xQC`wn~5U25(et zQjHh1)WD(KQ^lQCCl(MQOh3>(LH`EVUdBMUhA`YqM%lO*j^kY60kFZeth)!L-l_)Gam~V0Plh7koS&Z5a5oQk8~9rk49M#awBM)Q{QK9L&(r-wX8|g zs5hhDlzn+sc=}$9PtC{R_`;h&wstyh|6`3&j?+73z5rjU32E1k+I(LRn?h(-?ma>n zzqr`8z=$J)(Uh5;5nfiAe3b0TnfWc?2FmQatu#;K&OC^wa!WXIW>WY;bwmr3%^mKu z8ZR7?iSQo*s(CN!FSNJsFjSi0&Zg$ehUR@VmUe{?X}^){OZC%^`>=((!guCZs4~Ha; z&=S13R-WhX_h<#psC`?l1>-LID_W6Ps?WUW4YcW~H+R(0N0~d0H3y!b9LCnh^LXdy zKaE|r|Niby?CTS+7AP$*Ektc*%9|^uH16O@A@l`z(-+WeL}PZ6 zai+PcCfHl6dm;tY2&@^e2;_|a=;dl-=1Rsh0($sbdAe1?>stN)?20?Pt~8#we|6Sl zog+lyo%;S$;RDjI&(EuT+y{r&^{CpJxfMDf?|wVtNMFHruR9Q(cNRy24Z_de{evM+ zW6W>w?#K4tK^z>O$Kd2r@Vin!gWoB9u1wF)uj4@U9fDx`5@X#*+o~+!|M^;7{U&K4 zj>T-Ke?Y%6?#*XY1)yg*5|TbXCz_5;IT+vTDmn!LDgDsAJ=sr0BXT6_z4hgonQO#{ z&vxPiJr)S6JRH4ha>J=$K=wSCTi4Gwg!{CoO6TvQ`Lz00&uzVP-SNvjA2*)1^fO$) z{Dw^mzFv9#N9y;=o{S*oJY{-;WI}*9q49$_5GrtaK$;993ds+Cc-Vn|63sY7@ZZqC z*lp#f0vj)yznq(t4EPI33{d4J!+Fa2)g@*r%ZpJe&!6SGp=mK&E+GY3zF`RsJEG| z`19#x6_PR!;1o}&%NS#XHBwjfMIEFlpzk-C==q8j+S)Fgs|IA@UqG3&*Wf+-{mvRsCW9^HJSRSdZkhPDNU|ud#&DE_hOVu zkoKp{2o$wuqWSI+_@pK{swxmVW&oHNhd|7-QE!d|AgmxG*vpkfWMCFpm?T5JEr=8$ zm^(Sy`H28cizNtI!55;Jwj-X8x?o2i095(N(`{+E0e8VoekS15_ej&b6jeU@rjG?I zWgsr~r#&md8#N;?1TKU&4P`=5ZZ5CtswgfGHAU!|LNKKxJH!UYM=YvbDvtfg(+gwy zd-7H~JSJ!iYkfN};7vc`I2aadz!w2+63ZN;i64t+G`YxgR1M?>o7^djcl-(Nz}|$q z!nrTI6xliqK7T2W-KicGQ~vx_eLNq=JKn@7wJG02yZ(mwjsB?g(l6cY?lF!%)8l9O zHw@#5{Fj{g$j2{#mpA>X_@!H^lfR2SJ^a44<3X=19|}(|<-?!Y`Lut!|Sd4~ON`0n*PFY*jcrq_g64ub0!df2Nq>@^J+FXSBO`*Y3RROI!NGcGs<( z88-}zr{mn26V*jZ6#F@dtt!`@KmHAChcDmGL;snWADoL-c7S`ELAt9A9F1>1r5{#) ze*3$sC)p&N(~UQddi3cWid*%zz^95_m6<3ulqx^y8EGXhVKQEE^62qLv1h)-(im2` zogaU4c0KH0zR6b>#<|ljfBEkK4wr!w));>d|Mxumwh=!SCDFzkMgJ zM0hc3#=+^um6W-A9#_ypiq4UO{r+KaNq*96&@<3W`WJlxX~Vq|Tf5!Z+})48 z-l3TpXcR!VakogLK5uQ9x!K8>n&4itM;1b{TOFECM3d>B8RZ3o2w_08+4M74OQ97z%_m?|&CXd^1QW5TUWXkcu<*s?$iVH^xA%Il-!fSu|9U5Ws%*X#Ni zDPRX(%Vs#3IxvlARK`}TX^ky*C!r|NqnY;N72UeKQfSz5aSUdi1i=UX1DacFZ&u&GhBiCJPf)-V?zN z+8ag@j4n2odBd6L%j2Vg*Df4s2n@NqiL$2va9ZVHopf&cmGx15PUW{21V?*an<)k( z4@Mj?M+m{(LwMF;t1C-pydmiGMlJO>!$s`}qm^X^bTtAt@+2PgFLW`}LbUTB9F;{_3my&*)CW7!<@n4# z+Ce8OlR&`uR>BBT(1Jp1=*7m9*xT9Ecsh&r!cyFO@W|yv@B(}pGaOrnzzdkuHxaDGN9P;WJ|w!555Sa0cr;3r^H0sH2bZQ#dpQuN4*=g1(-cN2xRYMTJ#4 zz2Q$`Xm8^m+MNE7&@sF&Su-*|N*@9K*+;Z8W!TuG7fPnN?Yb!Znu>0fOL7|5e`fFYYQtNYDL*yTUa)!kPQs1L2Gl9|hL! z_8f-($y$(pL%s;F5aw9$Q`uD(n8XN-j320n2_Pz>^}NRF)J$I0z%h&om|Ux(v4y~U zdYU8jG;Y+l5U3e1sI1^jZ+;+*a3+FP?mI`zWOf#OG37C79*4rG)&+e*V_4}SJV$Vc z5a-y(oN5iO%IqQ3>Gaeuse31O_qu`w_c}3Or1lT6q`b@@2y@cKlvzno&D%^_B2=QM!&ZoC&HHqG9Es-7t71b z7TC|u)uY~8h}n8eB=A)9`ll9pA@JfjLfQd5g@A*$23Hyvs6D|EXy9x&kEDVk1T z5In{$2vcz_WM62t)Q)rBL}EUJ47?8R4&xrfeYF7(nouY@wdyr*xL`v!_Z0$1HU{VE%pclb+~xP|$>VtX;k&W*{IUDUkygp`_a97-kXdZBnqML3*c9^%LiDoGJI| zar7;8V^?nkW^4*zqkx8j*UlhL@}Yk4O)KqPW>D}mxI(?n>36#Ww<+^3T3&1(0zS;Y zXdyC(D?!s>2l34NW>`-0&0v&E>}(f0qM)ULdUEuLm|zzU2lJ#A)0< zcCXT|{_rb*AbaL=h*}KEI(`3I!OCkLthU3YDv{OrnpwzXL zNp6H4Rhj+f$N!mI){%HsSiLz%F{jz8j;a2X}Tsk; zxZfmWN7Y9^8MpXhCkrQ`Z`UQ$a~#Uepf6!@OXQPfG^4)qb543YUy_l%#D(_5&6;xj zF{u&H{$yjkEtnOezd6Bal68r}-a@vCTjjUfGJVWqISD54C702RiE zAY(#jA|O6HOxRW6yfukZPbLNoNR~yb&$`x(PdtP_Uid0KkS)7gtpTP9#ac@$9D)?; z#UuoAjN$BYj`V{_S4m8KK~yk~EChq1PT8Cyt6Ip$!84q556pJg%BD|PXlORHvb#<*-qQLZ8gb@=QlQ3md zNE827G1rQU$&uZJOjzuqrER^-jylqwlv@@SRtRjUC+UzE3uo$I2_Pp$Tn*cS$jSmg z3l7z<5J)pITf<9vvSS9AL-dn}cjwU7DqG?Z0HmB0AGlK%ph5p(vF1r!f7FNU_<@M? zygpG?8Fk{w6c#oRbx8y#!^k^Sl%99A zx=nKt2NQ)|#T*#|QDDKW`=atuIxZ4rrY!_4$^bDlIVNI2L?N1q)ZgRHb;(WGX4`%&jMK<4PP^DWu!`MJ@k_TH&&00m_Nx9$p8Vla z%eyT8jlePmAC(A60{`lUH_A!Jz}HTMDSv$1oi8F* zKDL&4m`q1M!*CfEI|a8_x|KBiFF(V;euT+V`^WCUTKLD`m0!juy~NqKbK zDASM=Ke!lc?;TS7l9yoUaWB z9D%97Wo29{NQO_?=cm5qhJ)!63g{?ACN}voW=fh4B462EX9p{37k|TnFgQAmkNXkd zA@CbMC5V11*i^8>BV&}Y%OCiIKb##LyEDx1Dx6D}fXW9eu6-d5+Jn;>gUw zYco(_b|Hv@In8r$c&u>T{c>h{`*LI=28zG4&rvt~@zL`g-}S)`;7bt#FxA+74>Qa6 zyNF(gez{N{&c2bXhL?6gWq6UvE!Xx;PW-;I?;C=O(Yr> zdLGRi?f|*};C|e@zZy#jl=M9Tqh9nNf(!1+KvReGtZg(gVOk0y7fczRS+MteRoF3?JcHsjr<5*4Js&Jc!9p7)lT~b#n2Lf*xvmBdtbB zCjgR#!g>Q+GlJER7(YD3(}EA^r_m>UXh@f6jmkqm^mtX@vVhBdE2Ds~EZ`z63HVVu za-)BG4X1LlhIAy;U({LnZyF6fG~(zJ$-K4(7eaGuadDp!ePTxN<2X(AHT5U*pieXI z=p*!_X^oK-prdsuw=xc3_)~Y6OL?=-WTODEqaRZz){5NShZe;g+PwNEZNh=KV00rK zrEJ`(2vNoOq<$7+3$9)_0y~u#(0F|h9#;7fYWk!X^=0;!EVW&<1K~OD zaAJc2_X`e=I5JkaO|U^zwzJ>yF}2<}s_?AGDG#U3uxXZcEzJ0KyB@1ctyo)X#!_=G zW+oK)hD{Ja7#u(0`<^%^kfZ1jZX-CRzo5MZ{#g-zyMOOqJbd^t*6%%t)pgAu>-S=P zec3#o&i-D!|BH9y@rUon#>Ufl`s{Ih^!WXF_T+=uc>Xv({NSDV@V%eM^QVtvZFwPn z>-%rV%3|B_As_H98x5)}G!PI0N3Yq{U#yj>@e9v`zD9op2Y?q=SC?b0Xsl8XV2^g( z@$tFG8vG_UULY8xF24VYF`~Rx0OiFdka(k~AU5?K~>-$t= zNcAJlUjI0@cRKNWYe(S_BoE>MP4aW$OX0Wi2{hK~7C>>=6&kBIm*=kYJwG{)Y4yF4^J8_fqnH}GjP|_nxxSx#@NPW)=mT${SXo() zS6+E3zWvr4>PKsuBUa*DZ+$zy_r34Mx4!e8c=XaM9)I*ta1_EB#&Jx{geL2l7M>lO z(Y!dWxnKU%YGbtfMufXgMN`02Wd3GuAU-$;I!@J8T{SnIUR$e>;{*A=5Kcd0Ly>4Z z=0woa`DNmLWe`Uv7qPL8aC)G5dn%UO4d1)g5bbf;KhT`9ANN)ltc8arqy=AU69lnn z_(0orM>t_~uN&K) zLG0?;5ruCM*(b)QKtAdpCmt8jQV7634n(1{>7BWrd4X|<5LN(F87HHs zIM23~c3=6PC{4hjG>veEzn?U?e!9;$2J?CFVWvpqx%f8(N0Ra!UY_5CDT1#zeguL_ zMgx;wX5`5aM6FJ4e}8AjE&$f@c1$xuRDIlJzx_+MOq19kUH>{h`DHrx%x~U&`YEZn zT=wz1Dof?zPs*#e!{b)ct^h_|?5~IXt9lIU=(6$Fp9`B|@{f4=uH0P)KfIh``6fLD zrtNUVcfIm$|H@BxS!FMI4eL)B`4LV} zwyz#ibGUTRaJZLzZ6|)ZIW5C{(=(%rXww~&{89PCT3s_vB~Z}m<;4v5y;fbM7iQ3=s~DRnk;~*Hw(htX{z>B z+c3HMqFrUl;t9e}O_Fd^8Qd;P7uY&4y$xseO@v64o#RY^D~oBLEv+^nFNjl!?i}mc z_ld72Q(h3;BhG`mS9lLXqUzU7?z9_ed2tGZL6708Jb-l`Cvf4u#=?Mw2z?AybLxQb zigL10WRb%TMen{6jLF)i|728_9OD_zhBR%bf3c9w zFBjVOk{9Ey{5gbQ4w?4K$3J|hOYtf{`mXH$_lNVX{)!Whw{QDrxb)XI?Qbvp;P|mH z!)p06-FPa&2d08e`Xzp2z*XhJgM18&s&z`_%$E?w*rFfe7W=Rb^%(AU1D;jk@XGuE zc8S3hU~fm|FQfV=+kpVtUX+_KC1i<{2{ndZsH;i{Bl0-14J*rvDIrerGuHa|j3E$uZ*p;&hk(;Ai+r-Ek=a^NlUdZ93_1 zHzwHPmQQ}mqUYA`IK|E3967!1&tDa!`pb`m8zcp8tiLf|yD50Ytq$JLcRmOQV2a+v;P~9f_l$^EV|Q_*-tbOi?(|^CJR8M0 zf)5QU7+f%E(2_!{>OwRH7xV9R2GKb<7CncC!CcJD&6yF$eH={~`=aekLz%W=lTOk; z&|lEc(AXB3Sh!U)?TH_BA(JWoKB>XGcolYc>Dm`8)bk^H)`ySpE~9s;jZ$UEl?4uPqT1_TVCK3WS$N1~)5UngXXjs-%X!5mN4Ktdi$FHMa zn>0fj!53{fUvG-eOF~M<9C!*20_l!2KtKKjHj|ZJtSX}Z^pr;x`2Yv2z>ZzYyTJQx^ctquZPN)4U zI8avl1^s4bE;VlGKe*=xKZF-KqvyC~$)i=C(qY`f^vn}O5VWDCbE>|~{Xhe2A-bO; zgezmmN7E~9Qe>?G6S~{&d$;}I@Wc$q!y|+qY9GKqGHJp0h1MOTqX=}=b~nDcMlex1 z)t6K;$30ZsGu0jK3>p*0D90;Sbc|2lkd@;e(S~Gfu}-EeFhJ?sw9nZIN0cHgKC)(M zbq5})5Qis)QV6mVei-@`LK_T_^4L|UW*mFHR^Z2-JQYOw!`bvgWz;?}`?GDz221@r z3BlV(89G|_6T&-n)|`y18IFS$oKzNYK!qc69hOX5?wsQOKLj86S#U?X^gD%Nt(!+y zrZ!H6e@VmbsI?y9C?haHpvJ~ggvE@xycbRFMZUsIJQ#2a>r&R^;BRp3tnfSK27bAD zl{<6L=0PCMk(sm+Yk2ij^-1z~d6gCqz_7qi`J-W&T7NS!qx?BqjeCfem)ddv-l~sv zD51k=P!k? zW+z5sp*1fYlt-b_KM;I1=cg-+%NA@vZ&}@+Y%RomqoqDo^Lz#0 zg^kV#shF<@{nSj1>r3_3T8yFjr*@=`Ij%IXDAC+@awvQ>i2L`~Jhxw8j~ZX}G}nQ% zfB{EQjtG~~AK=0C)fNc45P%_cHx5u4LU`y>@nJWCm&|ix95II;omis{%~axAvq-qO z$3`9Ds7`kfn>%|7b09p2mUEa-WZv7f`lach6VVd$v9QpJwdJLF{nc0F;REius;TEC zA{f^*slLZik#nL$Ru`M@bIgGVxn6tyjd=C7*JJ(u1I@upvAVhz4<0^>^?Ua{PjF}c zzh~{)Qw6HPe zI?gmCxd&@&|4?=9#h&OHaQa0NaM3T=G{f=39gf&6M>alwx)DEr?@4TIZL6Q33OA2O zeMWPI#uZw!X!otHwDWGXu^WwzMfWST_NT{hERa8oH7;^rJq5fDX8DtR-$6n>(?&y=`IGh;S>k zC*zm?%{V|n%Y!yEo3C)AuW`TWp=hG5j^^qk^_|PnxbWNn4hA2ksoozqxPH3NZ^l&V ze^t*{Z9Xp_dO;fZf!|nps`Lo?`Y*`N$2g5j|S-zo99j}Tj;K-Wr7`iJB{g95+Ds4hI-dL(|Lp%QIf}`CG zBfry*e}<`kv&7i3rTg7D_~0s|j3HP-QCA9TKAaX@W19TY_!71?5$b%I*@RRfo{vQo zd3UCqAgmxLAn+iJSZqP45{Gi2Z3B^l8%Hm&%y91byW+A6U?6yiPZqT7v>K`$D;$Cc zF3*MF$%Qe+QFDcxCZd35Fn0m=H}|i(r9> zt`>5Jy(eaR02d~+!{}ULwCEIpHYZ}9FfakCoh}f4)tzk~OG=9uZRC6iqp%1VeS`=h z1piC5FYQV^j=QulOqI!d#qvl=+J^-`1crs7if3U{c})B(?JKPe-8RaYK9LIp<)bi6 z@VNj}jZ`Me=JKiCNt2z%5U1b|c7l-(FhV_>{DBbyEqc83&sCiJ0dq79D+osfhk3bd z5*!R6=gT-CAI7cHqs+vg9v9)OMG}H9U`jjE?|~0b+WFBJ!{`$tV zyh>FFR9qb(Gj@FbieDAqeT;v9-`aU+_3gl~9?~jsD8H5AE2H_x&u#gOpWlSwuLLXZ z6h6QCrCh+3FyzW#iGv${PP=-t9*${yhNIIOAIZ*0LFh!C98%>XP2%BZchYda#3K}m z$S;%dw_D4J6P5>Cjzb9e3{%3Aj>?Hcy5q*Lor;UzxVe2W4qVDZ3H@2Vv6nb<8K!Ly z%8fk>>oggkCB8j*$(ywJ#y>k#dOJNE`C-LPf0<4BbHFSYhT&J4Do#eA?&bTAao#cx zt8l)1LLUysyV&t}7>qxN>k{BFY;U{RqIaQf>{{H?{k9Kgaf^RC=ePd+QNAlTJE@#i zy6Il5{MaeWb6Yz*eeB_fcLmF;kCLuY2G7tWe6u&D$+v#_SDcTYKK(}Ub;tY-X8n!% z62|lNZ^-2MVLY)y$@!4vZ-l7L7@OmmBhh%GH8>Kk)vCq)^`&^IhkG_=rpKeEr`@Q< zVw3wgxVs1~B(!IyeHr}h_=p*f^P*c|(1F`whH(VYa(h13ms)13L9@doXO}O`3+{D* z`3b`V`UUN#=KO3lR3>&1Clei3TFxVs9qsl$%n)m39hq@M8tnK+o68JzeZ%zX>~lH% z{!rkB;DMvB7M2#G(W;xqIz2(diX-d>N^hX_xyws+n&r+iw1`Gbe{-B7v=%}Jn8&75 zVbM3lKBWg)dj{8b@oO6H9E|Uujj5sQ=UY`pDkkF>= znzt4o_OTFcITBN9H;%kBPMl+S!L+buJ6VWRtZ`nj4l&0zH3T#L>Y&5Txocb21J zqQTH|-=2&5tk!W#kMY61VKC!J+nRrJ<48B!xY?NZk(7&qJKBbuFP_KX;2_rTt*d>S z!4X_&v+VVH9)GD-Gh;ZzpgTpXgby^jyEtn-jZ^if-0a4>0RP0)Ftv01$_}7pl6GNS z^CFjA8(CXYF!CBn6#;H+c*CE~pa@+kBgfPs1m%7ln4*rWz7GSQu`=i%q$ZZyi7^5L zmSYqV5~d&pX62=Y5eT_B@)HIl?z97Ix_-aswHAGz`T}!cNqMNuD5$^Df;FSL5HrLqAH(CG)XxS*Kw8;}(B3M=Uu=;~y zPFMnOeFOK>F1hiv9JNaAOy96clH`-=&NHL+Dfh^5v>F>{Ir@?^!(>h&1cF+Pd&Ofd z2BW>vZ22Cd83eWy97U*cEf_Oi>TV=_W>KUV4L+uEG)KTb#*D$)>cvwC%iF( z<}OFjsVohR8-xT1g(h3cC4*~;0Daj#s>VC z78ZO|9|C#iAp|6?c2h7?KNU`3EFi=|xUit{%n^h)SHf9iH!;PDKl(dU9q2@81dqm5 zboaIe?`zFZqj7n96h|CI*x!%S!){z24`OQcDwZ`5u-Sq>hA@Pq>^^+&z4+*Z_qF~W zQQ5c~ZB}J#TS&suhRZ7JzxYr7Mf}kp{!x7A+ux0s9z8H#UR_#^S6+T4PBmt@50AT| zjt0G$MF4km851K{g3W^J&@`U_+~%WkH6PNR2n|~*4^Pc=ECQri^H;WZ_WVWw!BL8g zZ-m@OC&y}IPB4<&rN*4bEGUyrAmC@(nRF4pb6+GvNCc3pON+7CLfFrJQDcgC?4#z+ zG){a(U>RE+57BvQ3I+%?H>c_#Xgb#Xo10mt1WV05N{2oVKTQ8|cHEEs zt>-a2IU29L^dL8M2kpU{|8-xds)mIX(>TkQqeS7PPfJ>TUVTM2#t=^*C#YC zfDQNT?H?RPPjmts6QGlrYiEU@YZ{A-n)BQ0D`?GMU#q=$w|x}ky|u+yUv8_coPdP} z>ZBgg0%{|0W!?vtn%dA^2*2o)=FQ39I9#|8Lw=VUtMJXhv15W8cnX}u1HHi*M@Z)* zVpaZ*`s+5DVcWtf`x*<%@9g3xo{Q#tvC|PvAQ+FSZB-xWFy!LvwWufOpl_Xh^7 zI|qfA13kDZzrI~D99%h2BaNuf(PW-w#c^OR<{Jn3@STo!%P@+|w-X><<);UXNP6^H z{P@G&f0U7ek+;bj2TDRfPnAY_NQ!z5{q*N3PP=^FeXCv&Y5K^p`lqJ(k3Yfk+iBY^ zA1BJUUS`l2cj}IPST>M+74MU8J+eAZ{`u2wVFn)Felo0ctm@))U0Of(lV{qi6y-+! z9Ja*6=Ko@MSkl2UT`-DbH~y%LBMn`uKgFe7_!|%z%K6EX?kWIfDB(!gLDa6;ujJ1X z;93iWF-?TyT67}-8)24JY7m|5B!IYM!eI9q6RjMK_}D=OA?>@9$Pc7T93e>-0M4_- z#hWxK4oI8{oe7%r`3-Zqdts}(FiEqxI}%bx00fcC`R68v*)gLuogaoOI$sg~Lil;k zx`=!hE&Qph>~w@Uwb0`$FqEW}CXGI(MZ~SY`f}74+A*%Ov&dwD@5QLfM;%3P#;D+h z<`idmADZbf@S>KTQ|#vCXc!jr?AoDU&WjM>TxZ}sE@GUC4q^_tA{+$Jz#oB`g-fb3 zy~XDUD}T3-%HUN~SpZyWvI91TDea9v5oNcEv*3?li*cC3GA3gPWaX*xZUzSU%5%k3Ul+h%y||ZX;bUVoQ9=Oj;~d*r7*Omx3qd zp$=ZeXi?{*augptv4Bs%~;GnODJHKHr#To@|AJ1lrQ_IcZSXR;Eo#wD&cR#*wb!) z^KG1#Zg;~CpW^T2cf#o*LyTs$Kyep(Mj9>h)uVd|`ctHQS78*%F7$^IhQKO_LlRCuPG5iIUzM@) zcbV)@87q6nA;9e){`PdPm@2H@%a`K};l?{>LpD}q=+bun#~&A^cn8+92p;)u2j0b` zwS+BpKOPfUtM7cAezDWfOlvs=;qq-8{@6=c|6#4ll^=dr?d?Xa>cyx2%HYAV0O~e= zwsG1C<3Go9B6<^{{6crhGhK?QELB__6wWph;#;QDe$1~D$*;ZVIJ?~bBwGT#tmgIgLn32$D)j(JVPUE*rJb%tBi&8SBt&2!Nnbd9$W~ zPW1*i=zY;tFnkd@t*xy^vw>E?g_)zAR^U@6M6W^D!9105+d(72vw0I2eU zF@(m}gGcv#OxE>H9=~|1@IJYFhAVaTFQMH{f$i_L`l>PI{K9dFo! zvA58yt6tFQ>^SE>8Z?fQDNWo%^^t>q-?Ti8Ycxt=NY-ZA^*$Ou{_%hCczEr#*8


    {=7xPW@q0 zvqnhzKi3M3dl-iZtJqXY8?YX>W}-EOrUWD9p)g*bC;)4_3zhj??Q*4Z!7OC_u+Cw9 z;(h?*QfadeM)1fw8qKY$KOo43$%%$co=S14^#~_$Oxg|%8Ef)Oa&qi3K>et{g{2A$ zj^OCH{HE_yC)I~M6(7MI40`SoL@Ng-IBh^*TWq(ZP5!`M;Z57>vEWX50ux}sc*LD} zv=M0_uyttqmukj1=LkWxR4&w)_B$Qn{jGSmv1JVonClkExqURBD7I2}e>*urFM!k3Ab{jnuePCDEB&YU*eg^6nKe#$vnq#p3FfZ{CItF8l&nzY{CHNFxEz{ zFSPzuJx-6E&h=&DuwMU2W#Z1GIrZm>xH!|?Fc9t)ot0)N1By!widRYee_zBDh~g{Drc)l#3C^igw%hnhEqv)Gt`<|Q~7 z?L-7%Xvs1cd#-?opngxE0eQz8==!Hfs3Pv1{$he);xK?+GzUB$Ehwf>PLjZ?H zAlhWeq&Yser!)@w2gV}^#t`zMF@!)B;V|I*JINv=UAL*isa6>lMCTsC3k+Uc_zj!;2N8pRoI$n zrJ1;ynDw#F2(xBtb5F*($woXCt+OMyjqQ$)?K?b5 ztv>Gl<5*h8#g@W9(YScNz3+LxCU|g+^Vs!yoE`RJPID5QhUkaTOC8})H1h{ai+j2d zSoQ>WHWe@ja=++amm>kyZ-wJqtwyY%nXfq+Sb^K&Ez$mKOD(nOw0WE-8Z!t^**t>= zV@t4KY|LrAU3)VUf<|!Glp1mbJfQi0(MOD`9W`FinncKas__fGq@u*p>ACOnLg0;N zGHplw@>tag3jk}zox;KLgU1KTLQ`zcnqmzf^LhXN{dn-;eypqtPYQqK9FIUcHycn- z1Z>PxXphw-CO;Cp%0ns10dYao!h(Tb3xUGdWJ?HQ&idiHdD{OafFAlWu zy->aoHV8N%NU6DLFij2+#-jIJ4-*lp2!tL)J_O8_%E96YfyjXS0W^`g4}L`kFjlFL zDF3CG?#Ej{{C+f-7DO;{EP@u?0vr=2#1zCVy5^%IV9!NRaQG}2e9)c}lfzOT7MySJi(i}NCrHPGW0oVzOP?C!; zS(I341tUjx@;o~`5nNe3BLsr5)?!Z+F2^)l;7Ezoe^_ur2-6@ep4pMfI_b`-ys}f{tS%wm;^yjzcOGUo{_Q2)X!^@?`W+z8%mpi#?+&LA!iPSbbMvWUBTuJRP6!^sC@x zPz)0(?haG(#iT9PD~KCe=}&8L|1!K>;6x9?j+F^7G| z{=EG;G?g3XuKn(ZV>+?oYV;In}AWv zj$4FSFtX7+7kzMcZe|yoom!%~mPNO5Tpc^Ek3?^9uM?Yk7Td8X4TJ%TZ&KW`t07XhqyOCJZJ$5A-#3AB;}lQ9)hhMty-f z$B)AxXT8ClvDpvz+{ApjP}%&8OSgjVU_}r{oUQz+1eCM)-&Cwgv{VU5VNqj zY{ouE(2+Ov8}VR3PiYN;(4;L`FD|u|_M{n>Fvg%~VX`aJWF$h*UR@~eR4laWF{`+H z+b`mspZ`40MAzQG|1eq$D}n*X&~b7?wgEyR81^uT(1s&@uqaGzwCxZy0mq%~UBiW= zE)nq1MwgdonzF8Aaj_ZA#+>1YCLO!{^XR$@*I{j`9dEw877LB(*zFv~v#q|5BSM_H z)M{A!1DYC5ypNu5Sn$L!nVOz4(~2^p?XcKxnr7v=yS=@A3nwqs)-ZEf7r~^Xhgkrr zHXj|EFw>8=0mdBn#=6T#D5<}qN#=Wg)W_7--9OYdqN{bL4uKC0zuMGDoE>#zes&_>dFQ9`vv+yzcou>h4k=J!Oe1upzo2~u7Oa?`V8aw5@=n28wf^RK%e1ozlCh>R^kBgQf#JmT zY|PB2MiyFIl!=ukC>uO$cnZb{R=|I9^0-3~1xU-n-+3T(Yqnak;QNNgi$)ynd*sar zb+j~ugSp3vWA<1V5*eZY{$9rdT%YoxbXd7DCa6Dx(;4AC1W5=mEJ#v)r_~=2&eImt z)8O0GY^}}AdP6Gx4_I*2Do5CHXA*b{xFk;mCNkqLPb49InC7aAmJ`Ay!ck~_ppA;Q zF7V4Sdun{c7|o+-=PjJ`27n9hdP<6v^{3mPZmqs)jSrQt-JBI(Kp?6*A+S>ag|wwl zfHyhvmT|+$Iq)Vf&(E}`y^0AfY~dfEvB(`q2!Lm2#(gZ^B)FV*RYHfFYq(PgEkibR zAmpM!pKol&`yW1WfBxb3-;P&bedIBqgsip6oJL=p7`rm_A1y=Lgd;mI)bD4e&^nq^ z@M(>&3*o(l+1WF^5LVn@Tk>6L z%mD~x;d?L_&Z-^N-Ms07&DWPo>ricoHWha{QC{Y5@B~7qMh$_R#-VUJRP*NMo^Vp% z_e4=9-~XpK$6nG8(X!)?uxBr}W8=l1+Vs-6bY@QVRvFmv41Ql+T#SeJ)--?21$U}3 zH{56r+1=botvAgBXa&Fe+AG$`-9I>q-QKbK-Dz|V@|fRdy=Fn@>>MZZAOJOP0D6n<5YN0{oz1q!lOc9bfj=X>7EzqkH8DwAHq}c zGjM?hK%fYmELc=uL6CiUnHs1!vNNV=k28${j$}n^3V2fv`V;NQ*jj40vK|_bqrxf2 zgPz9QbhH|EwUJ;3u27$cj+ocHg|H9Jq>GayjfpGYU57R~+IZY;cC7TRMW*&V7S4ua zgeK^M=4v!28NW|AMTc~bV$5TDJg(G-MsI{8M=q82Xli0EE_i$~HugH**wmavKLNf| zlOyrQ%MUbX&ui?9{$YFy2JlfA(2UkRy7BC}@V@Z3P!ht-b>Vx2o@jHv5RJCeJM}Sw zFSfb6?^11-G#^^2v=jIjz8E7P9;}8%3IqiYVG@r8XgBB+<~nc>IEsGAQO}Hb;ACN& z@PVRhyp8*)VrZtWXeZ{hdG&Gn!a{vEmPD7R=yA~Ny3ak`MqrqH!NfqK1C@@E3r4gk z{o}72TtD6C%Nz12`TR8lp8qP%=jHvIFrN;eTN%w)ZPeSCkbh0{qyOf=92xoJfAKGq zk04`~nL7uQo8Ell;d+%oGOlRx_xG(;hL4=cZ;ca3tL(R5bja+Uj_-8!ln#m;KK^om z%495lZ6`_zV4q>w3{|B@vUyw=;mS|-F^rU{M#6J3?8=( zXkxmow&7gG&vM#76Vrc{u)@e6@B9VMw`pWu^^Jo~@o^d%1EyZWpoDY8J1G#{@ns=T zn<`yA`3EZ|I;lbsmUvbDtJ)C?WXPhEhxBnHFvPJ5JK51nH7P2$Q5HTz`csghB#&?8$>Yu739k<7YJ|EcPa0z2wE;d23fM0hfuTTk|vGwGff)8 z@En&xI0y_AiYhmR`I!h5i0dQSj}Nt=Rz4ib;R#ek5|f4(5{dy*J`th@nR~&lIY9kAY!Dk8><=^YJzz1<{ROpn^{<-e&V*)B+3Nr-9To@UU}@jQ55B3;BEUmOo(_bJ@;#r=2>`pCHoFP(vWgu1gpq z^l=tgu8RnGFUVC6a^cqt0+oe$X1a_{80M6t+BwUe6D(#C-?F$u0LCu8aS;I{db1$* zF`N(^B1{l`iEN10{6aM5nijCBDmfsXGj-FW0Y}+wFFwWzC5&BF?rQX=@W-J_S|vVj zzw}e(RSb5M8pFIXyzho8rgEx+If{PB)Bn{QC;iGR?JC_}d`g+|wz~uHpJDZ2K88>I zoA_&3SBFX$8{*rVAuzdd0Q1Svchg9dF*0^#J{bm+X=?#5kE(1RE03K%8OuKM%HO-+ z)wr;c7b&^wcam_Dwq#CKeih6zv2;to@-B%wp)7Thm$X9$yK5XOT7R`qC0KyKmJhINoxVFFt zZ3Mk3Cp*{=RX;YfK{HY~3k_5b8_FS?j${2`(!&H#9Fl(=PXs*$BMR-YrKKgU7fxe; zcQ5(}2ZBT2!YAlZ)+*4xFtnCdRxKnWPt%=B6J`}V&^bB`L0SKx7Z2{O$Nh)v6vI2Y zVa&}=Pa2j81%M6Zf~h<`Jr);dC-K3%Ka0m7z9044e0=*mZ^!Drm%L6vn*=(R&3>$F zNK;@C%sATdFgS{e%~xPeAF1UwK8fwE9mN}o`n=jv@nOy(1Y{@ulG=bHwT?yqqYa@X zR2I?TGPK`uzZ1I~AH?}lHx?FGW45srS0j^AZ?t_k4LiwU2C@@-XTPg8R-TAKe>am= zG;O0XA1lj?)nJ!U(~b9pA&_xzy)q&%FC((i`f~4S;Fe zoSlqG&7WvR_*gjg{j>8Fj67OjjMwfj#LPHCLWIN-JDo${tu~G}l9|#Y@l1X5@zdv` zw=d(hM{DuY`a&!;r{nSC_v8Qm|M>5HG}gcTSN|rKR_|#&acKs*1*}@zO(}Dja2)Bi zvDJ-d8|vqSBejnjM&-0NmC84%bqb7Mv_62%#`BGMvAyH=M@tET3xX)x7J-Bu?Z&ZH ztgG1djzG=p48ey!&KQAsKnQ^lnROa{mo+hWxt*RIdo5?FTeD_ZHr(FVI@M9)sDe;0^&diu6D}t65(JdVVNUVp0KF!2$5!5C+~DX_cDtV0c3J*3MR zMKDPK1iZdGkd2lqhmuk|bBE9g!1jDV7&ac$zo;t$+1&WarqIL%hnlC3Ef5|v-e}h~ zR_8goPxx0&$khd`W%m&zsf|WO_VP>jExhP-Ix3g&dX4+fa}sAt0Lo^Rr8Y;dqAkNl-qRQyoyqS;Y37}o;1TMBR?yyl zKb}3`7S7q#I7=JyY7!G`bX9Q0#CFj!t(^4JGoo~Ulz(X`(`jm@0{3&6PF z3t=mQC5{Q^9=2Aqrn*j8z=UuUO<#@;W)lH;_)7VKmk=%^@MNHz-iXa>SZa_$; zKCW`BaT z+(N5iAur|k{f5Vf7Q!vcolPmsS!_JwzOI4t1vN3|nD2lSg7U;}Dv$az#|(4KADVgl znm^Cf?rUm~wdJPfEADxlvM`uU)BC$SO8+{hX6wR}+)sEOY-U18&(XoxYX5EF^`{?w z6w8YHgYUj!x?pQ-PdHBS7)?3}9E1MmOsy6D)9d(XV?Um69%v2)pCWY46POSrnkOoI zZd@5tzlAP@2IYuaja&6Q!&ZHpdshejW8;&$=Eb`3KJ&Txk{X)`?h($8b6SDMBKQX$ zqE9`cBgqIoh@KUWQXJ;EUG;?*JJ1y=M5p{<%chs_459*Ml+TA+OKO;@b#bmD`4Oh=~F+;5D7 z+jg5onkwX7bNiL$$#2(BiR35lc2@Sc^+J*k$(Qk{ca{q~uD0@13gdWAGs{}FQ`~3Qm7mtB{+5-1)@A0b?6-knwTa;5Ke1i6&8dV(jrR}uO`I{E!570 zm=VUH9mGzzGZEJas1QI*X%cS>p|=)Mw-%ADG^aUd{w8;L(w;2*i37pOVvETWwQQ;~ zqlFMhW?1l`ML!ECt%|&xlZlea5zQQgAuKxB!Jr>k0JyWb=4eB9F(Sa=taD6i2Hm&} zdBHD>JucE#nqQM?h*)_2x4s|iuRM$y5zzDkCSwQ>ngJo=;ou;SIM-PdG%z~X?sEVi$}Y>5D$fLHU^o$4%kri{9a; zZ;lc`i;J{L4RH)L12A)?e?#3MfEMROkl<;qc-@MBSjNuR9i?N_mtan9IHoREHeRDulxI=tMf zbQt)hLYX`H+c<$c4vt)`c%}8$ zV*kFinQ*e;dqWO$Nbl)zGNXPKMwEse9F(^)7|MgB57BF<$}FL zzAcZwadtey+iL&(P0tLEC?w-y8#W21%I9NlvZxHipmeT-{GF=Z`5>@DP}Yp3f0zZl zhb{_%A-&?DpY)X>UAt##@yYNXH_pn;$zrO?%D|+llFn4B6spwH?bcOaiUUq|QL|zt zT82-js;;uD0K+jWlW>tCTos=*i%<2=AepnjandI!CgJO7Hkkxez@7A~JWG3EDqJxX zDBpU?B0t+JhuacizD~i{fA!yfIl6c32D=+}b7^ET_H>?IU;78^%XM9hyL{MTa2t;=To#`5ftUE&po7krFg3!Wwqc!*m_= zMRSVwf#EfSuwY_Bv=Pi&HrGswew&M#xoK}Of=SFSdo;%8=j&#CasL+cU*1Q>-K=BE zA1xK7DVoi~3DNJ|sR|vI8W~A@!65csCEPJI=(~2@skFGb5G%_|7MgW?-8kqClm^V3 zh}jy)=ggXZMyTV>Zn8s{fy1o%AzBIg{8Y3bv?=94s|a`z4?2!In@P+gy5CGy=w3(& zmCZZD>+?P?5dj|?sJ36c@Fo2)k7)zyD#Fdo95m%tS65T zkF|UEVsg5sykWeCg(}`b4Fgm4gVvQ$C6cMiemab`Rn&|HGfhrC>WVq4bUqMC+z7Wo7L_y!D+Q2xe<$y!%)s zJ-sekD|^viY{lBzx;MRXBoci9Z6}y{zSrdB-1XSrg(17Gw$~a%?Zi~VID*MYU*_&2 zgkZB%+@Hd+d+c5p%tZfkJRMB+g~nVgw(4F}b+vv$_`15hY-U+Hcdm8`!|MP!{KmUs#$8Y`i zKaBtQpZ}+-+cIoHGZ$gLclLLqySJsbo{m;~F(#&JajCJ$yxI(mN3+?Cb+viD-V|)PFNyp2<}8#v);L~Wzvs0Gf+e@9 z#sX!5nMi!v*1|7@7h2a{To8`+7Q&z$2Ul7gFb;sT1r&lAb1Q2n`YI1&^3|6g#&2ug z$kC?HEU4R+-;D2wq7QSd+ML$wZ2UyQiXAz*wgo+$Dxq8^&5iYFBVkjzfklbbcOZfdepTZJ;6Jb(W0j zhD^ZphS%|`JHpi&m5t*9!EFMA*P5*Le9xHrAZs!1M+2v#dBwx}AFajC{=Uk1Xneyu zFYiP``$p}iK8QvWV-2la@FE&`2xiunIg)I~%yu-fI2H~@H84Q<#yZg>R=5XYC)6%l zP~^?pm4X5@AAP7gu^E&p2)+mcFOD}wqmVquH11d{a$*QLoCiS)c*`fU@MorY9>dSL zVxvHJe=l~oU&#H+T4fyn_u&3L;~Mw}lxak`>yTskG&b23z=jA5Sb4xP6B@TFPrnGh zm}@xpj`sZC_rLEk*cbfht8;U8uX$NxgP#!sa$GM0QXU_3t9%d$Oq)+|qc+yOAQ*CY z6xyaX`{;%87QB_l^~I6a#g`Vq&&|$jp3!<;dGGG-#^&aW*xue&8=l9@ zFFlMmUVlZnye=G=ZOgbrAp7bouc)7m$H76*LW`!xJ9kID^NaW6#j_3fMes>`amjcQ z0XB76S-l^l6EkjOG_;wk5U3!Kc=2L8wl=pdoVmBA`EaQjb_1Rjg9!=@v}I+9*uhsUl#72x3=T@+KT$2>Zh>@Pr2P{t8a=vP>#?U9QVhO zb=;BFRe3o=nfZY^2BFBxQakRiEc)2s)N0e5roOY^>kGGQJoZy-41pxPJld4ndgHL# zTZ1@mG}qQoRIHyBB5069Ds?K8#^#^a_DEVNaBFkftx4fzx5Uz{!lzDjzFIi0ZJ*Ex7bDm6Sg z;K-eCttMLIGoI(TYZ68RT5#YI=#DYQ8T80$@;R^0Phv`V^yG3hj!rKR_8#ywlxdxrOzXotZ;KmPR3{xp92lb>kLUymRD&hN$C z{9OvAV*Bo7Bn$uXKAo(`;z%anvNIN_jJr@DKBZAEjwr z${%yUH|7&2A!LBteDeFV4D-|11wT6E-4t0y5-LlC|9?gV|EKv53qZ zc+%C?CZ6Gmm;5qw{THA(e6hLUO4Atwh-3=+rs(bqd=tRw6u%M%{Dtt#X_%v(%)|_%Nr%^N2){T+h2!B| zFHLk1T3!SQIWo~9=z$>QjBXzpp@|-~Yn8&pGQu>}<$W)c5VKX)mCiMjn9@vwlSLdF zL?Xyl9fUzNEy6K~ZeeS~-bA|W5Kt^iAWU;N+m{r4Q3t^Fs~W|>CqnK!|L})V7tw%l z5dxmwZz`C|hd@sYCrz>koo*aMJP96`BEs2u%l%$gsuO}JHG$%*(KIl*sCh1_@X10TQOjIq@nF_q8o`T;xkXJ!WUH%FIqs%H}pweSsxB7z>D%20~kJNDxIfIXV%onur2+_^5BXZFztY z1)_#&arumY{m+;#Zl%7qS8jR|O_gw!hs?*q_!r!gxWeD*A%mqv8rtuKkrglxaUN#q zB{xqVeB*CR+WbR6!eC46R9tCpzg?$c+F4`DX+P|K-~ML8_z)<=XIceXbS5=MnI7!w zIQqA({G=-jZGzv1!J`C89EDM0B}D!LkP?`DDgLk?1{N><@P8Xr>G?+=7{+(TwYd{6 zBc;7GZ+^<+`9a^6Rvjhv@b2a#g`e!LKpbyh{cN zKmFVa9A#t~hW7{QsDG(|CL!!Q8vog0D|26p`;X(bsMO{GA#=|K2r2 z!Q(gPGmYthyFmPeN&hczs?gaIw{i0u`a~~{BjY^2g?BIICJHDT^8YjST2eG{4rK?1Z1j7c*VClGpZuSeb=Q*9ng^n+_5Umm{7v5Wk{(Lg_rZB>Zix!@+rD;cw9PDnthG^Z3U^{HEpQAXo5L<*dvhm#{Fi@e?UXlPeH8UM^^-~1{a0p&j!(|S_2{$+ z>M7Ch5qBBHN57qu0F9@R|V6)$!UqIZ=2nZ5_Dzq!2^&sApx9p8EVe!RTaGQ;?T#~;Q2_NRXqfBBQ2 z#hc%HJO1FG{$aFKKl&g795$(KZ*HjleiEJiJqy2@3rnKS8%k?BdcAIJYr_qFa`sA5~A*?Mi-+%k+WHg9^Z>G3YVT1{clj^K_sgg@hk5$oGlE05z87>q~A?O1R|1B$W6y4Hdx zl?|-|w3GV1zCx)lDm>$rK7}?ec#=9GeD?ZHYc%i)S_@+uV=p~ii`QOx==?3%7cK#B z0|x}sXi_3Ti<>d8k0~Q`E1IF!s#Tl8RHod0!H}a)(fnl7==|)w+k^gqR<5q2zA>x>E)8S!1-ucN-#J+(TXUWxj@?&<$5n4M-w?ixj_2toV>g%4?`ph0`Oxcp1ab%o8uN4U=-~t5yIO3k z?|rn<5qw5cGj)2@TAbWh$Q|&EAq28$W+CuKpx;&<5$dvugMP(W91MEaYWmB+{0sMw z-~C6wYoR{#0(ceN48tEbS8h}hepDYsGiPsaFE*Y(i%$PgxN<61R@NMM6x?@)aOXns z(ilGIyZmu;9{1Om;j;j(>A5jNf994+vt9<^M#u=7T4jaePMGCjMhXGGpiPsIR%{CR*ylP0b}&7lU}HxqNzNUg0i< z6Es#ewwm)ZhBHTMGX4<6!MmYs@ch8b2!=SGmSS@U>O!mL2Tj3ag{9nslS{WBI2}GE zf*Lm1R9A3tha>_V@F#udpxf0PFFdJ!$2<=25&Gps@PQ8Ecui=v92?x7%BE@I0pThH z;-i8KT589~qQ%rs2-qn9c9-Lc_klHv$0?OLUYMLbp<|b#)1a~ z&x~VB(YoU}Luf&8gzu))7z3|^^O&2c3;2D&W`Z7C*~h}MC&t|fXO|a*A6DA2w%Aa9 z;I%`;h4~r|8uem>*EMOWU&G^LcFVPR8t}RKC*PP)7$AkIVDriE&oZL;zczRZOB8zL z*D)4+{hNRFuRoSl3PcLS0xA6Q=q6g4#V7j$tHj~3w;8+ zsvssA@K9MaCgq;7E1}Pjo#G$9?8$GMbjUD-cH;ieVB|Xtk*3O@Ft*?|jN@PZIW_%3 z+T+GknG&J+Idmy+l^+H6r~UoOZ~nVr@^gR;RRX6e5zHVeg#}3@%y2JZ^kbf+h`jXE zPZh?nr1S7?7yXnE3|6O6%EzzW>?kt~AcI|xD^ca2@F4@k$loxmgm@^s$^>*OCJX2Y z!HDQOBW;d19Myz2E<`yYg7ij>e<7rGrU|wZ9C$aA5T$p&v6$4v0&|~5r+4qMD_~_g z7PK(&y;E9fAsFMxl1(j&IJU6b1u`iDmECpqTHQn~eIM8%xL|=|q7dY%@-l&1t4u_@ z2cQ0dKLj3HKfnMY0xu>}&bS7?lno*QW&%Q%>PQlHse;hI$gooc;Ie=v&o5_aj1pLJ zr|NU@+IPPbZ)gF7P?7VXy%18l*cIv>!6N!N&heBu13X(f$Xdhq%182lSP1=z#`qbp8(&~Z0)u&QdU!-kCC{JiYr|aU6 z8_=R}Qby9ift|AOU0A3J!1_{SR$`gWy z^U|pcWdfhFQ`-?;K9~_OhEhY0Fc2n;88jE&9~7LOG?OB@V8}oyji`O5MyEy4HDi9J zCSoXeJu$zwPogK1u&7 zj5AUwhb3>PkwGiwe$F{El*cLZr847>iwLV>8urUX$O4?0X%M3LV3D!i+;YlPIg~fw zc=4le=k&2aCBX2vnBj+FIvxE~b;V7;nF6IvQ>BQpzvGpVM5q1rP2JosY0JQsQ6+(& zqxu^s+3dhiy5CKkbndo8#syxtki=v?GF-M%=0A*zyKTh*KmV$YWVub5{O~X3r(x9Z za!it5hO2(F6fz|!_F;L`M=w0}@A}&+qnQ4NxGibuH|uVje$qYr2jLyaX*dtktm>M< z#!j2^%bWJATF? zN$`QotZ$-_O2P*lt|}YlDE`B`D3a6RGktBv#!tct|Bw4QIED|8#nPU#m86{|9~OL- zevt+Xad^qjzn&zR$s^OtJky2$%48`rc`8j^i1Tm15qy1l1HkXppkg3a<{QD+7n^Df zeU`Z$(_hwnTKF;sN>*&9(bVpX*^f`J;($x)&o4zYYc5B4pofmdcwm7K-G<=n{4{qE zvs0K2MF^!}l5!NEcm9hmAuo2E&(5UQ2KWQIm0h`wdM&s}9>xMk()h@_%M^&5oE$|S zi+5-SH1x7H`b~SWF5zC%+{p}W#xYnh#n|n=w2*gWOhEfxor%T{Gc^!eSfFnPFU+1R zA1QaJdZ2v)uJDo16UpfHolv6VE9N)M?j{V`xjB~uh7oa~#V$qD`FQdEQE;>#3}|Te zdZTV;>!j8izzv2iJNu!DIhq?C^3@H-l1+>e1)0s=rZk$e<6f-m4AOzNWqeIf#z z(9qZ$3GUKhHr?ObjdyV(@adubMKqPO3 z1e6D@fM+m#_jlv_-}{c@*9>!nRxnV{VZt_=u^?C?u0^Z05FFw67k~a|@!q@dC?Adp(vkAER?1FS@I4el} zYcIyD=OaCA8pP!KDmS9C_Td|xW33B?XKhBE!H1NysjCo7eNPc%iep8AF-Nspvqf=e1Mm&PIq2AWecnQFG?=*04M8&Zdg0EIp1_SV zdF?E`39O0F5rYDWwIfEfMn+rZ(fw6x%^_&YV^t4KJKbBq7cal^QV7kc{|T?Ep#cQ~ zGZVZ!;@ zp>War@mD|o^Z4+C_bsIR)|=ms?|%3DIcI1LKDf6QFF$k21@*6E6i;LYE{Gr;IbYg#mYn1^T&G?#BiRCm>nO-&pDIj?aDBcEeW(GIKdH5(LI z$8+=?_-tbIDhAy>GrGBAfqS(P^e?L2*Vot79wYJi>5F*wq8pbZlQE-lxW2X=_tzJE z)bEwsQhiGOk+KaA4^^&d!xVV1N!fQ!f!p`C1s^uohQ{kg{KZdxDtzB}IaV|$eD6E2 z#zW!Bx%rl0eQfPdPO6#K_y8I)@&dcQ$ITwzUZm{9Q%0D z9s+UA7u13K&FXX0vC7=Ex*W5$dC#v0sxtyb{L%PjQ!YYPSPYCc+6f$!f-lYYf)fG; z#%<2|=dueo%kKGE?2G{D|yseB>%x!Vj;%_OjY=-Sw(* z^rK+%?CH~Zrg;D%I{YdG)Jw~1KaDACYpN_UqO#whft4F>;Qv|6S_oiHxE#JGGz5Jb z`Uv`9Ao`=j5t{P9Cmf1kh&Jaa>eF+@6y5+=d(*n$js`y(PIFVEv7j+Mt#ZIKy$LqB z+;~2-@K9ms4{Xvg`%UAH`|#?sdH?;P;00f*p?Pq9sSz(fSd5c?FP=YnY{BRKhmSlr zBe?uu|NXy@&CPAk*|p|ky!yK4)%J?{eBc`ROx$nR5&d$EU{&qJeOzdynXjihfS)%~)!IKx(P~_N3Hm)wHufOqdRqeJQn5)gycMml00iz}1 z`Fg#f{xRzN?6x%j3#`VCo;4Wf#n82L-T96AxT#=N!RC|SpJmi9zczTP_upyDU)7}G z>tFvdskwUoRVN!VgFG>1)vNrlS3f0~Ka;oUkp8zv6~Nz)^r^o?~=~lp#CMSjMLP^7k27qpHfzbmt)o^{nA$a^p!(OuJ)Au8hdfW-*y@0 z=_2ZT2t&O~Q8Gd7#qai`ysL0BF1G$kZPRWye^fvIC2W;nzF3fEUF|+BD-Kwd8Xm55 z`sFcWxj4!M`Op4QG50dFDh7t%@>L3e;LFKsQDb-uE15BdpC(#XzhhdwOloq{?5PF) zm+Jwgxx<7 z(Y?DDI~(le99TdC0n0*@GrfI8h{}a9WOAHE_=L)uPzE7G)aK4s&YER0ap?*5=2DYT z1!To%Vum?@9}5mZ%!CIK#exhX6BT3@%{X9(Jvwxdx*IVhtt=M3F~}!Z{zM2NCaGeR78IvL=-Z zgpd=a3Boyc@8!aBM8qaXmH;z^UoZ{WVWRM=1HHn6GV+jL9-XLetoSfvAWFU96rn=e zoW;%}gE~Oisau&iVw|zipninsXbm2YmqgfQp|KVOEF!#9Tj{b(6JakJIAa=%Q{y5q zYK@qmuKB1#U;_@PAG-f~{87`pU4$>a{YoExi>$~_zzI`*XD|Zj-w`QaIuV!`307%i zGPn}pKLg-83`0qWp&d9gOEql-?Jw9gchEK3n1`v>!%cTD*Pyaf(#M2p=@)8CQ(gU|-S?y#y0Mr|An-aHr zTkvKeJI>I17`~Xw9V0&nS4M6#`{@U3Wv^ZptcQj&^KH+3mo%InE+u&O4jH=>FQL!l zu7;n?os{$@Wd34cJ9+oA0@%mS8QSSo5h=Ls39Ag3X_1@jMG$>rwSQ&D3kzTV_eXx) zHw|f-jw%iQjmFn6VF2)#s=+trvrNu)pAE!ceo^+x@OSz;<4B|LQg0Za+ns|L9E%2# z8=6mNqDNprc}#0iL2E%LKzm(46JH4{87+yX5>bU_4EMjl)P+d_6BHT=GbNg&-QbSf zX*0lJ0Gl~^bmDurI-P!Dm_SZK538ISgqNaQ&=#@~N;DcYBQzFx2O0?`5C$Ad`8dj{ zt^8M)xrDtPT-sinL-3}s@;|HSd!;cmJ0EDX44{EjM>bAD3v;gyWlsiq*|a2o=u&7K z{3t_eG30TGW_%xVJRr1P(s|H;?4V}OhH;!49VzUhUciPHAPwMwuxovNH5$#jkMu(* z1YFSe==FNalcNb6@$mjyEG@On)S`So>QHc>7`uu6osGCSIW*Jw`NoU*=jyvhLHtMm`1eIWH{+f6K8&sH{TLb3S_EOA9<&EwEWwbIM5rZ$DiU7s3>_0@%#o1arZN!Ye9u3S; z{OH5?VsU9P9=-HxbO*=28))Oj3u|$F^wEd0zqb|hwfT7Y)i>fF{DXfO%j(xhhkf-q zw17s{cC+e5F#OOqnzqpC*^?*Md}E_vyS?NxbHv`2X!gTXG+eZPf-$Xi;*Ma2U~5YB z{_;XoZ8R>wEI&t+E-bb*9=Y==@9ATlG9G*fGr|p}#qp0YBk7MEamcy~EhyGjtPvQS zz?1O<{BvU_ciLT96J&X@8Q=T%>psGb!0{89**gv|02j3Q~zfDg}|<>c1D|#H9mcm^}cB@p&D=Y6CR{r zRk#E}o!3=nzAL;cZWP71Rh?iyFD);}%F2q@aWINc&)M+GdTLBKaMJ5DaK%A)FUGD< z+sW~Z$&m&ct=sQ(I6t1R#fSRd0*TkUpCOwR>Ja^^8;Xziil z%01SM;k>g5Z5uQz5Zt4w!8&zyWzl1ZHL=_JLhv!+q;d*>pBx^<#>R7(3jtTn=@Cby-fmH55i`zP^_{-fWIxq97e^LdqfTsZUO2yNR#3yN0P@5iL@ocojV z7-1X@ICAqu?a#4}a~5PVAI;CtTObKeJ4WE4CGY5j+ChB{;b~`gC$=`9$JWk{a7*0+ z9*&`V^kCg{4)+{^o6k=N*0KawJ$&@Cg>Qz5*28EpL6xJ8x4nB1TWX{3A@hiEoNy3Y zVaz@79++pjLyYyhwTRU};U%!a84V-G&T;=BR+rl9A4|qFA3fWQzxvs`7F66@X~)CW zT5Jj*K7R5%KK$@~Yi#}DAN)bA-+SO=YFF0oslMDfb{2a(92sU-Kt)yV`}ty~h`0P<@{9 z&z*Ffl0~1Qzh#^;Ydj+y8rOVMo0+n}385}p)@+Eoyx>UUbGH%w8TgND-WU^n#wMmy z7|J6Ymi&;M>(6E9NW2S`@k(nhjuJ%hfshg{Zv^On{vUoE@4o*eCPh267nXgp4&#OS znaw&U$0~>NMDV=2wh}KrdZfJ7?&miaE}=2W9AGUh;aiSz>8(W_>eoh zI(xhEMDsVAldrz=C|-W~q46zv4cJ;hsPaNvP$P~sJWx5n!!6BU;fmb2LIi za4~onm~kAZj|~;B?;W1T{sDJ3o_P+ORwteo&fwmx8R53M8THq3!B()^(VV-xCmek} z7D5}EOH^N#hmA~>-D`1`jm=KDQNG8IpPC+l&-T{q594>f|9aFk_pu>>jVyyh&9BM} z&DE=mylMoELhhF99UQA{qSFqK6-IqhV~akuv#;^50>E=xR$bWq!cmQE_MpEZ@B^(2 z%<2o8gM}j+q7Tv3LKF1851yC?V)Mv}<`s@LU2D(Al;|k#&(q+IH^22Q&-qin18hQL z{5+mM-?g?KeU^E~Ji|MN-VF@CF`qOHeoO_MPkw)v$@%u{G0gu}xqfwH!PkHB$Ny)i zMRE+hs>1xbI&%9s0|iqtLa?a=3wb$6i9~uC19u$LBaHSr{w+x+I1EMFe z!x!&--G;>-22D0VmKGlui+ELmaKz0o#VE|$92%fo90;G^5ItsI`itQDrTn;;bkeuj z?Uo^jZg*@$=<$+M71uG!hhHU~ghv`z4G#@w%EV_z0e-SO0PYUxclzs>f1(mbc9V$d zSrV?`n{m^#N=J6bqt2xcvcn$DTIO#Czm1nbl)Z|BwRmYhP!e*L!;L1(Q6X^zUub=4 zR?6M1sub*Twuku8N))&-jGC{R@Z*wy`99_~= z_+!lk1rKr_?#jxtiCYK>jux0x91AN%d|V58Gm#)*@kPEuyeychBSbk9xfu+yTlk=Q zFd;x#`%VFsk#e$g55X4g;I8=qe3k=ioiw)=WzV!B+@#e!Q z7u9ceApsv2^aw+#vxRj^lO59tMvp}#nb;AGxQmX(5Oqcw2(|)LUs&KY*EtpAU~voBZN^*De1tDDHRSIdH){9^e@dcR3e} z-ZJ24hqtM4m|Lk}k&+&%8E>RXw<nvZ6#Ma7h7=;_mR3-PZhe3ij8J;${CJJ}Jvp zo_-U=Cf#wd57F#;Tb7}}(s5E%zi@+TF;&V}iZHYfEiNbNv49uubu{`%$y;t!gsiWv za!V`0@g|0|#8hGMbso2$SxCy7fvYk(PZE$fPFin@Mo_8lxP8(%*{pQ+ReojUZZDY% zc3H>_lj-HJYYHwZE_dNHET4Vvyj-r*&m2kd{Vr*gaCS%+rKesjtIOkG+nG>nliU;kew?57%ah$;<8%hYP%V??wpyM;%h zdvxl1E(T`YLHD59kXm5YLRX{a@mfhUK`(IZ5;O@90uLA|Fgeh;g4X4Z3K$U3DU7GN zX_)G@SX*8QE)-|iFvsG&*xHGm?R|xZ#tAcRp`oDHeAJfcWN15RIy2LcL|ckpqg)vB z<_I$2O8KCNVBEu0kHuzyT`f9fjUl!R)pz-K#k+ep|Lqgk<08UKfM`7 zINB^bJ9}pOT9Bu*kuS`0%HiGVR~(@xT1aW28NxUqtT)q%?&aPsHhaP7f%YYB1Wp`> zhOn^RZi?nzumI^`(2s4=y=bT)P@^p1t%hjeM-NtGZKdsvO)zG>DdL)gDX-&1YmwgG zPTX5vj%QCE$G`hu{#U2}tv6qfmtJ`#=39#~S8uue&t7bMw=+VF`P!`S6oYP~U7;6` z4$&TgZWMiZax9t{1|{_B4&#}2tJi9=u-FzjluoxV zxNH4(d12U2tK2hsbIdpM4or3COOB4R@K)vZraqX*b5oi(FJqu|54i_d?aCc9%pVBg z5KJ%+oecKk!M){p?aepL2u0uvBlNJ(9V<@-gRxlG8fRj1#yi<}_6}5s!#F?cScrfy zjfCK2(3A?iMyL%ilQmUMf{^$lN>1R{r&xz(^`N{n6-L6rsq-{ zqjPX*rXqDaIXu$5dL1pn9=h*9_y7hf!Y}&d>>S6=v4+c|8)4kH7h2YEVNJ5v>AKH$ zl_u~`#&xc38EY8q7F25pabL>*?!E;Zz_lj)@yern@#dSaDWq^xuV;YPGm|%pb3a-wwc+TL+WIt}J$vqcI9t=Y2n`{QWS^W>S(GPQ4UBiKm(k*4 z9i?XRcmQ{RXVCmXD+(q*+C-EW<~cYIK`U!4#sbm6kKDDzTJ_$&^=P)V&evKP!+MV~ z>ytDDhwDqlJ?_TQ!Cq`_JoBd7mE~o}MWDktMQdkLWj;Mqc;QSm7SP_i(mHK(XD9Z$ zJwO-SWrJV^d<)~6J9nrbc!Hz;z(*7iK7;YZO&(pyQJ!cofR8yAjpM?g^=4-0l!{%NN%FldRc8l-&t%gSeOKEPt9Dkq9$Tef($$JMc(XFdgo9RN4M1;G~h z=g#k0O2xQqrGOjr1>eqeqa=aOYIaaufBSygw@D5fNoAKt$ ztI?R7h>d5DV^Q-FLWYSEjbqUcXvz8*VZmU(a}Xas zeyXw`xbMIlL%9C-TW`cdv#z=Sgx;@lHEI0P)m%T&Tf@uv87(F@H*gP?1u~jT>069J zU`$`;m_$EHoBj+>0+^$H2M>jLX|er(u=nTRktJDvCw8#|4mcc+eF?;p5gEBvWoFmX zUCo{*C6U9?9Q`74INV1%8vPm4IpX|F91YnV?&4vS&F-r1%BtKWV?|(x18{f1u|wa_ z_rB*qL}pf2R#jGaAC>{npFP``Yi8H(wR??2E)!n=Sf6=NEs9Fr-pkWyY_7!y%vZtt z(CB#7rerpu@ z9j$g=nx7Y3PHM~?Xf5io+EVVaWB+q_auywRG3#h+f6o%$%k$IjTh?D_dI!oIX4dXL zDiKrq5Il{3Bz+iVzyou2gZUn5NsSq#L+hhj`!shzW%Hb&{-<7N+Dz>$&(5j(JO-kn zHhTVi!!#wz_v)QRO9`smj5k3qg|5aOp1|9&+-B5gOLH36Y6Iqo=W1^xsbB{7o*!G) zvFEqi1jHxfV{OgHj5F2{?(hU>+t|v(Er(i5VVcd%sQ#W$huudoE}7Gi!i63Uj!{*6 zqrQ^$8rmduFxE3@z!z$V%7A8Vm6x_XQ>E)#XHi=^rnP2sdpCai$#bnvBel|}$-P&TA*=nF!d)mG7$T&dr%Wz= zVu}r?RrA5r&_u`rWc7QR)M19Ncx)}x~dSo>)MqNQgvsiSUg zc6KJ}n!rK4KrYw}a!LUBWHF`eAow8I)DOR5xq}3NR3SNbs7(UM8;Fh7(g-o&6e1@n zkp5zG%qE!z0AU3|M7Oz5v-}K0)4C~XdkhWuHBFBe(3%i~H@^FBEZ+tJ8!*xX0>J59 zPM36qymeGYPEA?`q!zIY+E;Zu(*}&q1_p+UCuYGtnc3xVZ1j5S7uz1Ckw1#lT#|3tYOZhEP8p4 z;L>(8>(tleN%}d46ILk`Qwimyjgr8hVNg*)8k`DZkw;|*h!kZ5k%U1-}R)pl5A8xewCAA|8FL|K2-K&@=TN6z9!dG$qG zdvv-I{?~W<=h!XWfjc#v!BC$0jfcL8?{^WH7shUSrKjU&@a(V5vk25R)F;z${xzP6E6l zX27l~KeHT#2d^@d(#_x3#+F{TDG%HV*CKR=E&aMq^31Qy4TpdE@BVEW^&2<8VSN49 zU|xdzuP|RH?8^q&c62&L7LR7(2z;{H7jkTsJv%MoKxe4hMhy|njJ$(|6aL@|9P~nx zB=OcH%y4Si8U>VCscwpcHsBwvc1zEJasjDPe+#!78n_f5JR0@!n&O>BW54C+@DQy8 zFinKJLO29B1a}t>2L1~E25txboRaZBH@yW*@1**tixqCOptaeKM z!XY}f2!vVgsOnLFzN zpmtINM|({qHAYp$Q}+R|$ev`ZT2l>sVqg6WqXwy8z+(2CK@if+e8Sf7d+iLSv zNjk5+hHaX!T!rQYH!D9AAb-#TkB>Tp^A!e z#`t32!~J!OHYR2~FdaONv8qc0SiuKiJan#&XUkqrBjK|c} zv|xEAUVrU={ML8A7em@t!H{I$@ZErd&mNWWlLrst;gcuAtNScr25kXG=8feW9vcwh znLm*@WuE510F1o@wI5PP;Mwf!ya!eJU4QyX@u(y7DDx(a2AHYr`TY4S(oY>=4WT)_MO{tYx$N5(%fOSqVex|faYE^ z_RzFBl8Kw!4NLgI2%MXpQ5y~lh7Qyh$&h5Pp^4K6Kww-V0m-_UYYXF#dYpL7Xc~;c z-gD0%leOVEL89}~W5eIL*04*ZJ)&`ad8+wuXG3G|Bx+h$V4Tu#J^flYwQoP~(Hy7w z0C>7M)w-s&gFB=)Ha5)gTfQ;x^&08O@%l{kv3{z+v=xk6=vt);TGl-7mSRkx_U+Gp z{9`jEzxC$p@y^@d_WTROocb`no^Nc&lht*ttH%s|)k*L#d|*;A#Ck?qnOgyr5*IMd zLTwMtqomg{XE3+Wm(Z8M2F6DRykH&u)2 z`k2Ib_3{$bFsk3pnV4(i;`L z$HhsYPJ4S}Gd9-NjcYB5Ub`Nx!5Cm)Vnrb%Kr=PzEk%U7Rv zfnlSUCEDbUJ%6!eI(F+82>&94eoCT}W65sD+%=Qs!$MiJROIMzP9y`ARmcz|oN+-^ z>`MOWETcRLMtTYaH=V#ta7+jU0@-jJ!WI6Re>V{sJhNpe5BYUniZFI7>@bGPauCvK zxgg3x?btQSn+foe(-B%=dNjfIXtSmjP}>t2T?(6kn9Kkr!$ix59hDxOEM=pBL<@|9 zGZtGRAzbE6z96J5WJd>_T3e5U-Tmm%;>PBQeq^%_0tdp!DXA$TA>-9?BLQsUVJLt& zATn>pjLLyD5_Mw(jbsj+d|x~%1dbDEs88XZ02L?BR2EJ=P)3NNobY0?MA~OhNOfap z*WcaKyCrR1F8Ge)|utU*}9I74r)Lz5dkWJ2O^M_gqAuCAk!Fb9yl5zoO)(+MeV7d)pZC_rd=6pqziEd{nhjn8wZebior$*q=XZ_eQXW}VSK6V zD#nPA=!x+OAr4ii)2EFGr-Ue1&IKx|(qPQGrBtAD-l2ZkF~z&EUb$eiCB5-eeEhEB zW~eenf9YRY=#_3=L*9CoAqhks%JwIHjOTB{l9XYv>tQ?Yj_+Tf^2%;cy&TT2*o&Gd z-7J^Bt~_mb-ldx@MOo#6pS`oN8JIYZr(E?WT};L#7@lknio6R$Sf`;M!a&?}l6sii zi(K`KKfPBZTp0Y*g>sQc8G`Vh+41q8U0wbxqsOoUW!mLOj%`QAM|LxI?3H0M8v+qb zr7Fv85B%lp_;$sTaSH#^!A!F5r~I-oPTS>72-Tl#3Qy0HghNmc-bH$(O%hk>r5pKm z-RUo0rAcadZnR_^|jBTi|^FH^?NY3q;g?1%K= zeN~qtHtu@tLcVq)ZGaSsT_C$xoIz$hvS5DZFA75n7#_KqdNre|m4 z@BjwEc5LnJ__R0@Mu|IU{!kq75b!6MKrp``Ffkumb(nAx-5FN#M)p z=O@9PQ!s-d5Sth&oURE@tTND)5Us$?Mn{KZmb<_vs;UR-*N)>zcoHY|cXm@$e<<6CO8nM zHilrzo`iHEq=6Sgkb>Y0eFmahWpv1GLfOfWwFbiIvnNmE$3Oa^4`ux~|IP24LHNN( zAF4i`c=eUrQJbhM&yhIffSJnAzJQD5!8u|6p%#o;6IE)B-KOuAf#3wboB495&Or35 z{xB(E7IA7E)k5|9MB>pN^!iahLhOeaJOpD-I5hW*aWB>V*ItkD$!RkYS2uQIuLT1T z$sg_zInZ1U{>&XEO*0N&ef4fE&P}T=kwWQMg&=pVpdn*zeKS^{ug275Eox&U-fPj{ zsHoy_;>PMTGa9(xV|H%F%(;Q#G3^zqaUy*6NN^0Ca(5c^)Vk6^#U5%X+xxp_wp}W{ zg{2#D_x7^#9nL;g*@1Nq+R^_f>*{d0*ui zjHgeYS%uT`jk%bePRSXFut;@rH_Gl_Q)yk8k@ocIr}5DT@0oG@Hl!(#P=UCOL>wyYVQ|ycZH*6z_3CU(D^6H#B=_Pa0hzf3>8xF~B~mM_!R#x5 zk33wOducEv_GJ){VGICD%Qu$Hz@5<8B)-)bs-Am|rrs^*Pq`So#|QiI=)nik+TRlR zUBuM%biDP}JF&R9?78Q?pZ-~_tUU3!xc}N)@y>UC5K}XY?nfAfw1G9K2;P~mP;&_* z1Lm2pE1;BWOZHGmLL!O7_+Y+3A`*ruaF2u$dnTlLAkZTC)oJa-qmSQ@kAC{6vA4G) z|Irwom{faB#nQrJ+!u_$`TFY~OP0)1Zp@=dDM7ygMuwFT7@o_j2W+fYc~KS!??{W* z$H&b)U|(W}qspXiRy%iMYhzRJt1y~>XVf;VCnCQXogF13TXRQcv=+UCl{i+D z)9k3MqDil^nMAgkzp2Lt67c(x}W0NR)9G90xr(bUUbtm@6wz)Xp$wP!aib z<#{}K@W{-6m{o7TbuVt;Ty$H(_(C$8HiOv$;|tZQsL-XHNZc?_9;*#tzQag?Nm8kd z26stunBw7+l~`Hb3e=<`4TVbJ8Rf&+quwx>xf5<)ZX6sKtqfYaG z)B8|s)aK@fnfk!wSgjVblhs&z@@f3=PyR?{8jO3d-isT{x7EJ$QJt93{5Pn%TBR4P zbLgP0hUA_mq(awLo`y;vZ`^;yl33MRJ&rF2h+Mi zpe}WHe_v~-U_~MlRHHzAM*+ZI|oNNkb+7?=puu|73HltPX)M?dvDK~@DSq}8PuI5M#~*yG zF`IWhB9XPQFsF58%<#OWxomBHCz>h?nsrDw4@YQDlN(Giq;^3VdV9{zfEpUA#KB=o ze!{e4&Gx*d`f?B=X)R1mNVB=5yRn6nRvrlsd>nQVh z-g^(dQE;MgLxNo%m|h%WU|xlxhV(M6WIB?>tO3@VnWG(U_TFUKrEh@6#MFc+i@F)F$+*cAL8`FJnUMD|ZCW&Io?ACp2A51wBxj zdkT-FKKGb{6S5wn3KQwV)1E;~eVwYGdKB-BYe`hTn$|HNJl7Zkw*dF(fqAWpaL8h7 zC+By2w)=c3k&6e>&#t;GptixuAX)M6x1Hb5~jJ?!b zFi#&K;aXFk+|>y#1Fi_1-dtMn*gEbsV{};Sl#s5iy^hj4(-_n^)SSg(q_wrp;NDK= z;M{NilvWZKC~9uSvMMgVehTtLVZU<6wfwfx2Ly7L z&6O|Q^i!tmQGjut>7J=;rZ#~F&ub~`zp&+-#GN(|XPFeoJ{jHVlB&XFcst2n61e!~ zi)3UYTLmgpOdFB(!YB+b{9I3uH^s2M8z zFD7=%0znf3@1+(bVE~r&;e5%hzmkbI)_5|QYS6bIU8g)i9i6%5mXqULz>fFoM==Lji^<$P{3@1xd0Q5 zMUob{J5y$CS$^v2yGR}sVO$vko8kh~bFJj!+g1)-y3uuuJ`le0KKyS?7 zx)E=@`%ctnX0)l~(#d8VY4Jo#?N|>gG}t7dV$i4mw9(?&h$Zd7p!uh-)Xs((41Mai zereC4zNpkjV@iloeRfvgLxEHk1O(cbc7r)&6$Btoif4w9l3?tzc)}R6^qdywLm?1m zcB$Wi0YC~BU!}wyr#a~x$JY;+4hVyR7%;D~;L7^0}&Jit7Ip$KEPUkCuIJlKGtv${{uaNm%S zAt9?m>bdued%o~<=1SI#70R6*=z5d(b>nd*$8roil&XkZ`pd=f3qN_-4F{!t6^{T# zz`~FOtyqM%$uH7K<904T@YQ#wmGQB-d}R#hp>RdU`C^vAUbs09zkH=JgNAp}Hkf?L zU6u?>$*|{d`658J2R}k=9Z~ioziwE*)DM)$L2L^DuB|Aa>?I+z8@X^Vzsm4luZj-I zxYt9K;nGG+6a~z_FI=5d8BOn8i)Af_IVQcz7=+Oy3t97>5pZyjeDUcYJ7pw)W=eL) zgAWJ5Tz%N4H2tTH7{{y&lpy=usT3x^X=0qq^~R>CGsMpB2{75q7EVJh8=Ca~=6 zwM-1+5^{)8sG>o#100l7`ptGHcAM>JwUCSwZmRLw-*;)LqjJ6<7#NO0;RMI07d~AJ z;SW_ZPoF-EWgi(K9K^#s_(OAod%<8rRT4y1+5;vN#4hk2 z$_}%N5^-7^HRuq$AO@i#47?vgy;X`SJ(?K?m^A?Sz<|~h;h$$}I|^j!|IyLlp5Kbf zIIJ>(m-((8rJam87ET{cs7?o8|V9s#_L`JTf~FpB=o|Ng(nqt713 z-~8|XW-Kq?j0X=NsXzCv3J?5qSZzKq$lX$?lG5G+{7-gpLkizIJhTe1t?iv??zdH3 z)NzeiG7iSWxbSWmh^WCn);_0o&~kernZrRoG&_|082X3%VQGtw@XFPdr*Y8Q6-?D) zZuySpT=3R&Grzc31cEaXB-9fI<)ywiH@D1axp{LrUVHTw-=AfiU2fp<;MJ&G0)Iz( z?%9)vvAwb8`rLc{&6t2Wq;R`CoAHw$|5>a&dlU!lR@Cd$ar@P`w1-%Vp~|@6w$Dse z2&?SHkTh%TY{$nRzHfZ^*4_ItGruVKP=BZ|7#B!9f#0)N1d!-Im_KL72T|!iS9$M7 zwLTT=JFWQ9PanjF+I30ow6wGU;uX#2epJUtO?ZR(3>psc5&|8n3b}(yMGx-OIcV;v z{C{G}qxps9n34s+2e`vsX0#ozw+ zo63JC_SA0M+YR4+wxc$Jp=>EN!RiF}4-NIk`s(9&{P1J-&za_e3AORGrQ~*Z*W>;7 z|19>@w?iY<_}06>9dEt!y_lJs^WNqnG|y-rq}`wkFb~wKRgKYMk3k*``5_^KYC0HR zFk_K?VxBB@Snu5D9Vgb9%3ov()W<(`rc~A!&;Pj;9xrDi~GFsJIFzRs# zZp4}leQr~8&&ujXw4159h(3o&$-REy0&H4L8&sdM&Q^v;ECDvCvi7LW$(Qv8mB)K~ zyFLuWc!iEKs5MSYqYp4c|6|<4h&@)hRZGDU2am(^=CS4%>cO1p`2o6)-blrPC#j3P zmID9W&&GVl+|F3!;5?FbHx_1n7u#?j2N}4BjrQYU0{92_FmlJ5($pk@6y)OEl={1- zHQ`*ad~BEojyRyiJ(A2p942RM>zXjM7Iw_QZ0sLs zP35ovhnWxxK&#V*8PsE%YcI8rh0e>psBgdZTHL+07|os4n4KPv8#fjJe?Wl0g+m?0 zho3x(_4Vx-tJa0P^s1kkpZdJ^UuPhx*nerv^>Y9EP1#aq8D9SWGE;`TYH48ftK+k5K}y~2Nds6+T6L(O9R;d?zi;R@H{U2OV_1k(TNw=_wt zu`T~Kz-@@kOo5}n^JSut;xL((j_E|sBt`yLD;P2tKRe!4~h9Qm4~8>EPev-^#2 z{eigHG2LA=X6^heew?7}dhnB*)5?P5~6o!pCo8)t0 z37101FNJ7dYJxpixiSuAQvVXAD27ioX^}(UGt4g*Z#Lw)u~pdwCWr~cDDehY6F!TN zC1bSEp(?H|1OpX*z$^?75WoR#t_HP0jB8Vix)5iu{6^9|hpyc#RxskV6u{IW*NZ@qox{x<6d}dSi%^8(W4LCMkk6W+48q0U@ z#L(!l5e!tsbc6sMA?2k7=ujIvHuo%g5HXPWqL(md9guto#VpL~ODZof`iJscVod{) zyV5E`wkCxv)rBZRJn&{on?Fu_07G1;3yIJB){m24I9`rR2 zc>sotd5|p-5}0zFo}{Y8F+wN9q7Nd@rKa>Bn202W|6F%DdE=b0Ndq`yG2VYY#M6NC7?O&m~O z%&jbVATl8KJ{=@iRJWjl62t%lVS&w!{|dw#WC(F`U>D-YQ2%gDj84R;5Vqb6!TF_- zbdDG5-+e|x6qNpSSyg%};5Mg^W#_?8P$J1fJUcrLr{WMfW((s$j+LLKm-EANm6oI$RIllh#D*Y$9``03`Om#p1noJkQ0H`j@}>jh9@@YWAfd*z&0nzZWYOUmr_ zNUwbGSNdMdx&=uu7lGj9?|>OrfRh2zNiRIG6b=|CL%FkWx?u?_J8v6%%1s3?dig2| z2QK2Ji+zjUw)<7xiwr!m>#aOTSk4ApN=oX2X^|oh*P!%?MxSA^JAZpeqm8K zZ7tTf_v7L7O-r+&f~vnCbx8vzf+I~tT4%yvIebI?s3ObXvQ6 zHw1DRc|4A*dRv-JxE>Nr^;*pm8$!g4PlH->{|5Eq;1enfAtH0CA4bET%0wF@K~qZp zPKDmNY}1*rf?X z5D8J6hT0*B;7G((Mg~lXQdBcM_I7to?7DgDW=u@g<5Kw!tIbE02Pc(xHrC_c|J#3U zm5HcH+uqu;3d4%pfIFN{g}&A%rVLv!GAC=JZnIn5+kGB9h(G4*I(@i!v@@uzU5$+iJ=e(xgSO_(CVZbHDlUJ zl)aY2DmJPnfmtL2I2jL96nuGhN_(b$;oH5a%H*Kih}wBj`_z8HapL;G;)g$dFaGm? z{P%H7?SvG`!~}$URB6?;|D{;+hyVcp^hrcPRJw?j$DhUzfAm8W(iWF)#njBa(t;qV zeSu0uSfqm?(q1Ut+T@Jf2Q2y5f?%eG92*<58mU`Lv#8uK0TLB_oX|(L+NGYw*?KI_ zPe<>-a6DMqiT6K#q&kL~H{;_KGs+lKFcrC1E#aR#qlblWClh*4{h^MKKl_X0c>4HZ zeDvXm>Yr9JrDvvNad9z_c!U95SN{$Sj+%kCvAG-j8pjj$NlTRpOspMbePbg&`}8Bv z5x~Q6bs~BPN7M)GL)1TNclJn>jeW;S=QvRJ$3DtT2lXe+CL{u2e9X;Gt8Md6ARopX z5L^f@fqmvC2-nOT5TTKDfnf&27=|GXc*Zn$cma3d!|Yu+(8riQK1uaqgqfL|ihK8N zsZCL1HmEWk1oyh6%0rb=b%hCm6f5&wySc0V?~3-H4c{qqcHGu}rzsd!|FD;{=~4gA z#hrWiEe$g?Too+!dC!JwL|~P}l&D&S$;kemJ(L+SiVFezNNoyZ9cc&pw7tI_+v`ta zYvXzBY;VNY=9;B`E>E?$RGf+VrTG5u{I$6A>YHi{m?LNE$4SBJlIJmD?W>JoNWnDnA=>E~l?j!495dBiDWnCdAo>OPd5-$bwKa{;h^fiC?+IcopPw9f zoYB8X!7vYf_Sq-#=;3FA?W)?lH$ML46V226aqG@2@yfl|W2`n8$7j77kJ`tpo-q75 zmODJ$ue6$GG_I{Yj>n&UYWQT{W39P=`%cWx%&7klqF?2^F*hCG|L%9=t#5zZl0?92 zQ*aR)%jZ2qO8X)XR5pm}Fk4a4isTxMDb@{EJ=CbdyjywxELK-n)wjo16Ny9>^9ho( z6~Xo6=WFp_e)MC_<8@0*F3eAv7Q+LQ=ebPb_mu9sB}bqEs6W+q+z(i<3O-Md;{2!` zckkYc8#k9d=M#p#D*aE{*-OJLXB@*EVXw{lxUsS6vAn!6ACu!Mv(_`Dbp{4{EMfA| zCl6ys?aAGB(|X1fA7%gt6BsMINPp_t*x8HKbyR(}J?Ekhb8dDjrbsi+;^?sDHH`U^ z@jIcup4E7%C?8bDu|7P1_Bh`A@sBLM_E-MO4`Nd7#agzdwEx2&{%5cG^K%PP(_AyI zwP#{f{lWOty7X*qJ*pG4z7q=?0C&|_)i+#CaeS2BBP#hcSi!s3xs#SqY4ho?D_3_hH_1A!4So5;rXF}~< zA0O7dHxrYS1v5pE2onOjlA2g$I<<7s)_yylZtO+pRCta03&s$AXRSHvdnAA=NTI1u zw92c`&tq8A7KhYfh9Duu__De@)fGwjjqM#vsl$w7yq^j_xI1)SZ8D_w8rl%dQPvaY zsSw_QCMlS(nrN+#a%xI_JvyrO;KWS-);_9s^X^9^s7EZ$E~PpHaE|DtxY z)ofbbB$C|VLmZ?T;IK1{7#ZUyw7Kj&(4m;0!DX1+nBSolF~_hY{HJTWsl5moi!>Cu5{SsbYO=?5Qc9X*Vh z>8W`4-FM8~_1*ef=ja0@msi$ztWJ^xHQb{K7H1~8x(Jf1?`G6P-$GApH1;*Fw%nIX z3o~(NaoPtAK6$(z&sMk0XyX9ExZoJcKlM-Efa=dRAkeGG&+Gri zY23cC5Wn}mZ$)(&JoHpJ~|1 z5%Y37FPmR9-Ji$&`7*|Sw)rNC_QiWQ)`_dkvOj)ypS*06@%6X=2bLT=kYG0nO=@Mn zxI2V?uClzcVF=;4C50kC@>~BdZ0Y4N`R!DSq@2q&KbN6&m*FeJ^IL@Bhfmd_n>PmM z44ipm4qV`ei>Edam{29;=bsP!R4>IaOqVP=TY7L8Gj|;JxnV2-Q1SSc{v`>|2 zLT1Cy0!8^K4G1tNe(a}-AI4279Yx>3{PGD8A>N$MgW1JN!d-3B+AU6RZpNM#3fkhE zFupTQ<+~89&T1og`~H3F?ic3cwqvu7j_)(I$(c4wAX>BwOgu!x5tsM9X)52D>OebV zXcM2NkO2uYVZ_La9Mqo`ZM3H5XJcx1*1D3>&&{1+mcCOM_q+O*%{PlIOda|Gctiya zI=0W$7bikm*jSJ@gbg-##AXAJKNAulLc3E>vPZ=w2oJEshMdzreLlUadR?B%o~K+% z4`he5IAKH`JtmZXuNG2EYpE>wL4+w072lyDe@+=?H4;vJ`KsWW6JsD6&R_X}!~h?h zgrcAGwD5=!;FL6^Zd@cxd4TQG07oVWmu;_bh_<6I83P=eh^8RGHN+h1g=)#6!C`G~ z(G9Il;aJ^_ul@`5*(Lo(4XKIDwK48KkvqQFu-k*Tt+JDuoeFo16L{HNPv^?`yNFuE z?z)u>1bdT@9r;M>^$0H`8)Xoi7d~Y4O-YitUO3n#19eNPe`i}5`xfb3+0%jFZWHL8 zX%&&(PFLxtQ7-F$p z!lqj`QHJq6tH*7s#Q5~;QlxzqKkW|2PxrfUR7CCDGTkDML*=I*$aGFCfAq+>KG-u= zyXrghR2kfc$vkpa*NlV6Ks-*Pcaip0P<@kL+6teHS$^B)Dni$!Q<0Y2Bjc6D v zIS#wk!W8+JCVQ#~t8nCl!`$y(_E>~{MtB%K)GII|3;Sgnx|KeZ$hVk{QGB3}u zf1c)x;Pn?ZUyt$idE=sV%LBOSDPfY)$xC7r@DtjU6TYY*gZTjA1sY$k z20rSNxH#UDS&C=$N)JpA?sp+s2rTX6Q=c|Rm2+(@Ref;?r?JNg^aJ4&!WV>3fg_t) zCOig0i3xvIB#MM1pyui5Bv#fNvAKH?Cqg?=FSE71YxPFNg?Zw(a(jWx3Dp;o8cFbRY~-Ch#R_Y~V@s0VlU<|FcV_Bb>~P0@71xh<`96 z=m!qAL13{&8s!oWMOueykJdq3IQy|GkgDJEZWxspTvl(S)0+FuSXo&y@o$(D%44H3 zQLjc_Z9QHQ-rI8??cMG8PygXR#N$Vw#qa*^Ux~5tT0HpVQ`N1{5*tIKW6?8EQ3v-c zjg%}wEg%))?h;hofh%4JkvGn&{vq%2ap85U3u@mx9n>8`?5Df90A4t=@XA5;HPQ?~ zs36e9-(i)VzGZI$!HT{-6zl-lv~}|kLg1MhOdPa8+K+>RCVnX`h*99d04aF?`&*eLKGQz3-ZkJ`m^H zmuzWov|(Zvr}vSRfVhbygZEc@AheDV?sSX-D!mT+y z4+Db(ZD>y5E}7AhWWXMs_Qr$9Yw=9u0X)7wIWAZjQhn40Dj@v|tRpeRY4;J0JETB> zH6OCm8&ziz<4-!x*xTNWCyyRldTMcLNo}PzRi6F*NWF}xF0An|j|P1Q@>G31YE{%X z9SP14e0R|w{ipvJAAS6>CE0G>c{M84TJ#9U#;Oy6G?weBu>;W$;xf`Pz`xr<^8<$~ zk(3~Ph@-yCihYgxo;zz8XO`Te4r*7_prLw-u>unm$vaCUj0_t-8fsspnP4VB`k;Ln z`|ZO6!zAaSP`kRkG^4)18K@~`-a7201kQf5tupP#-u|9X`kVNwJ$&y4u&w##6sgXA z^$n^L_hVoC(!*BMVSp8g_lyr1ji`Z}n4F4QeL6??g>?Be3gbAcra)xJ&bO+7wTM((Sd6g*=`73tpYj^`}XXf#K`2pAk0HB%qed~KzP zbPy7ORWiMd*J%rpe%+l}o;GB-X-mlLTg zq!BMw{tgoCDzlo}u*1D#2koZHc5F3{sGnusr%h=q@RX^^2{XE&(E-D#B?Wf@CxNC1 z9S3G7(#viznNh9Hz`Z)lb02s1qaxS`bkrWKsmv=d%e-EzKrj|LECT+(+?})@a4e=Y z>}r0MCvmC7OURpb*IJm0gZ7kxazTqkI&xZNXI?^T4TdtbC8Wntm3^RjbZzCi=kIB) zh1{=(YD*4Z`%caN#0w5IC!>1y?ww`dzlOA!8E2YD4^Mkyr+KXQRXZp@@HTKq7`{k+ z(e4}ur_9jXm`nHeTJiAdb2HrUETn|j`p#i|{Af)uv+q9R?nflUkP17y?A6-49c!E0 zR^tpzGLHjio=cTCRi`{Kir;?ym3a5fS7blYc<9l*Kjyi#v8OV1Qj(gsWlbU;1{Xg3 zE=;+{q22#78sOtEs`)00_Kh;W{=xt7cM955Cgu~yCHNHSWj_2QS>yBBP?&r>l3#Yf z;#f(^NH?cI1Qog)6r>x-^+)D|r+(9o`2NB#0XM_sWRm3~?sb#l0T?G?w=8R>mPlQe zFzdyGfhg6D<2N>c=@-&WrkyUOx%w)qSA6JScBe-W>^Sq?jpGl0(V32`NLeyl?U}W_ zax0rA%X-xY`CGg-(DO~&vT35}29Uu@O!9rXM&)N&m$Lj_BZo46*V(Y!i#7;P zO&d)k@LDh+47h9x?KHKy0WoIB$SIhL7N{$90>gsHLd9GOa;899 zSPLeRl0DNRL+bc(N`W%-5T6sPh)(Zokwn+>=EkNbdLiInG@gG2ChvXH0x~ibi+66v z@|`={2#vd2P+QV$Xj8ep9VbHYS%^^?Nt=2@O#6c13K2rJ4a5fbHG~|POnTFoG#!kq z3oVvTSk5E0v6x<%i^;h;EwG$4LS2kJ)E+D{oN$I&!ygMeeWs4_hMLoGETX6a;Sy=> zFfuRoo2Agyj=VXE=YCUTQ<9X{Axv&2V1vP!WGuK3w0X#dG{y4I)bAbF5k_A@SkmKq zs*DhMe5V_KbgUloV`I$893=Znd>7BK2_tY)T^{#gAk9Ew*N#2ATTzKC0t z1CyheH-TSFJMDTD9-p$@xcRN;`WxdSIJKhA_PzRbIw;rdJiFN&4eY<7J(q4q;r!X#0QJ75IuKJX{NF<{Y zMz*YgjbYp|GQkX&c1+eS%Uzo5?Qvx?4VSZwFDJ(@0%qEUMW&P_Ed5JUcz2y&2%_@3 zs&dR~6d&nTS~Efdl&yI%q%<1SxTgm{g==a1B2%=dZ5f$w)~t-f@AVY0W3ojsj9u*6 z=4q~C6!G=41R3eeZYCS?Y`%gEq8`EyLisZO3r2o;W9+5Jb&-`*yhy)g7D`+BzA#>#(=}6sy(->S2q%GE|9|kW zf5Z6tRhiHA=bxjY-+xu+mt}kzI*Yb3?hFJ9o_!b!90XjY7paR=t6M_t3hH-|kN{r* z=bVHwGJ&*Ho|1;JiJCki0GbOSAPv}$io<{q8YbNJGLBVrR4;L=ADj$g%%JcK)XBhn zP~yUMktpvKes^ruSm2zL7S)NULPMIRG7QnWCmMV0Slei%ltQazf(9rRcnieA99)`Z zG_Sx&V(5e0m{{0_540jA5j}|%G>6&)d{PBZDJxW64VoYb(Fg{LCG~~-fZOx?VTx+BQu_j-K%BBi3Jsz*c#@e_0}%fy8;8tI*+P>ZWB<_iSkZR06ViFKDbj2l8bdM*LKCpZ z{s@T>)MY}%<$jwU^~>bMxYd5m%}g2pMV%wWVN{jvK`2$HLNrIxr`_C%+jo}Z{{8z( zKYWots@XWHPai_ahDgeN9ed4IG@7O$v{7V`=3H7S3NIL zlcb&H;_QT_7f>e!voJMJC{NX$^mkfnN7_yO%V9^x3DPH^*xZHJu&T9_7#iU&5eTyy zqe_Fl68n}ZR80jGc~&g{b^Qig1j4R1oeQ+FW1J z9&smDR-VRB1UE2%k^wOt^{J`&&Ub%1Zr!|Nct1YUJRsPfTf7mY<8{G8pBX#{N`G}@ zThCT>v>$=ciDb?=<4)}YjGL+DIVPpPV0<%vsve(75C!Kz>VUZbW=E@i7-oJk7?nTL zf{YRN-|W+oEQNUkBZYC!UI{4&;LObAj`lC=r-sH1#BZbxm=nj;)-VZBJ9lXs$cC5Ij~b*+lyY zz&-!_7;G;RpBxhCQ(J3I+G)hr#)jJR(6BK%UbA!=eX+T{?RoP^aKZdKH$SVPbZSOX zRb{BE4loCs2Wnr2nSuj97Ic z%n8jVnpX}wXM$s3TJ`YSsq)wJet7of93JTt5L8FFTP)Wa+ExE%2tg}=X?UVB;JHg> z;l9O7nDqi#qy}OBz^M7`*?K&9{9It$6Zh}jiiuI~l1hy>Fh&^LR0vhGqga%ZPNY7oo1IXyp%353XE5@MxYk&;NV1V17zuPv##1-^<(`- z;+q5JP)%XBrc`pv>kwmpQm|H4pL6FLjQA%{o@icsrhYt&5v_NO*~KNK&xNz7PtXX& zJis7Am7c&PhSmN|SscuOi46muI}BmCF>b&)DySva9Kw7=+nRnOe8ubY{+{O0hQ}ee z2sj2>h)|tMo-mkDPdPm^ZTtY71<5U#j@;43ffDFL9E3MRPW4KaooFS>yY$-arsgeh zH(>{Qz-?f#0cWT+M4hbfZIqpRFo9FgJFN4JAtnuGTy;7yU`aM`8nrC2RG|rmbL78h{jl)%Hqiy-09JOO%a>&f& zjopKI@_fgPdFJRo)dxvz4lc~h&CnW_Zd_U2RG5zPL3)?D0m;-+GklR`J~(Jab-3SZ zLKo*Igd++1)Q0pKI5(%ol7S)k0T%SuOMO92zu0`?{`KcH*O@L~WL{49tHOUB^Bcw& zhH-S2S+@7r>q|4f{^8&G9~DdgP&L>wkSGsU{doGeoBoURix*B;c8B3hZ_0}&1~>Hd z;phm3NBP3LNF^(jOd5zXxpc_aaq^q6Ab~DokzHDdlOeA1AP(t5{LP>a-i?eYNm%yL z@5=*5UrtvqrCX-+B4IJzy7ebKR++LWrE&PeuLznyaw|`&W3o*O_jG!}IH*G@ufm@g z4$rG_^GgBTs&s=Qx;MjHckT~O8 zi!4m9^C2O}THr2O<*0xf400IKJG33TWtq6OF8CXUmN#Bne7IcL{(Y!J0@(XYPSO9(z2LZrPo5l7pg9)-39F##-LUV@NP62urW+aFU zVUhY{^K~JF(VGJG8B$<0K55f;s1Aal#C;8Hwm{-MS_Cr?U@+9lbqCRKo#am*l)b2{ zPqnCyFkV4&SeQ$K4=^n!c_)JpM=wr(3O6N08_aq7NcB{GA!<_VGiz}gdP7VKzGi;fw08GUnzrRr(MR8 z^pbbb%((?~b^Gusz;+EKnP zRPoNx_P=h$q^}%tClNOort5PRylmudIAFF6S%h<$fW=~bW`kq1U-@OVj)l9+EL+#; zBYld#b=0C=3*+|dhRd*5sTaTYECONN9>r$?Z^W>1*tC}B1t;hKqUrj}VmlvYpu$cp z`(f9QTZMkqpX0hrMI;Br)wNcfqGcQ~y$K37L5K`Pa%IhnwDii6uRo(^(1uV37}82M}0%VQ(s@SCunkSc5-Q2D~$S`dED?Z<4;tBv@P3EU71Sf_mu zN@=lPBW+O`8H(W{a2}XnIfsB#!U#iE4NMqRXG4I2iP3>@qWq9MhoEJgM)(BytRt9 zfUEdWPCxun@z*ZKxZ0VW-JVun}$r^Q2lsh2waPs9wYY2Ln&%Fb}GHP;mtA z&V5R#?cbexcR(QZMj4RmKN5~aeYn4jGSed_SPu=y zSQQmJRTD13nINQse{$*`<`54!9+C-2^!rc}^CBJZzE*mQNV$>r=s;vVgAtaR1vuFc zv8dDDi{pd+Xg0Rv(Zf&U*`r6k%O-ICV=x0=Uz7?4aypWxv9vR`TU`;A1A3Bi5I zARUJ(pnVSnGYH@Psy_^>i*xQrmVIg_I>(o>)o8`;e#>o082T#vOSrY_KQc0CDG=@; z0*BVWC2#;@!W^^@+@8SjsKSCDL%?e69r}JcRA}z*?rX1fsQR3%|6p{%Bms`{z8xfE zASkk@s!vYE{KA6DKBB##@MF#Ov_E(BSVg_+2JXMHwdwsE(sIkUmMqzE%$-`T19fyt z7WG|1+*TbbBOZ$Pd zP2=YVGnczIHW)o;CxVTZ;luZ;$s10|8?*E}cG z>ow04?dD#rudnIZG!g#4{crzfeD}M*6Qh+e)%ze?YNy)7r1n^DTTQf(|Up2K2ds+;KO{mNsLH9_fqO`Ndeic~jv~L)KRO zM{y|lOjTIW3-qX8C#L4&-ka~L|L?@!e%lfp)R7qx^>EaaxsCF{1evN;Pxt3N~? zTLm@c72C@*u}f!Z4toiG4tr_qs$;0?)Ajn`4l ztrwj*Xf`~bpcQXSeUAD`)&&*Mk`g_GqtUCr1t){)1R5pq;G%gt$6*lH`J3o@#M*h z8KAG+yBD|a+=&6ryD+CtI-THtCk>Anf?*7Uesd#!`e#3mPe1y=j9l>h<;8{g!SDRQ zl35(oV2&AvJ^&3xV{CI{BPO&)OwCMLGY!(BN2lCvs5wjdY;JAE!_OXQjBIP&XloUS zc<0-1#l73hak#%5&sSF52Q!OHzW0iIsHSJ;+*YX8JJwu%a0H|NB${oFd!@;Nj$FgE zrU>?6z7DD#k=~>pFv3vFR?)gSBzOE_ps>~;F~eHSJ#xUYiS#hD$0~vq7GrTG3P;wsy7!y9Y6< zGQem!LKM7r&@c{egQ`__-^_Cw60R@OaJ0qYQQmLAr}Dx0Vr@lT;DF{+))V?0n1oiu zT8#S0`c&OvxKkb}+zYj#)h4TBVPe5}Brn#1E%p80epB_+#Lze3`XNC_Tfs0Jsi@6m zhqeWC9-0>8i@Q)!`D_{=^O5=mtvIy_Bn&mj4zcEI?xJ5b@3Ni<5Ild#NpR4k^5q?< ztVz(Npd*6QCH)2Zk6K0W;sfF?7YB3H?#e5r(U8;@EFYSV0XUhh&<&+gdYdo_?z+T;1G_vlxus zRvtbX26j~@RD`lt%ySQy#{0SYjr-bMH)G>-c)GSDd>8y0 z#&IZ(x}_UYdCEZnq{63bBQZCvF)kQ_>BXJ4s34`ynW$+SaCJ9fHq#4+GF~@s(?s;X zmU%gym(9y*epUFdV?I}h;{6xFfL~mhU$kT|w%r%^4}E@>eunv?a9?f;#@F9ftc(bd zYDlroFff_eB`evOfWupVr45tYCkCfK(^p;wNQdD`&x}!;%&qI_AUVkMLl61uRi=c& z#|$nkr71k^PD9v}l9nmymw!39yk#euxJL=a8$m53Y+T6;B!I<@$(Btl$OI=uIF;iKy3zt^0dZ^Z z?MI*DPH3^HYcU-c5{FJ>kTy;S!UTc2z=F?0M4cfHkS-$0Db}0|JID=}G)`I^4lw8%GR`qj1zuilQuJGX?8je7F}(c@T~hePFku7wlH7irqbaOPI!DeZE%k)5y*0P5pWpP7zvAw{EVOI9y7Jx0uc3(^uS zz>I<+NxlY0kOA6Du)xL;rYCxqNg9=loVo-FA`ZkGU>yPvn|Y8w2s4a9;09HNAhZyx zK~&X+N(LfEK331DKWYFRKpX&JK+230q-^R*3wSeP0SqclHrw8O8wn|@t#FhH7;{^> zlC&F$a^495B4l_`8W4gM%xS>zLh8)0Ek`y+W7q(k2~PB~6HF6ab`) zcmvwdRjSn(8PsNtcD(G5sqyKkYt!8?1XgI8>I3XjJn95eMGH_78OEbqga*%gD_L37 zHLI(5*W%zKZ~J4)wDViP*rB-&gZA9z{gMfs8*@7FF2ga%6rpois#F=dwjy_M$z~-8R1qFn2T?>@sE6pa0M& z)*_sp3wx%a5B0SJIbP9r-3+c7oE*1nv6W~VfU<&EGZwNYFN7=XnfB*R*0Tt&|NLeq zxN3X+i&TpDmEoJ8th)SF59*rjRwiiAET6u$Z_SA5oN1Kd`Qo2A3Y%^?5y~F6Wk~tk zk|kpuD&r8w;Y&j~{MM6^^_InN#g>(_6_)OsGRvY*r3-vzhW@vWV7&R3CFdqb!Bt7v z;%vHQkRd%s#;(VQJJgr{cDS;h`O81v)Dwa_uHCWBN4h8+0rQ)du-(y%IO$ciTj583_x54Ujcr7;(G{!#gK_xoS;R!0NMgztZ`=&hlpUZaEhDp4}s~R za~iD!2oD_-yC`S(4lAcEyjOTCC-G752L6irBZ%$I7HYr2nO)1`=}}(bVKB>vO^l*0 z5Un_z15r2$hKXarSTatfI+t(*o{T@tw$af-O`z}+jPcK-j)_W0B0>1-pb|~(2o4Pc zaA;&Orl+cLYpx!n+9N60 z8>+^*hp0MQH7*4X2YzD>2WnrKHsG2Ntx!?K0jOTBwMa-oB!hr-rang+j55-H+!qBd z1`~%vWM`+H=;)1#v9aO77*n1!2jRCi)_tcCILM&Nj8q9yHZa?!XC^Jd#Tgg*=JkcNOU!u`WY_yN01%eQ0x#!Zca-1E>r^cg4iqfc#hb{V^> zi`DhH%#7s_?0BICsaHRqMr~B%wErTG4q@s-faZ{<#;MwsJs9IUB@ns4tS|QV+OfK} zuJleU{r2j;yP5;Wv^VI)v!{>Z{hz|{{J?F$uy7-8-n5lFRhD3Lt{r}bg-ET|6# zH4b5Bv)@MTB#dXqwV9izn!(f%%uQwt2zJb%RQqrTnc+!wX3X`doI`^Zj{^w&zzpen zzXb7_c}4K9*)>qh$Q;JL`Ps9lv7!Fk*jS0(oh?f_AVqnmv5I5|`|9>V%X1x4a`SUH zOyGwAySBa>kDokIU!iIiEhHnF=KA7Po08G-nk7IW!XBuv=tu54^nOlx11rqWv>#Gi zNJTBp&-#uX?0qV%iT{d^>PPlzgPQ-4?41!jPIzo{I2M9=olXH z96d6kIaRoMpW15>W{liYlSq%Hkr*?LMl;qnnz5}pzgP3%l=8W?I2|+7bdd-g`5Cw$yefg2`KpbH11FLT!(VJ`Pp*FzAK$*z#Xpc@is6pT_L;wC16^hKG&k ztFhN;#PsZREZtgGJ6%QthN;HGk>-%oKJ9HeG(4I_^6k}?*x7g<2dzDo2no{Rn3`bHQuE}*4>7qG6tOkrJu`2xcSW-bgy@REJ? zCG!z;3Wpd_!HV=XW53fr5R9~fJIpck-Sq5~`fOfh9Woq13!<$VBdjwVu%KO;A2|3z zJHROAPR{0j%U41$zDVCjWi``TutEON1bq;ixn1iI2de2)+7G+}dJu=#$28ty{wsOS z4~JeefL$2p%u{`Oz=4>Tp%to|F@Sl!|NGqDbmNo1DflEb1ckh?BBX+^{A+Bj?;r^tUZkRsZp&_cU*sjs(Xj3vAK5? z&)2s#?zvy^Jf3YeEZxkQVEl1d=GM(c#T{4vmx8NHjsG*@FyLCphWSyg2Yb7%_~_wk ztnaBER1Xe_y|OeD;~IY}YnvW3;4PIQ)mboz`bF}yggbY-P%S--Lt3S5;E&c)tB%XWR4N zdD_jTkE8`3 zLvdUNoC`l&F|rg%$f^&%v6GGiWq>k2Hr=#2WyG6izBJ>jCoZ4^Xz}Y2B7TZpe!W8S zI4cGdV?b@puKa)K?EOPkRtvb=GPH0f0quKu8&kmLnnM z5ERgd%Vw8yviO+cA>^P}>5XZFKB2r-VcZQ;0UmkPu-` z*l_v{^#W{gFF4(!KA|nB0}MP6E|3exKbt%Ho&IA(kc0zZpI((C4@kQ5t8$Shn~5>* zn;J@3QXe4xt<>E=AmT7;U=V^N(uUlVz==P=9<>;UDl5oRN=TtzhE1~2R((SxB3VlU zs!uu5hgukr3imI_9bt-c(jQ!)PJGk}ovK3gJtt2<-HKXpp69^1_ zukxC)s&uG5ZR69`@?+x%JYK3yAg&OefE6};X2h!8oa%!a%jsPh_IKP2@7Y}MGVcssBE&dvFIn~)3S`%^)BjbLpuB@?QStKPCMO_Ay>G|6itXN+t-=#rErEJ zBI(O%W6C-ZNN>5@s>jO@!O34%(n~mzqZ7y!oHnjF+eN=FoIkRy_4cPT=*GaMFjsk$ zb}lM*I}^_TxMtSZ^X}$F+GYS!PkmEvyX)VTk(0(~QH0E+NYf7dDskG3xyCLe;5c$8 z4Gs@GVup7rbebHAM}MRtfz08`=sOGMbjy0BkLD9w(%<-mY}|iCpk(mK-SLWGvSs}V zSUM68t6H7xWT($EZ3l8%lq0{KQ2tVW63YZ|kyUUiEA>zJe7PQk(WXL9@+Xi}mt85_ z&I`!LUgT!Su4nPe-^`s7Wek41<36v)4A$1%?1P0umaf znmhfCCxB!-`)S@+JP20nI&XzrFodeD?5htZi<&-REZK-Cp2isHKD9^6=q< zc=Gs}a6;jjaz~N?!U_z6ciwr|_v1jIF7Nq8tHAEgj@3ePsLF@1RB!Mt(5PB%EN(2{ zFarivZ>Z`6rw1-jC&s-+s4a(az-f7i)RVRG_|Cg;$E{n-CZ0hQ-Pu}?y`4?9f%;1A zwX-WYQTv0tB3*EPb`(z@J+?Z$p1z@YW%$jhwwX+q^l@BTy4V!A)LyZ%dtS~G08k=UEK->pkzWds1aqrc8vHJ9> z$J6ir{$Gomx9^(CIj(wFDy zCd{FlZEttm1Wu$TTEgKiO`*D2b^4I@1Ov$=J?L;xA9rXC1o!@MUk+=0L$LF~`#+BV z@}K`>tUZ6Gwiz+w2STvNtp28E=3{(fT5$Jj+`a#X({8B_d+ihTyjlxr_(qwu&#<(;On$pI=yv+1Xjwi}8ze2k^>%vcGRobIpmR^R{=Jv7tGGxeEpp z60$J5py4o^lM0JDMJ*09BXIX$U9n$=!Ua}SI^q!wY)dcM~D!yc3Smr$uYtUj97yvBW6v^(WF z*4%6fPR&OU-%kp4s4${fmw?}$t?gKSzNWeQRDCz4aZyR;l-jpXFx)>n5j}cC+^?ce zO>i~br-~>~`VrzZ_nL2PZU<`bAkL!zxj;t0^7p|fAIHZJ9>(I$JA&Ptap&fe;Cj%~ zX-N2N2!3D?z4PvOd}p3AFl_a3m{X0+Ty}ZdiLLeLv9h+RrR^k!G^cXU7IYrwW(e;S zQ!^SLlQA%&`AG54gwv|^Jclq=k|}wizSP>IenTxC(um&X4(C9c|i>C5^Pk zvo5SXUpJgi)N5{U)*$E*+^fibq0!j0`aJH+nw>-CBXpEPyN&t)ItObXV|!?LRPBsZ zBs8joJ@y3LJ*jR|nYm+%gUZmeP|>G3sMR!nz+IjkOaN+OexB(8#+lE!|BtzgaW|+u zG>u1NZ{HH1d+N(3_o->zBgMu#=lQ;rRumkd78W`KI7Z(fchU{njv8a6MA7gAEsl0V zH60SZl!5v)eQeBe3iTgDA``kKQ*%%QA99LAw69L(SlH5o7_m4)h&Ofbr6hNf^hm~_zP zIJ^zx9Cy>BlrC!_^iCE9;xk8acpwdjnlRKx^OWEzG+tnUF;@_QxsY}+^GodyLoMlh z!vCOGstsU%`9S~Rh~@;1U9GhoN{+?=zz z%#+K3*lM1{`c}(~sY{Kkt^EV7BRjFWv7`B4eI!7eo2tj{-@3CrAB*$#ZrfR!7N(chW#%fq3L`hSja$dK z$>)swKI8p5%r}`&cdzmn!d$JTS?8}`wx4hB_F~`VzV!?G`DYk2zW%WpUnG>jO4Vgf zJIHUKZxI@IUQRm$6sb6PM!T{VDLXvnaypt+OaQa5LZw&nzMk$2Kl;sd z)3K^mE`^=3gdx!=$y#O%fx%U;X2mB zqg`E$s2meople#hiN}V?$alf`;2UNL3n~i|n>4a4%Vm*UJ)9(A0R*XmB8v$2zBYMV zLLi^7tZLJ^>k0oGGiu7=(cxIurfxzDGG%6gwR#!V_1NOgTDVzEwGg|%sFx5GHm@KJ z0HMd4+dzHf2cn9?sJ$%>rMF>9ZCOFh;fywX)iEQK3SmaARpYSmDjnXO>S0mNe$plY z0t@2UN`w2ZK*HKWdjLUer#LX=*gVImn{sV5s<%&4-YE+7h&nSSK7 zRYypYH+(8HhB4rcy4nHc&P+J$KC? zIX$GCLEa`qmpYrV#bx;PN(o=OgN0)$SY&z#EmK9`|TL{O`&9UG@Bw` z@$UAEUm5=@tX!1O^)g@gdm)|D?)1t$(qPLKN47GU{$6MgEUwGT`Q#dmOOZnQF_kHS z3|*Kq?Xphx%Q#o&>Z|L+i~O~Lb$Vrd%5!a*ad>;lCO`KN5B@yBVNr+D-`;M+glU&q z-|6QR9UfD*wNp?T{3abd^=(Fx4UwHd5grR`S*Fu9d^)3Sg{!toJH~Ns&$vadMOn(q zD}0f(zvSl>m3A^MlN@#xyGTnUE6dU~ zd^;0a)JEjrP3xL*kgFe@GOYf}GM9OlaWgHxO8g_!`QQG=!gY z-{$FyO@c0Ph`lF{&U>PxSj68l-J$nnW1AIFb>{9fF>doRB8o$o~FIPbM;?Q@C!X?*tC1FORV?_)A3 zaixVD3-Q~(`+ITo)*a!Os)ORRTYF|+aTg73ge1b`x0%;Bic#U}S_;GA( zY$#3CTB*Lmy{Z$_LSWU77m0V?TwaPhw{FDD%#`{*rK>n0-)rLUsmcYx>BM(n9H`D5 zjDoo`)PJEp!PEHo!Ak5l+g7&)c^w(oR_%zJM+SriQL2?HV zjHUfnCt48J)ZW9rg5l1A4^o=xtA2U*=o7WU^Z4lF597)6wYYQlPAtyN#RngL7;nG( zTk+Tb#{b!4jYD!st{ry{V^=UXIgKWZDXZ$U6pjWqgxS5uZtU#r2=3YE3|cB>ZUJ@g zv)aE3mp|Awp}bz7)*g4rccUO#*AaZ4o-oc}8tbh+3dHTbeHf9as^_@j2WAjz&~~=g zVsrIz?CosC( z{aDwyL~WkHMRhoj=?OHP3|qzBd++_!DjiXqDIik&A|atY2Dr!NQT)e$_pf4iV>MoT z{q^|k|K0z^u>V+N1B^o%cpe+CPDD-c)iXRU_|&|mytg->$4`FzBTH?)e*cYl?ag;$ zaAe%lE~pdh>({>L^jKp=dpyAuT07V$9v!u#rE!476|hyGoHS7sm2F5P<=&2Y2pU44 ziT2zFME~>*R(v2~eG|q_!%Rx%VoTsEeeW$foWPz*Qhk^c zxZ906Vti!KOxIU#&BsJl^O^brng!B+?Af^I32Bduek5&1Xd;h^0l_uQeCAS^yknZ{ zsk34${|mt`5?}1)$p74XM;HcY%Dd6n*IIL+y)}1k!JMrK_K`Z_vWDJhs=YgESNDnX z_Muay!@2``e^iA;DyZDMdTr1eXJ(7$4Dedo62?)l#!E{uwxV(J;NerNZG{=IytHTu zxI-8g!0siCPTH%->lf={O)zHlZj3_?604j@{K7DUIn&&0#Gn1}PqemP#_ZzlSiZ3s zH|A#Ipt)PWfH&Gh2FG1k}T8+);}dtk}m(GkrLBWllHwU_EO)T_1m^w4)C zo~bQR0Zdy0`^+KGkznqiHkX0JT~i|!!J(#`Gqw9b-$k(G4l12KwHbFpanRyiYq{^* z)O-s3!0h0_$;Q@RJcFJin46oOQkgXl)vhpo=}Uo#N&y2)Fu;1PxFhOs>IF>EHmq|4 z`bLU!NNvR3hRm@r1vng?QeoU-hFaLXqJuddM(fl>Rc+9(vUlXiAp!2AOZ9}EW5F^^ z8rA?6XrIG5T3=WlIS2!DkT!t{vAy3`o2LKn9-4``zY6t!(6FFAFitrbd(KVjcCQDb!}BBdMO?Z7}Airs^>@IpG5@;9Qi2 zJQUCeW1tCwPtoQ+5F%LQx)V#A3MLJg^fk;p)uU$Vbln7en#Tl3eM*}vs&!^`xHn#V^_JmgZFR$U zzMTs<=RiK=E%&|IKKa(KUL_47U9K7Y+@4?G{G#zNzf9aOGQVMb5r;m`e*Sq)GQR%D zzvoyb=yVIs?$eI>Hshxo&JOw@oE%D%p82B!`Lpyd{7lU8QRBi1Sd~WxnU_!Bw-I6GDP}a3$360B5*-Qq+CVgCsB;ByyfOd zSY>hM`7&uL3zI?k)GI?^aHpL4#$@R0?`|%IDP3fv?Tdg}H2LAB2{QliW8%m#l+SUx zsg)72UfHjH=`?_pv`W`9ckEgq`BGe}&gphE?)I>dXv1=>MU>McK4~am=X3{~X-+lz z5`0b0XIivDTtGNEslbAfj4v%vTCg~Q$fC=J)Jz-dMp^Z+fU%ha88}iLkWena^rEWp zauAYn6z4+VdSxGBvDQM(Nk4Q5dj;2m0^2LbdNP!+j&c#?r%-C?uYcpG|*Nu1~6-T>)pwhoA zqE-BgA6%g#HRHOBuMEK9^}BMWCSzxHOL0AhN?^4OdwL7LBvd0P(mK> zDl>l|gD^fZgzrUKoG-UH;}9<1gj} z{ZZyJG`*G~UNjlkmaCVOE7GJ=q@Zud*XBVrzH)PfA`dd8T?#wlDT@>2Td!AzD5eA(+%bgfHdEIXgJX%ZQob@~Y0}5WO+F1A1238)|$LCdis%uTU7sLj4};E8g7fwthbpbAEmu0KV`Tcj#P@cX=E>)$~xLR zeTq>0sum8XP)f(C7U@t3n%gGFu!4Z{rZeS z?gew*;qzUdkX6`=dUU^w_sic`23RCsK1g|Rj|W7o6L}m77h!YH{Ui`2`V*t0(C{3!mE!v2g2P)eVB-Q!8mv{syrtrRo~I7GE^U{tx!)?tBw24 znOE-IjpduSVtgW1g`w8yMEEDF@jm+K!}#>$kK@tf$7;W06D?7jb?=RD$18X5tBw`* zc}H!46iCHt1R=^GT>(>PNH{pS8T|u(#@w}|a_u%-YX6E)lMfB{nAo+|XveQ8$-N(4C##SX0};oM8)bbPBPK{1Ud$)mErr1V$MHq}|-#GgIN> zn3M76ap#rSqCP!mcpn=di`sat0Q|(YX@3Z&9l;!u4ONK0f(wYGs5F9shZ?_@_7lJ& zxIF|!q*gdNKCZSPe@*ifIMW!c#=F1uo%qi8 ze>-YZi*easRX&VcBn&US7h+z3$%(2$(pIy?QF|}`noqd`B5{fwaK`5{|z%~o;_PpIxrPA2MI35G|pxhZ$xc&UhbMVw8z@t z-HE49ADLnFTkn1+zW0OQkBR!c%9aGyV~tm?L8yGsYks-?}juZ@zZhjIR-;3p3vm34&whrIz;F z6PkY}>M+W+A01$vgb#NzKXR8Cho51tTnIK!&QUd|wE;k;92$+o?z2oEXX?s+7K4gO z7-WQF-Z)izrP?&6i++ujVH4LmILU4v2{jll$$a2mHKgsTUYl6621hu|t2tP0!aa*f zT+&ZS&oOq{uc{&%^GFVj_--vEId`>QaOVz0co?=wjvT7pk)oNHLVewWrDv;^VeLr; za|cRqYtwZ`Us%cun5A6Yd&t35RPya>J>-pK z^C;3~nq%m{%GkKuiTm0Pn)_NKn(=&nCmudolU-}K=02nxxkC>64YZnBwb6~m8MOiP zZ*Qu{9OghQOg?a!q$Q~N1Y0mw!C#Q%g>erq-ls7lcUbKiNnx8&~;$`u+I2!iE$W#jM@p+u^f_sNm;3IrzVHadxdXI#LU!$54<3uoeVAR zx)g4uGSMHKJ9|o34k|2bC{k3cJssgZ927@#6iH*ojn(8)7RB||69sJs8X$NFw4Z*Z zuL?rq^Z3?>%S?F29mez?^`#k9@+Ula7;6^?Zh&3ZOBmR!rOfw^syL}h3VewoGczG^ zhSc47%*@THujW*Se$Q*DDrRki&IJ97J36N)C(U#M7X+tl3RZSFM6tbNh8VDl%H@u5 z5lj0Cj(xaE;S*OJ%<@BzQh&qf%6cOa$^B!(+h}X~Ax*cpr?IQK7QE?PINuqxRMnF* zSqqo!9HXhJ{M5nP0F);Od1_i)QAY_w`0ZC0;@kIT;`YM0>Npjh^8p{Q0EXyS=B3s3 z?O0h?UG|S+zjdm)gY~TA`zz;!=fR+5|JOb|i_Kl;(oT$P+(F-iF2`De3PjdD)Go5- zH``6Ei(9gf2`8HO0SE4?MPmRw2~5&gz=G&YJIT<-+28h2n660&_rX`1Ytb+-r1Le+ zFBA8R%-2cpSDW(}nXAV9e6hYP_cBiUfB7Etx;yh%VU@`!Ul#9+4UDh8x8M5qKXC&l z43Vr7Rze`IawiY`H8mKxGE*V*8e|#IAu_B05hvn14v+jDqWA{dAmpSy3ExEs|K?kN z3S+{j!|_i6i*)%T-Soy7XP{Yq-9qb zN0L3?Y8tmo`At~Yvv}OJ{5g%Z+hQAkxd|!1(_HyGO~0`cQeW5Iir`K^t!_(C^W|jW z_ESz2hHv5*kAC>?e!GjiY4caU9mrvAiZ}HpeLP6sL|bj{&G^zr8C8ccMJ%~Oe8pj* zWfD$F7%eD*Xig(A7)oYDmN_MMki2122(ko|gmfq<8!}X3fZSt1VpyzTQo$r)!5dHq zRoJv?aTu0=Mei|AYsd~y)=VHZ6APnHdTKFAy}Q6pp6JDx;X=S`2E>AegT)dA1HwZ? zNO|Xw4PL=u`lbwRt)iU?k>KPR$o$y}cNB1sfsjURD$h=Yun55hVMrp3B6#-T5dtNI zjSI;^fVpSOhC1mFsN~Q6t;evTMSrY1=Eauu@?z0E=}ez7-mE@H$TIB+!h~LRE(m50 z85UxP+7^fvY^vG#K|Jt@V%lC03!){i)Q3Kmqs(3QVuJw51eh=~qco|GCsB@K^J4#5@aQa0e2G67el z!RaYBc@O|dJsF9d3Zox@d9^2XSD85-=1Yx1R+T610AY!|LA;E#DNi=FzWYmsfMGa< zI;J6*j6>eQAq`U0gre$KZ(DQRdc4c7CQ7@%i$Eh5gC^WG;J=Lg7}t9YlZ5j4_KFYnNWQ*)Q{C=sFDr z$~=oQJ4}Z6yZE*#EOv90tTV3pzFv=XbNIp!$L^Y#F0zzsq5~H0MOfx{XH>YkLNcV` z!xwm6Ul-Hcc6pZVXMcwwd{M?Sj>Fm~-~KP&MVP|H#j@YF9(SQRki7Y_cDs%@s{~5-kK0o(L2M?|{mVYYCF_8jXJNbXdr=@h z{wmW3KFHVbkn!D@xI1h%j$y}n7Je#JITq|zHjKma@Ts@c&b+$e`Eh=PA(&iTHit@o zyJrBu3J2_N2HUVCz~q`+hAm7H?$ZYk{+Gh#8#llAH~#iNDXhOS-?S+}zz?wNfs&?# zozfUTG<;u~D_`J8kaF!QO~%o;;0rW`J2ToxXR)()7#od)*l8a}tE2TALcDM&2m(AX zp*p^NA7UK$yl~fRo-pR13aZaYn_+<3H_C^EIs_~57~r;Kkh89XlW>R&1`E&OAzA}a z4=5bz02M^wM90Pz82{iH;71%HLQQny7T~8G;z3#lV(F-vC*}P)Ft&`psyxIS=(`jS zEL;Ix0{lnqB5xCKQ~grnSunLw>jlwm*bKQLtAK*pgVYU78cW_xRrQPq_lbd9Lrexw zg3*MO36cg7X5-{21}{%zw4XaA&Rhmm8}9FH#>XFhXrkfz`etlzZ3$=Iid#3AP{ zF*`l$Q`xj3_waH^4WbuPV+RNAn46i2w_ble>J#h)B8dJ)xXEzp$EIc%w{YNB)CSNNz3VVDw*$vqpK-aZiQ zu{PAkMzvS!QypRW4#h-m)J!`tD%J~#^{6`nevnv%Agzd2Z-*oSevB>lOqP_|gRq)} z;d*`C_j657ad*?W8HU^ig9ZuS;L^00RaLRq5*+tyF9A~)JRbGs5ITpnpJa+S)cD

    &_%ZfxxA$DZl{e%-JBnW|L*4OQu;kv# z(?{{)`|rh5^@D~`%&V?*dZs4FO&CY|4|QUexD$MH*Dp+Tm^Pej-`1FD?5iGvrO6rP zzjPxO=Wkf8C3{o$7_D|QR@YYI*^|#=_4zZ82{S^}*T3_NFDZP=$$lM$$SzJ2qTy zZ#*~5Z9IP*M~6+#d1sn?Jk5IEg8MQxA_$HFxZq>8t6mU`q9>o?GgSPV`6=uGWo=CEKAJ9X^2IEx9*YYWrWn41`mneoAx92<ARf^$%7h?*lbU8v2ed#@$asCMRb-Zj;^iY3wvBlp{jI{!3d@|QVOMs4sq&Wvc zkkH~z_qx`qy4J+WI`=Y;3Z^wbD{r#8u`n4o7iWDq0r=z~3kPeSZ@|3RHT=M=W6hYT zX&ulSfa*JN9p*sjXd_xrStk}3W@BMt&UesFsGp!IVXS(PgBz?z`s3d;JEiMG65u}? zpx{5?ISv3$rg*@Q4}Gi7*g5!;8g`Vo+<-yGGmM>-s3u()c*$789Y#4!m{di~U1W!X z^LFes)OVV{VQlg2qFz#CYj>|9e1L=etnDz`6E9=^g2n|dR~u(t9CseTpy^Y3P`f&a zdcqO4r^Zcnd?Lox7PJQkdN^RjgSunZD`;svB#!#rQ_b%j>M-U@GteCJqrJg{U>>Mc5L|93Jd>okwDlLo2>BR&56^g48E>;Bwf)`!=;X%zAKI>fvi- z)HkfRhr%(yfqW07AWYM_*D{YcJ2W#WF$D6L;%YM(QdwS2M(uG%51 z@%h}#wkqp+J&hM1d;iMJzxy};^ndC3pZ?z8Pr6DD2mQ0X;)_X-!r`pU?T1G(!LYN# z3n#l|e8QVpXBXbs2xW_ZeELzgBBivGhk_?j2$R1>+hiEt1S-p8hvJo<`heJ8G`>D@ z!s1sMfsZ15a)lM%0kC5Vce%NYvf@vT3QG}8e%Q-s7<)UUgXR0`w@9(;pJm0Z>(Vuj zUpmR#S?iqyDs5cso~=wUfTWuQ;r(_f+aao5_1m?ug(=g)l%+Hr;Og`;1Yy!v_Hbbe z52xXVQ5p5p-Y+itHBo6((62@ALK|*QZ2JU;{w>oxki!LWMC}u7`oY=VV=>R5E zm=l~XV9^;6;znjL%TPB*`@nEO%$kcVX;oknlPkA3=FJCll-6-uMsWi zFjh)t1ml232;`JaA!WtSmE)xXGMO`3n~9`!C_AUDP_Mu#CF-=bxvh=#L!U@P-JmZ; z{w59OQ+YX!hiU~70GLXsmbeh&hIATj=t+l%@Ots4ebL=a+a3ui;iM0M#v(%>Fg9tU zu91CE2-T!FC*vlzaw^!T%Df5CW5@0ni_C6rUxkDCQvoTLADb%5 z4U$W?K0&37umeZJHH_q-B9YUOoU-MlH|?2aOC+eDQ*1>&ed1PSAsid5+E^`SCT3zx zn}~jGKD6iW)+;N^m%G&^x8=Iwvk2xEDZa_e?s&;9tzFL|ysUm>D^0dg5!L3(w}@1l zBAtwbxt4I+Y_8I}N*g~{g?vVJHd3e$tj9Dmgx|VwB<@r zJ&a@Wfyr+;?Zz)HSqk~cT-owfq)l8P-SLYOmOt`_;eo#mNfgp-{?w~%cMM4sk!2jY zOy;_4*M8mLmPrw($fKKfy7}!FWFJaJ{faVUPm6(9whu4`p8j(g46y9*_0UI?M^e3x#d>nJN zka~P_krFFfZ^03KfJA=~jyb^#!-e!9z;oB8rOt(GAQ8i6o|IDxn^U&u#bKb+%$V{p zoaM(S1pM+I2k?3rPI=dsa3_d63Qss!W1X-2ZvCV%$*$&wnBIqQt84|gd>8#4hUz5=s?|2jR(;IwTlpIEKMPN z2DMYDrQvk2ORCKJdWFBJjbIw=H}`zc%lT0!7N;j;VX78mm6V*JFO^h${L#np+2bcM zJHHeoqj_R{WMm*-yLUIng(E)r^g;aO!w=lo^;*q)0n{Kt@Zyja_tGpbEc&$iPu_n& z9zJ~N!*86j_T}^nOIxCqU~+cWgi!FZiHQjl@K`j7`&4Ckq6dQPtvh#O`PS{2Us{f_ z@tWrRem^L%;w~W$wQ(2d$ivFeVxyx*Ob3Oil|Nh^^BUC=J7YR;u zlZo(FncklB_}1I+#1DS&ucVnqE6VGuQ8yDg0YwK0sDrTJOo z3EZay9?a?Xz5Tsd--K~->2X7Q!1P?4n~s}{GiCrZcDXxh+hgkR1f2gw?a(oE7kqXK z$uCqyPEQ#Q>C>j_XoC1~#l*8_8$z4#eBsHAG4>L`=$ZBi5b4>|jc5!^R4aix^fm5F_x*%VQW9Ox3?63O)%GTny3TgPMS|X z`6Qkyzoo^c_?_SRLHyQtzZ;9ow>2oaXQ;=0`|#0IjT7$UIaNJSZK-;gz@2yDG2hJ3 zO~ul}jPUz0!N!SC!mmDm96$NfKh_@eW9@M|p0h^BCSq9Qh`X0CsNkwkP8-IMa^p^- z@#?t7g!ahV8^L6L_Vkg^h5L|EF zxEVFQkr1H`m=D?iAq~cSLVGPO-(;KZ`GoPpT)4KjYN@wg?M;U`_^AG_s?0aJL+s5r zV|n?8=Pj7k^fCKTh}R|pD{rLlPSh@q=0R-iG}UfRO9LS>0Sv*YN6G|An09+#WBQ@` zy{&Plv8O#Ek_2NKtElLL>0*fr6%sg8qq*N8uup4G%l%LC6uiM`Ik!{`glX=9;@|)p zV$d!#HacRdD%$Kqxo(_Vs2AB4I=h1@b zucn6Kn`#*ek93&cY6E(Kc~)5~70m-mcS!aDU{PU^&V}}XlnqQh)Z=lT0b^=dZHH7J z3>d~biP5&K4M?`NG+%FTZwR)J&D^O^X)if38A!P9754(dq=jj6U{$u-r?Td0zJUqN zJ{-x8#f3RDDPcnTo^hD=8hc38aR21I{Hx<*Y6JG~c@V%10ho^C!|~ef`KW09`QVdB zv9i7scW*AlTd%*OJo-GBG}~>D^FGaEz#xq60kuDjsomC5?Cu?y!C!^ZI9c-?!+Hh` z!HhypTVwy&V~j(ms6<5_Xmt#=yINP359*9*8|V;77oy1rDVeh~!Lhy>4weoa;+lmp zlkVZ;XYus;Mw}?kan+MU3_~NM>L{eFwEk)Z8PmMPooltRiWxkcTia%!BJBcfGRN&V z+wthx^H|^BGZW;^S8jQplxz%2E^<%%%{574&aKlngcAXFP2_XfBBwzr3qE- zNN~_RU~NuGThiJUyr72lviiRcmG#4?CvN#DmxJm*h5DcUd)sm$Agb2UG@f=pu0?4gejwJz-jz z{-+PfW-uS=EAT8NnYOmKyHc`@VXq6|X2vUoM=2jABbbG@C>Yh636m3;W4@wa!N16t zFy&sDH{nT#`36QB0?wAuxR7->KQENPmgVYP+IlX7vW|6FT1BN+xH zFvDT+QO(mZf7ug(4?Sh>{J1}y&PDHI93p3L`i~}CR0jI%>P7GbN;`{Hu7Vo_K zj+yU|pKipq<^|fKhSsMT(04mFP2HyuZsV(%r6u7WkXuOy3{^zt`{}i;Hn+69-q%W_bB+&8$Zji-~U;i_4R7@ zPyXNk&z_$D+u!>K2D>s@C(&&r29bQ|T)9!aE8x0nNZi=ukr1v9bFG{P4twH=9e+X< zY4GDH`XLw%l~z8m`pId`t`6fb+Rnjq&||WZ%5c}h+C_%ET^7}du%!o9r;%mzx9u`= zcO9`8{Y2@zXoB?Bb(vjm?Cv)8CgX*U@wbdUWmHYzJDEWR zWXkTLtMDKlhDRrvku0&LJ{_N~$5?GbZPIU~1!N2LJ>J-8Lx9>Dt2(6J=mSNkjT2Ew z0LHFgBbxL(8)P=O^gl!-Hn!GF?2UgSED&sxp+mj0LWFhURZ%lC^#`LAgsGH5!<&<0 zAT^Yghe&*9I-I2LQ{VS14-h3_61d~kcfu^pIS5e9*&zJrOC}Fs*aR`kE7)Vx!O3qE zr}W3BfqTo6!CRd8Q5`txN!dUkklNyOESp4&^D7>VJI0AmAE|7lPn-BOkotvt10cwa zj*Mx;HWL%tNWwrffm(fT;+@L&;%HV~DX<-~t$<^@+ms>ccf#pWUJjw3(ih`o$O~WW zIC^fzRs=3179aU{y*wEu=RHh@B~{-1;%2|hu>30AinQ~?_QJ)V8AWlNkbcTK`HKKN zILVE0dNZBnTH!$Xk{@9RPHf^jzP`FaWufGWYG6>E?VjRZ!#?n1@9I*>*B^!vVL#&bwRg!gRwaCA?f1oQr(*_S)jFB9RwNv2n3Y zrto$$PP=HCYtb|V7Vs$34PRRFRhqIKybIv)cQLTjUzzcC7`w`!;Ii|$dlfv}AU9Yp zu{`bPz@$wez3qX!jQR-tq3qN$ZNK#X|Ng;0D?@(c<~NM5KPN-Eeu1);fC0p^?ip@m zfIZwSQLXjcL=EAQ2S|H052FnsPirj~yn~bYG(I?k*F}mVTmT$EWn%3G@8q5pv=5vK zKY(!KdtQ{TwGL>G1t&u7HU7k73_w5vc_3BReWdVvgx`RJ0O#NVT$JxSYnic?uhsl0 z4NS>wQ})WIKPtk*AlOnTi1Of9#fWhkP)A2QQYXrRKZklyrG;b{r-UJ98Glkx;z0mJ zHB;yCAR3K^aTLnT>1Xg0Gy)(AHa<2I)yj|wy{HE|>Kw%S+In#J62wCAuQ9dHD>s%b zC9=7_A-7ZEjurRCs=~rlxpnJyRH`+r?}6yZJy{AEj~+dWhtHl_#TIxy2gpWMR|snm zpt)-a;t=iK+H0BtQ5_wR>cqGiU)(iDotwhRIlM#~dCGhuiQtuCGc11cllM(n`PSRt zj(5KEotRr(i2k99`VYwp)Iau_vGRO#-^?o1rysUk(cIs4+oCFcaklRJf2Nc-xE;iy zy%u->oI0N|we^s?l*3%~Q>zVO>nujp79%60o{N2F)!x3s2=`OlefZIb@!=;QnISkf zR&zg79~gQI3wiI()5nkE@Sy4X06QEkYaen5ucLN6Gl6mG=IvNmx)tNKDYXGA%V4x| zVqGvnUd+!0Y_S&_8t8F5ad#}tJBA@}hD!2ht2?pTIJ9I5cPz2DA?)j~F2~KqIZIbT zIE9hC*Xjs<_N|7J_TZi}4S=W?r~E5|9ZtY=AS_R-54gQeY-YcvvO(m_6ZXAU?I>YEF-S1sn}rlZPf`~j`x=g0B<(Z})Q zKl|f&^!PJNW1(s;XF7T_=dHf}l%9ie!2Wo&Iv$hLvuf{AGqJZf*Gwq)Jv3klYD0*g zFioF4dgz0Rn4#fO-@P<9H)koVUCj%tYpd!H;#N(}-Pvgf9**M9EBE5|-Fuo>szw!I zU~R6i#s}~JBpO>APLF*w%@_7v&^ zCoGM$*X$GoRKeNqUTkk|doRU(GTfK5+t~EIbccuB8Q5`aFb_f(fB^=>#nU=v6L3Sk zW=x=J4JnGT%9#C7P0y79zHeG_VYDNmGB%8M4b;3bZ(eGS8xXvtB+Phy(#&D=bES0H_V5EE&2kLvzv@hk(!L_X&!Pl|x*cnw{x~?Z3!znNc($+sX zEEv}MsPdkx{8bGe<}vonZ5Y!U&&>JMg~Ji;X4`FiYk4V_m*$lQs#8-k8Y$AfeN;V0 zOixY5^z@|rhJEy;+6_h}_q&Z%`s2HA-HLj3D1P|f!}##Qst;GZ^VU7zD@eU*7bI!+ z4o=)wtUvXMG1X697hR#5no~bUZ>qzNQpN={TI)(3x*L-Zod+R7+QuRF2cfZCR48){0oG5%J zxLY3e!!uJzjExyL=x7aqiLx|15!03k95yp>m%}FNvuPx)x!3C$30=)MDgy^y=r<&= zIJm%G5RAewuJkE0xCd($YpN=uw&K9ch}JGmf~pV9;?JI}Xg=Qz?lbFEc{Qb~{OxF| zoTyr+zgT0y4LGFC!4B|-h4~rHBcp~t)R{Il7n~oXc6iwC!gPI$yUeL4%Z^0ZST+Z>yh-GgGzDOGbGb)Ia@?58WF+3;?k3Ez!YXgU= z87EWq@wjtKIGbP*b-{h-hw)r^#{5)0e)k7&$D-Ex{noM8yzSUk9|4cFi-un`_K!5b zv|@E**LQzW7St8a%})Bz3$O|^eWS4_d~jED2~uGkRvC=j%kx$x3mgw?4xJXvfD6M| zCT!xitWk!PuAv1=^MW7E*Zsb7XYc-1=H)zIHZL>2ewO*Fv|ct}H~h~sr1h&y?epe( zQGu`Py^;0!eC`Q%_u`zJ+AxPt@!o71Im&$p)7>!)=Cc8%9v#d9Jz4KFna6L zgeaAvn;kLq;r7C>tPhh`5!c^ka2eZ+xP-TF`OPF;Soz6h`Qf_^hoPk801#w2Oi{ed zwlI|0ZGO!iH<(-(n#eD;DekXoa<5k6T<&=RCCm*@Bqg{1Op6`FSSD-ySh3A`&>u_- zO3eUZ66M4L$SYZy0p_*(P@7VaOTb_fG>E~k75M;}v9pZ=i?$_Lo!71E4oKga~g5d;@h6It9}h#-lB zfS7qj{@R#x(ia19prdkFyxR;g%E0^8f zSEA~Za6Xmp59S2DjV}={=aY<)HX@a7InT@Pw26}MZfL&Ca4w?a+Mf_4RhF?x`voI6 zC;E9`O5k|;pKi8vQ?~tcrgYZhx!5UP#j=aa3Syh@E0eC7L>k#B9|%%L%y(&MPvE%t zOiSiwo?!zTLiW%ZLiPIwT#P$?JDl|NxnNDm}x=q zGKJC&LhFe+Pg~}|mDg29imuWIsU0?lOYc846LhLNXl^e;GspPvfe36dtz%1jG zL3rE9uV|0%FR;Z+-;@FOvaI%S96Yim~jWKyDqQR zTh>(42X6$YU=4-tneRm1#7?DaubLfxBzRta7{hr zZN`|&3XW^sSH(ELfEb%ZJEXH<{y>OPLM{h{A<7RvM>$btGXTMy306-s*an2p3=4M| zba_gg2BM!(4Kt6Bhypj^gg1m4`U8UMh~h(BI=dwBGKk3p#6P8}o~5GtaO@EKBlAvlvKl0vBF z;*$6&)DVtVv&|rCt1jT9%E0Y<0FhGpqcRObC-?lK0(?mI;C>!Xq;pv7m3wzBjYNJ{ zZza46$sBrQeQPf^8ZE;TeY?NA>vDqI()QfDvNThV8}pNvAfPWH%%KSa9CdU!RZb0P zQbWBG3=Qs|Ny&%zfzSn!e{^&_9zT5+AAb5EP_u;Qgz?(A@W?aY3q{?=$7}B2 zk%1l)sumY!1OSdealad9v0dDK1i`g)q&8IFz@%MRydl`E2)MN8(RW96L}G?MMHLc~ zE(>$Bf;0A3z#eMMfzedq#~R-}IEkIT12bkI+U~3DsCk;Gj>Rh~!;OV$OMY+?A61}R z+dJx~O^>@%wdJYs1;!$OfIJ{Isy^j@A^QJB^~0aN76m7B}auQs_nKJdMAJB>zs_T+KQt1Tv{QF}S8yoaOR z+Ko>>{xE*{qaVc|{?UK7h(O(;Za?c3ja%c>Az z)=_>W31P&+U~lYf$I6q3@$AWyIB2$%=VC0~ycttdvsSst>3&qVA^jApB4CMlAJNLxWfcD^%3K4eQhm1`Rsuia@*V6hUdcr!Ihp<^*yl8 zyp_Zz_Mv@-gN4N_)$P950M0nzr}<-~5_j+2^PPK0?mU0? z9F@Zwqx;?uBZ)#D?4@9YjZ|xj%6==QpE?KovAdJ^@{u12kJo16?RVad-+Jerc>C>l zV|sSMYUmn*ubsx8nQNP>6Zf}G&(Fm2(hU=;cXswQ-zv|6;aFLD9vf?`IX`QpQs#EM znR_iJN*T|s;6s`>m|G!QUaDNI4b&M}^npdy9pbN5w`mW>oCRZ(`IPwtrZqDlhZHMQgU98lyMAe-hsh$rv7kTd8X7!9@IQjn0~<`3^?W@ zBy5p1;m$P@Ium>`o|(5`8bLsZ`O?^FxSmJ|GG=cq%*Fi7RB&e%`NEXtPA(*tU_`Gs z_Tx}(M|keF?Cl%Y9B>k-$sE%BG+CceI)m!hj+yYxaTn*unxl~lQM(8hIDkx_qf!!v z)Sh4)ddESlsrhiQkmjifW=6bUWe%kck!+#-laqDNDNVu7vgWL}?%z?no@=cWwd1`H9+_tI<{Pi7UQ_C0q>?W*2cafVYqjbDQx)~Q)e6hj5!V! zh|FzB+n{EW!x-%0xogufBv|BO%{oOo^Ae_^`c`Z5=xEJqK4G|xjSR$%xoO|Yi4mM`{)@I+Gs0jzAKI(q&-+xu_anrk4A5M;-KY$ZO3<(}o zQngXu3)<7e{H!^vI_h~GxP_U_;Q??g4mN-bpdy&`_IDd<*Mr#B*yo-(7_1zI;II$s zSdq$RNO4aVYXR*H%>?=zQd8#|qb2jp1!9!zZTgW6GlJ(i`RDw=TBEj8e?#x#0JaZ0 zpCh405-_PyA3fxGojIO(^egj?^eKIt=Bf1Q4-S5CZN@S4y6VAwU%*5!_@Vj$rYBOFz#5D;#u;Tw zqeN*Ik2df&>R-5Pt_Bx_-U-8)wfxO{%kj=@H)3?)GJf=ky7k}11aez2VA$|^^sPH7G+pHcB4QUu1oyr8r+FX43G?eVw1gy!%vZf2_p`q zr}S`wd|XdisR`gn2fNEeQ1VHqbSuK9h46(bzO$0WtMI%|IO>{fVMrbW;$wAAlvy4{ zw&~&d0|M-)a7fb0Hj;Ls~SoFb@bBJk#P0;{pZ=ixit4 z79^{I(;rAJ6QUUgt~Z;^UN2N7L4&)FV0bY}mt~7IptcO*U6{T$v30p?38cqwR|}RnG{aP@rM~Ws^`5l8H)1E;xnp zm1611;Nv9H*wlpe^|LX^jFK=lsJ;UU072nomQOM(-6Ss*Md63C$if)oqHqihGTNHU zI!Vh6AOb2Pb5IE+UAz1$&qVOVVQ&aS-B8Yx9B zwyk)SJ|DUv{Z6dq2)5i{?r_+=f6v~YE}48`Vyw@vZNOfqa)6Q^N& z>3;R)ayyu8=`CyK=QWMbbo6f-{KfUQh*-9tJTmY6Ekp8^WxnoN;* z5mSZiGPv|p#Qa=Zn2gJJhPQ8-wm!0)GF05dyYS;%R>yLHbR%v7T18^^ki8oyf3F&{ zcw-U{u3XaAEn!(0KE5crO?vwGx}QHXlAXKlS0;GPIG?LD$`CGc5f691v*k;p)<|zf zPl5=aWi{UqZ{ezIr3$F9R4{Q6Cl3C(81Zs z{3Z-^hq_E@Eo+kVLlQE<-54XhjX&z~og>;{x3oEj{MjqK1o%YyhQl$(N2rB?$O2&k zLg$IrZ^jw~P9z1uH8LO8VhC3-gJ61)@0r$Ya8Bk?h!+t2j4R4LamQpTIjnG>l1NM* z7>_NLh|RrK@yMTpE+ui*_tz>vq!tJX{(!Vu1qmkMViTy2?(ef?69h)?Vc_6bo@jf{s=FD5CyXgX$U01Fc7~WxRN166(sLb1!er|{3JT8)JA?A(&>46a1XJ1rsrw<-XMhvj;6!Sh-d@$0Oqma83zY+j z2h=c;@2D^H4-;2m7SIp06)M7LN5X@5a>5<8+8}nQ@1eaofe*om6Z!|OmZexAz{0>o zE!D`_m>Hp{?H(B&6#jE=g3aNfU_p44z#^V+Y)7+wtg?VZo?5bmc7PxTlg2742YO;^ zd?;q?qcJ+1Ogh>Ccwydx=>`)3)nX9mQNzaFIzRsLPvWBo52HtYJ-cutZrr{n{CYBW z_8|Z^!7|+k&&c7^+m<_VwzpCFx+sRVrgqpPp9zgi9))&Oy_v@qE|GP(^z@!Nb6?38vfI z>XUu7hsMa{#7NX@d50Ba0|Fd-BGfN&chzOzu=1;#xO%R3=5#kq&0%m|b^EE{9ykHN z^4g((W{9Ac6p2ijY^6pBU>eCoqy$=fjo9B=GXu6hIT80>eLbqRY58lsoOa^0({kH* z%nFaMsNXT{1-RozMKD1YM#>NW?9Z%9Yi@eR?8N%^wqR$-cT(Md z^{yqMY7@#!FjV2r=wa=5m4{}YxHvvgnRczB>qzhi0S^^%6BBjA4a_Rk%ppO@0Xyy* z;{LJe*+sn>OOt}>5w{oj5+T7-tE99ga}2P+-B6p``&K(3m8k;we;B?9r!#%6DYA z5@VxP)qT{=Y4)VyrW7)8N12?2gX_sS-1AQ{tgf*$K{%BomcaS2}dg^uLERLDGG@i(l@cvdaF~5RS zXfTB@WlYoesL`C(+K$Ri6+TcyxvoBi`DK-!3Z)|YKBlVHgW-OaMSaIrBaHKHwdJg{DK-mvwbYbLmWd+y^Yy1$V&QomcM0!orgJ?;wW9#?_86uPScSLCx(*Zw2t7 zHIVtB2jz7tKu7I)to5AvkFg1E(5JG1qkwyCZ8hRRb0FglnB~4mq=P($)UsA(%E1Dq z$=cuP99vrVP~~oE-a8Nu<9ndg20W~D?t2VlTYs!&#^Ka$$#x1?YVA zFAS|be35iO#(vWDz)K5Ua8Pr;nNUdhK^ugILmB#f0K7In;r^q6>1P;}NC6^I2`!Xd zSQF}#bu+t7w-LlN}j-AITp;2 zw*i8vKXguYh{CA)!V`z$&AUtSgLm%5&ACadIR5C<&ouw+$GzK&@%Ec{G#?9xrhWPc zqtQBzC(ku!2){nN7>sS<1Kj7vdPhrv3xIcWSLpoAWX!6bM;dnzpRUD|XRDU-1s>|c z8*a?c#@tMfW0>)%;^hDqQ;}N5rM_;cNm-kc!TCkTe)M(mojCUwhflvRH>S(~g61pJ z{tExEV@T^)m)aK@)`u@PKdXIzK9l3?i_9;Qwi#dlkAL`&iX>?mY?(;9dHR+q66fC# zp01dT!5~Q+-kw;l`TAc2ogg3qkjOx&7%U|2`CV{-kbL2%8tdO|(pc zynSK*wRB!gr5mwmXGKw(r?Q+e#|~=Q8y${*Ayr6xU1-8L<4couqNK^7NJKRU(XciZ zELuKoq0J(vepqnKxX>hySNAWe6(O*vTK#!fYO42LKAbE z&1&fMpv#@jF_R)~$eYuGxk#b@BN<=lb$4l1MhF~cz-aOHhF*&;8-G-AKtO1=xLkWZ z9zS`i3A?TS`SQu(7cp*o*X3)ZTXa*`@Ljr<{8dnJI3@BUFYjA}Y<2h;3862!glgdg400tiPkn zxEZkUbIlQGcD%xaSoy^}O=-(8m@-tE+*NFTof%~;f|ubicE-CKBhx7gl7V@Z5lV;B zvuNMal)h=Za>qFBqCIRJm$&|DM~ApFMH4%f(mmbstBmegBzq}X?v^Lr(kN|xcH6^G z=2g06Q0iXz>4lB?nKE!{(rW^a*JIh5cH$aGusdO|>XYlAEcz*1InyRDxs?QS&@!S;i{L{2EV(``MzdK z=QM@q^*DO6Uf7Ge=*dXfHZy$^QL1{=cRqcmw|$GWF-2+oeZ?Fj zkIVR9e{;vzFJ-=LGx6&-U&Z*MubCUVoo*W?3Bff7Ucy|4+(H^9NZv0kS66Y zZlXV{n=wvvDL0sLNT+K}S4pWqcoE^jDJZ-T;OKGNC_@M*dD2_B@E~|92eSGsmBd{s z6BAXdK^s+BQ2)jqD0w%K$|*b;h7T$S8BNu(N=$LT)!2xMa4=$cPK8gkP(`IWquOXh zxJ6@kC-xfq(Wkn>WFS8OFndsK$eCfFi46c_kS=eVP`6^>6m!Ew}gv_9=|a(EC!{oEllXr>+yD#f{1s9$AO zBPss5nO>+4M4EzmW?%^EFAmn7S*ig-8Vrb2m5USn+#L&1YHWPmgyA8j&z`~urjCxi zJe&(wAn@(%w)EL6{OmHUrb}%yR!Qaq2jE~-qH#bw5#e8{ZVWYDw{I?)G0CB=lw|9u z{rcVhz{d9WPW7L2 z$6uZw$IRqdEHBQ)%^M3bt~#NvZ&&$Q)!}qCMzo!23Ey7dSdU|+OPf*8b_W7y#O&-` z)T*Oa5l1~zI*vPdvRz^J?KgJ3UxJwj@gHIq_b!c$O-AeRJk~aLqJ5yY5u78PRu}${ zI!z9e0f(rigHTr)trqI>hLyHpUt{W2<=EcaRXV^yj$_6ROkk@OgLv#ckDx+jr|(dQ zbfL1g_jfG0bkN@OeOhmR>m5sU`L>YGK~z+C)Ns+Es47Pik^K#OIN$+EuESO{YBlX! z#wRSn!CXKgIGK<17x$YT3zy$%aKF~7r5~1WEV&<91Bb_I>NDUo?;yU=m^wW^RKA0; zI6rTxMD|3~3pI1vki=$VFW&#@`(`RaxE>SiQqNBxK2%$73VugoTK)3Mox3qnpN@eM z?vNX?RLX?fmhkL}*l()HfO?K|HV|#) z%RMg~2&Jvt8pn?wKaP(+{?r6fR3UOlANOi82XaRmu-Ma&6q5GTvct^gPQIa`KEdXW z%DWXERPAvOm>Qlj#N5xE%6tu6uwOKRTHo^0Tl>As+*4tIA2YL*r&WD2(P9Y9BNyNU zW&^Ya?!~L9P8>jhs9Z{1!9=<288EGYbw;y*=8I1BLW|IT6XqIHK)@_z(y(9~sheJ zd@w?DBIRA0os5xwjUUrx&dgj!4gaqCbmjS``n}`zRnc?*uXbX6Olg{A*7zWY8U*!% zlNxud1y$est=+mJGERpEE0)A&4!Ct=DsC)Jna%)nZGCgwl1i-Whnn9lS=)CROEU_$ zH0QOVse0`0Grw_#0f$!A0m>XnEZ__S?EwZV-$)p5H5#$M2NOEia_AEWXmL?Hng*nB z^egZUliPG6tyf;JRZnYWVeL|%Foz&<$-Ds!n)t8z!m8@z#^Dc`fH0NW_tTcpIZ*$4 zej@nR9D)QhI7W&2&@Oe&1rw8+4^$`OfI6T?a7t@0QhCq_I1r08Gz<}F7T^S^B4&&W zNPPf<@N?6XrX|2UI#;>4>x_PKnN|1NII3GmJ@-C(^w8~r+TE$?88hXOOhsiUa{%+7 zAm9Bx*ng3Xuf74r3Bi@xLhBd@RKNwOGmN%<&G{Q!ThZ7;I*2u8SaZyT;e#?GSw}z6 zuEtG}Zc}-|6TIJ4yRtqockIC+VJ>9dP=A;vBv`VFP_=>A4t?|HATo2ubsQ8N3uZSA ze!_tZu(mVLkQLu2w2Rs=8Asr4^bB}i(x38fK2I$I6b?LT6%vfF-mz}`0JdNUSb$c= z8jR#4hrm?=GeQ~n92}xwxV8c*Ear97OqDQdBRRZJn?he?U2SQ8FL6y}>Uqp6vNd*~ zg;5~t#QZ|PmQrBUxmRlq ztFfxS8C09?wT@$L>mUx#gpZxT4Cfv><_#Fy%3tk5yL0df{BLGvT5Z!8E2|svd~H+V zj!e5nLjZMz;XMN*{#0#!F(0t>#O2l zH(#08*GTJSL)>3H_RnLk#?Q+p%l*sb&bTXk_C@oHq+Kw+{_zVbX4~eZaAg=Qy!es3 zCN~u&vy+>>{EO?ADeXjqIIC!Ud7?_WS#zbCNUoZ-aJ3g6Ox|JsL zO<#hY3a>n+$l84N3JK{Q7BV1YEma+Id8Rg0&MWUi;9-G5lpYmsEZ(+jbAvP$n|c;9 z{`!Szu{pM$_hNB7(}Zt&nkM@bA!ta_uw6%F9W@_5xut?71C7(8xglc#@hJ!uo<$7u zd`kQvx|~c33=32eAbM4P)D37s)}lg02^69f@@$fVB!J{Mp%O{5~ zGiB3W?}u#P7fl!LzQV95(=*+Lp1uK&OAHXB47@3zot3T^Ds?)<77%6H*e8f(A0E%m z0E7phpfgelLMY@xi}xrZ_1bK*z@xk0aG|^bITmyb>J>Pp$LTR|B-D3Q(1acOOm83) zM1y(=W2^H0sa+r`M8we`M9h(EXCpQVG1Q2Yi93W+H0Lp@6SNtv)?<2VMw@N*OON1| zNkyU**!R zgsf#-;ZQi~jRzkY&Ut5}rBepV?;{4WdwU<_%w=V>-7Mb ztM4pzk&diBcJzVfk}?i}oOL!DzWM zMC6rWY}G>u`mTg6TryVad;OihWw_GKdFn5Rl75tj)6h?uSH>(174+E9AKpb9<#;K| zZ<~|wJ3}zL$fX!Fm@<^Zx#4(}4%4k8@vVOlalVT%W}Xonn8t%-9U6c6`2$BH5hZ(+ zwkq2hgIoEFn{7p3cuY92OeW)ywroh;@Wzb*enIR}+QiqN#{f|*!ImQ|9STCb3?;$M z8*95<#y|ays>5H({5<%=H*eI#9#FEq+?#U736N&(^%_#bHIRclfrxG|jT_-0mM+&@ zn5FO$;U&T!k;Gx$K0fAdl8y;!?e>w0T;+i)m|ZZ3kp8k%5_o`c2A`7EpAXrv{<>_y zVm{!AFu%ZOC_@sjAhN>bO1u%gFqvpd3w#1xQ~n$h0`Kt2V~qo!?4@GhB4xd(r|NG9 z`I)Gux*+KSv2=23A|`58;UfdqGGNtt%8%fd%!2r;KL`pCNl2>#v!P#gQnFm^KUo{K zswC8K4XJ2@%CoV(9e?_#KaB0ot+;vTcGRaPjXQCw8I1~~BRs<<*3#D8oq}XmpZrie z)zfqC`&|x>AacN5>-Wj?UE#vqlQJ<7(qCknwyWlp^?~E-}+$Gh5A!C_=WOAa*L)s*M8zy`5wS5Yag0mrxq}i z42D;wGGcrVJPQp0sH*}tDNA#|8GDUg^_%e6!C@1hP-o3v0acU00K__oS-=2<9Ww`2 z*6FG7xV1E62{4!;>(5t(t94>_cE*e$2z%=r+wtJxvv|I_7YD-QC~rTwuhOIpNDNRf zaBzrn+(QI05<7TsOMTusIuP8PTK(P4<)yg$%58_=+28k^yEs*i#n~yrgZfr=+1_p# zzaG)Ptkv4{US@h~HU@_)Ccps?sIojhY`e`+tF^nktG+vpxmoV<5^j5n8ojpfD4JWm z6&F1tv9;H+R0(STVA7(7t1>KDfkCKoY34_Z`>`&}9D%sUnBXuQ`EKv-1sC5ZJ`V81 z!0EAiJk&LUKcgP7TC3;y()UqoU;RY=&jf#})7W^7)lk=nYAEeh&QH|-W3jX_r@V?q zQ|Uu+-D@=B;lqdV$)}&j*vLq{`Q{t3w0zqPCUvF9Giw+GY}Bej^lR>I$64nv)rQq; zUa63R>le*C+ERgkHUw553=#dtx>jKh^GMSttX0!~xIqBic7|m>^ZW`5>a& znXT|NwN5d&C1b27>M-I3$HSFTmyIZ|sF*9fF8VD2(+a*rMB)$&|D>SLM!c-%6!SUMutkq86(@Zn#@=PoB;5vf)B z(lDwAi74*if`JHgDCsBq6C6`t)29Tdj0-RW?xy6fMHp*+y=n)|p~eSBgp0_oE^z%= zKh@~2n+mM5L8BQ^ol%v`+RdRKaHwROZfPDzqRdQFjbjBf9H=1fQ!{Ij+|;wRy`?p2 z$4o`a0b_k;YC5VgXI1|L&9yLnX(Jo;8Ep#l7!|o3@<37xo?1s`X(}udP{0B-7w9?3 zSj@xe)Pp|E_J%GbJfTYi1IL2Vh)PA_1cKG1yFizL@r3%oL)#N~?R6PRk8w~1&s#DIAE(} z_5nN4!hi?UPS~+`chm ziO=A=b{LeXD;}?o zD9r`ecVlZ;<5)P*VIDeyZV0YAF)kcU>xm%8>q$ai8n-=dTzq3Z?_#LRf*?SXu0>24hTl~lS@4YOd~h#* zG3m|^`Rhv`PD|f}&roH!BD7vAsuu~nI1lpjul=b4RvVnkZ%qQ`;>v-r)Bwq)Oi9M} z!m6ixDw{7m@XExB80pRzh3eXQQx92bhjg{c9F!)(9gRS;^Ie4K8mwhn#JT2|-?n5J z5-3bM*)h{*?y$A^z6x5zRcH!S#>tR2*wQ5Pxgq?yYE2)ueaP$4T20 zPt=I{YZdUq!$Qo23=#m73WS)68_6vC1qKtF4~PX!_#jl21tg4x#fu{8C>+S7W^|=} zsf{2AB^Q+nX)NNEOdS{poYLYk0*gD3u+MTrr927W`cpX|cKEce9yaGDoES;T1&9fo z37t!RpFVvSPoF&XMwyoTDs$DQKcC5dO2!;;`>JzFUtBOZE(C3sB@q13b9tt^z zfeT{7<^%+dy9jce7iAZMO!-S>7g)sZ6LCU<3|~r@4VG0LVpll&fKxdjPqZKEfA9kt zI@X2-wTBbh7*9{4W1b6x+0-IM=Pq?VZeSk&t2`dpGAduTm0TI``r{wp1dU>x`v(^% zP=v`4ZfUG;PFWmG@k%Sso=dP?H&^q9D(bM#s3=qUi78&`P$q0sreUk&GO=Y4?06K; zX-(s>MHrj(&9))DOJ(B_MR@A<|7Y({x+G1q^gQsIxy^&B&1OD(gnLBfTsc$$ec0Rn z1-uxmSikT9nzA0;54%ii<$sg&;71!LFAA*073h zJfr5gxh90iE{7a@Ycyh%$n=*)U3u0JLuOFG5>$34n~4tmOsr*Y$}JDdjHym<8J9wS zj8E8IGrko!sedM3vvJzCulQhB67SlkJ(^b=>Q18!+eljSxD^mh61bGb(1fB66XOML!H%-=M{SK{dJzp>D= zl$Ewmo5p77w%;s}8S})S6{6q~LJV*w`C`_>BRssYkcYdjn834Z<`4nM>6Hb`jH&RF zjDsjV*dfgw7zjtWiop7e2!6XMgy!SXy3ESx_QQQAqJkBQZIZLMM131Yqn;VyBFEK3$&0xpJC@8!G1)->TT$FfE zK6pPKJiMneB2+sTWb>FPcH@xeVf)DSoe>YuQHUG?$nkgJAxBNo#_XJ7M+&upKjm&L zb}C$*o%rskk?Zq#@%(eO`)PdtM?a2@+waB2b>9E8xV&t^p?PV+h%^vRD!JgkDt1Mw zYpQ&?01Sbzc_85?N;Y^}=7sbxIPJ^Rew_Dv!u8j}351*pWrUF3PTNYlW@A1^C#K`{ zax})Ko5FWxO&upjVs1)6S9%B!ZWK$(1GWCU-%+ew{l!!QV^x?GaYZ-x8jjX#V#+UcGuHdp{N$bMc?Nj!P{p5St}z3+Y$E2|sEO@x%-*6!YJeEjh*Vs~fHbej8Q4uzBSeeUIY|HBX62S-$I z1kEU>*yTd|(H~BQyRGhNw0fes!f|$mpfo^v-EJLqv7||n=>?B>ahW>m5e-V20Ch#+Tjo^i?_dhb9(L{#9>Z?06i{nkiVQ(+&`nIX zWquHvZ_<(}V85NgBxp{OQ>GDJLRIXSU&74kYq=1<@wS!nD z;XIv(EFJ?y69g}IZ=nc7VZFSvYy~&FnmBrKZ+ADgcXnKk@iE4zJc5$EHKN3$2lwK8 z-+7|>;f&}m3nE_!#|)kv_hYfyRDWHGYuZX6Iyt+J&e2I6bh^e96mclnW;Ir@Q1wE6 zu`x65qZ`>3#SwMW`d(dIQC&u2b8|QL_B-kexoZo7_x4^Z+TEVpjXn=vklxzrlE?10 z`c+3bg@T;jkqwPS?9im$jzueIOO!Z|9^O$O+KA;QM^K7JtDm;JC-Ho%6|Z($aVQ+) zek~ODPafTk`*$}~zP|dP`fj@y9E-~_d?=n#a6q4ZqL1J~J97sZyOqw*Sv;M)ZNXpU zJSgY9>r3Cv`w36GFfP)+7~g>pJGr2vjNOa@Ii9OU)Uc$BeB$bwz9IjS7m69% zh|fZC>I1ES{?UVGg;O)rV^(@B%+GpULwU})%$UshMBQ0*!qL#|)*98=G&|Q2&at!l zGG1-(sty;ixX@5sjRVRH#TR+C+nw0n-m%ilW7o;C#}&pZ6g`Z`+|7vMi?NJ2Ea*Xz zn+m7wd+vX#-<^)!!Yp@qs+^|OG?@y>TQ9dJmSP6Bx7?h!+-_X?%rF1GriR4~+rQKd1#!y5 z-`^zukomgs9%F{g+u^@WZr`?Szc1#Sl>49j<9|3Z@{j%>{~+O2!t-L9m&1OU@IkEy z{z<&k&JVwtK+V&1M32Ljv|XS=V4Oy6BwkPuya->P@nSO(^miKQM0?E9Y*09OCB)D;)c5xe;^oViVgfhCh%wmyZcVliOcg7SG&K~Uk}04;(v%{) zi7!n~3fxCYFaR2vKQPhE)*UK!U2r8GQo0tp3c zj&i7qFF?ZC@T9@9FKod_0mxAvl#k1Csi*Om`YR8Pg8-L1JuYSj|7jcj2yb8#DL!yW zJl8i&)K#`CX;2O(S*-S=ysQu;VXso>=o&HY?DSe+(gb;KL49B{@@_A;o?0{o+%&Iy zy3zx;vwm)3zlq|44;vLWX-1kF{7sXtU*(riNxN86P@idM-kC}*0`RahfDpxP5Em=< zff@3^rcaW$-S7Nx6e9BJy6J6u4dIq4ZG^K+WcN(8xbstdNYkJC^^O^NI==F$;rvTL zC!lykcGtrVq))wT@h}6wfg8U#=C8j_nU2#r5-X$KdUAmSu$KHqa&sT zzjVm>37a&7IJP;G(k(dw4_t@S&X?16tdfw+F|f-*9J$rLn4X!l!6JaAFdWyLAh;0+ zMGoNxWhXkOeDY(MWfF=@0$Y<^c)Xw4wK zVsgx>DG%9X0Up`DZyLMlC#$IX@-4gJkU?w+m++~syx&f(nu2sTPS}rYR^t12C<%Q1 zE*{Vz_yNjM;cGu;-SV?r35)ThPY(HqGm&}g%hr+jlmG9(z~!&R{GHz??I4g^Z@rU>KU3*lWxf?e*p8v+3x!vj4GP7ndt>S9xHy(PZr zSbVX<$-RBBXMsI5?}tD7Q9OL~NOcmhMo>YB*Haxi#!88cXA_U;4xGE@j?b^-O!YVu ztl;f)@f3lzIsCGVA+aRo=%_qmFgJb)+N94uJ7vdLBqd7kl@7=#0 z-PS>z^bdnOZ&3X7PsIZ&&h2~mV|um`hyAm7xwRLcKYI}zy$IY8TCuBuc>pwpdt7K6 zfWW^?&ohoH;HfOk95-am*_c3vn9i_GTB z-AbmCN}u=$%;*=Ke1X6ZerZYNdHC?IkG~RU>zxb77MOBM!kFSvrk=`pE|^Zno%Q9o zv$otQg5bJZ9b;v&+BJ`k$4zBF?!{4OKPH8O z>&puOj-qw?#N z9g@?rw76vY^{bCRj;*b&SiimDom#*E<=WcXTKwSqKZu|F^e1Zn*P6p_$7i2?rnVbX znj8&z=%XG{wt&YdO&&aa6u0l(ce~J^kGe+|hA*&FbaFbnC$IHfh>j**V@|`a($-$f zeUB4CIDG@!3Qn@4vM)HJ6homqqJHKDs(NaFt@Bt;(C{2kc5oH?2eaXMk^A{;@gIa$ ze^(%$0S(ua^gj7Sh#J4V^T|=kG`=h}^q3$=(lsxuG@xZ93@OAU|3+O%J5$8ue3W@- zjgRt<5c)I2rgUU-Y)Bu{LSRlDXajwUc{j>$=mK|90S}6gpOD1;oc;r>=?!r=)6zagB_o4jZSj$5;mN*|OTTF&AFXoBxk zGJQwZkP9U$uAullQD23o!Ea!gdqAgYcjzEv2DnDMk~fM8#%mUAlO}nYPY@2^&UnM( z-g(iJY4s&99Jewjl^66&j^^|Ip9%{NweqN$*Gv!y9-Lj_;fIvUUleC<7;Wycl?wxFOF!`}t4&@YbPr|@&!mA;( zy1lv-cQr=9GokQ$v^pJ+?=J0 zSjwyV@lG78=571U*PDK6hQsn?8LFv$`d!BE@Ai79`LcAXdD}n7t{d}p@xRIp!}4#E z$vS^^+5gEu{$mth|9L`7VJ$GJA2tP$O3bVP&UK|PLJvNj5zM{bbR>89bVtaMDXPPj zcm1}HUXI5A>achb_9k4~2%oVs6z=k|L&hbZWXQ-qdI^ zq)2J1u{UKMxXDF{y)NbFJK@21mM`52mSLO*@qrWm>0K-;pTj6D^>N^mR*9J@7<{_pRbHtBJ=IeFFSC# z5Kdf*NxBllXywCfz~C|n!Qe8fg|Se| zIWTE(yVRgcSs8RGAD6;1$ig_()x=B=Uc7i2uU@{=Ag8owi{H7)c5{ca}R z&zq(+(>r{MA%I~bi{9C`iQ{IwQ6yCJERAKemc92Z2#$J@dG3>S>ADR><5a!5}fm8}H0rPGtwiz$@XK!ZT^@Xu@iSR_RdRGcnPWmv7R7!G_6T zwJnCD7EqYMl(AZlx}s#`7#Z>f=QuuyJ~}-y9m~xXO;p5qh#?#`@2x=Uyeg^wuxB5o zKid=<19Qx=IE1eQDZhhYj-7NPUF8Bi_;PsSr@iE0H~vQzCG$&|TbY4fuNxXl*b+x@ zAZ^3eiDvmJJ83&9nVKJQoCG$d;V^{7Uw<&4j#HC&IKKVkcgE+J_-RV6HddYZBV9A< zO?;P)Pkm=K5>{Ef^!JO;l1_QqZ`iZe(0Ll>_Rv$m36}Nr?;vj(2PLfQnhb9Cv{>{4>Sv@{c z9=%B|@$&8P`F0UqDOJ*T`S3|R+0_z!Bi61=9BwZ)_>2A7HnH|`mpx1ml(%2S{f{gB-N&__nn zn{c=T0B=B$zt{Y>vmV+ny_CD$X-lA%&LoJX1oFcxzj@WN)wr%h309+LwDfmdR!74L zYewLg^7&1{NRuGx9sm6A6klIzD((J#HO3D;Hw~C=n>GYD;v?qgf(!pW_KDx(PN+GJ zcO3Y_G15Ex``&SMdt)`m#1CAGm*{K4k1%3&ZC&HzRJ2ddW5078-TtX}AF-+#LEUTh zclcmRD#5QJ=+;JqnxTK4pg%WBu_(W(kdu7b@ zk#P{*L4^>DvaoA{qYy;}%qv?tqcZqHbkV!f>njTq)>oU+oSBIiPoKueAOCqQEiK0T zPd-q7;;F^UaepMv5A-k2SB7xHK6xL7LlL6iky z+Qj&1G-f7aVRq6-#o^B``rW-f^U(9tvu=;Wqi(#~-cmUVpDtMVh$-hUSgAaUXn_&R z6z%~&Xdn8X2o!(_aS)cVn~P(!ScK%AMCb64D!1q&yKy=ll!fi^(T6CHR38LP;2pdz ztIwxU(oIf!97M?gUqZTh#2pllw&Q4`N%M5<67Z=H;^|O?FhB6(I6r-_#?E6DRR!iD zY7^qJnjb|S0z~)*;Lk1>j#NWPMR}&hPjeau_u>F|63KZI^O0-g1hC-#I%xcq`Um%n zHRstK2A`<%3m0aU7fOUP@x>@RXt$Xu;ls*e+`G+UwMn@lXr?{EQN>fm~ zd+5_TF3%MALVUIOZSKFCRQr+7_RD8+*g3F3`_X&v`R=d>58sak3&Rvf{4qlDgBGj! zPpx!eUcf4KRls~YCp4T`>9ZTHy)ExP_~7xAc=+%^aBnaIe&W4+_0sp2&ChaI)Lpj+ z<>byE=3w1!+d^K1ZDZq8@%Y1!Vy?NQzB-~X=W*1}c4Cg=dy0g&2o+iSwzso`Bv5q{ zY}F^4i{P4It2W{2C4~0$W#%HQt83n!&=wxVwwp@3nlK80nfW$sIvBwDRu5C&HQV9bjj|hmF<6c>MTbeDC|; z^R9>Xq1r*P)Feb{?E84gebL{8g99(@!Mm zcoYYnzW5T&$0EFC6-Tx~AH5RH>R5oWuw4%ZcgjF`=OlO1P9qol$yb@=To)lfJ1hKw%8HMsL-EP| z)HQ7A&Ydfkq3t}6Aw@B!QkjIaY+>cMWVMbTaIq+C8~Q26G>L-al613!?o zf&N+3$+SGsdZ7WzB(KXhTF^RZmOPawihuQ2`GFU7clxc5oYmN^0QLi)a-ojOBRG;T?F(#C^h3Yl z1%P4FBGDS+P)C$}Dig{?=z{0az)4||sj|zI#bk1}pCLqZD}9FpiYhB~3EqQU#_vCT z=-rbSC&HVE*C{`9`tO!3BUU8%^_zrBwITCwzPIb7BS37%tPpU0d<>2^n z7OAiUa7+Bei!FGHW5HGYrf3c01&Zq96BhI+J+;fksPI8!FZ6(NRRf$cNk@Ov*uVOT z4w?3rPkjyS7~{lHIzwJIZ}{2%c8GVILAu{8xXo~0?=o-ugLlK`>*9Zvc{}EBlh$9Q z$#Q;mS*`f`FaJSNd|^O*#YshrI-Jnojx`-ZDq*KRWUl}p1S1jSmfj{7_~;o(G5l}q zZyLu^6#bUqj>k)XUYV*mBt&ZeqBA6FY8h~@`tz6 zF5&ctQ}%sB%5O5q&28yCYkE%6ZbYu(^qd^Pd2P>Ia838Ub7$8(&u;-G)OEE&+-NhuXUUJFg zlvR%?HyD)iQb>KPatz+AZeT#>2nQxIOmGOxfXAv2uOci14I@5w8`YouA?lQ!@|oG7 zekunmDLJ2*$tr^t6G9o;7MBpzZlPi z;iy-g&5Mzq)SDHnta#;kKZG=_h@8;Gn}PT2f(ZzWpco#(kincm8n`h51eR_$JpwIA zpn*6Cf0$aD!Ayn)hrkPF<@!2d z07HyI4xFe*f_TEDs2sOM8JHOOI0Kc%tD#C6QHTK}Ph2%Y$bKQFTW&m)W0SEkx1>qR zTFgz&n(yNXMA8Nxw$P9=bZbn-7r#h^VEW3PIq8|dC4#=N;YJAljo;~DbE7zrqcY0) zNiQ6%{^Y++O|{0vVm}oy-QFw>?xtEGp$+J58lErGt{wyD zAzPXfhF`x3oNoMD0r5r@m&!2+X2q_9mw<1CttRVe7#ABwb5P%`0NH{Awh z!|0XxP(AJ7Fx11e(ayYUoS}S%j8nxK3&!DWNthT0`JIMu9(|XWjng1b{rGZIeTSo` zz0^q`=79!27-~}O>TKtKhzv+nOI{x{;{5!?hml@;d@2T;)`?hgQ z;?64HDGSz`%{d?Oa{>=&;f}^Rjg{jXv)RRSuJIo}j#cmDjM=ZxV`pA}r0{=v zhery8;JXpHuu#UK6bK|IumKl(7<5XH22&f(LsozMgN@V{v{i<~jEKN<5GFAj-uKdUp3Cm_m4g0GtI; zhrM3hQvDG`B2b%~TM%rXKn;_&v z@Wy-tJ|CWw)%)D1WZ|J=aSR?uIwCMc$cOMS@1V*BZmj0#?i^r@0EU(SBOFzwa(8=O z^RfuPS)GqyiF6SU>%6B& zuu&gcU!IS3;n|eR#hq&>n!B8wtM6T2$FX>L6pVZOZQ?yB8Rqt$Bp=sYiqgAW$J%sAz_ zRllpedYh|po_b-kXV>d+}dpISyU&M)Ud2esm_ewu|_FQ@Fie4-! z-Pt%e=)}`!FI1kM<{_zkc>KYW_}Nc>8t*-NKPKmwMIWKRnonttzP{2_KVc_qH>PIh z)FzXrRhQ={dQRhDe_wU%1V?pkZEeQKAAhVl;%q$m&JSa8^{$W0I}+?r?4p1Mw_2UH z=f>Q{M<3C|PIG3_ThU~8OmNQ}Lit>1Wr}M$3yo!N#KOxeD5r-*i!tmRLct1sMK(ZN zqD+R4GS{-=LFo|3Y3ZpnwhBvgyhPaUPg!xVkBs8e&b7ZHJViNyP@M7-y&m6(f9{M) z#T|BPb7SD6ghVpro1Bdvxn+6ssr6=#%h+cHpu9NogGIe5)YkYS8b7W%A7zJYVkgSI z`?ur4ec`#>UcPu4+dF$!P#hnr{l~83CqMdb{LxSUK=VR&6*BIOMfd15p1s(O9pNT- z@<8K>1I=T%&;5IA-u1;!UDFTKe2zk6VFoAUpnT6cD>VAWPCNG7C^U1Y)}?T6Vrp9S zY|dezz3e`^b7#$pnRC$-Xg<3=P<}#xx&LcM_=4iA>#{)OL~~Xb@`>We4Q zJ=pVD8|vd%Ba@=#x0H^?d(jw> zrZdsJ3%f(dQ<0iuJG)__Rk`zo#kh>+8e@@-2rjf8f6!pYpHxJEhoSoCH!!j6L*c<+ zAA_m1a3gGjHx!PtfRErF_~Hd1C_|eKk0%%~jPm-J zXXFpcCy$ODF|XyF&q|X8$0^fdQ43>T?kGg5iu@rJHllZ3;g;GjWjvyp3TXHiIFLRH zL;4~+u;@F+efd#VFCvz4zjQg$jzNBcvTa4Ql{#A~sX9|e7MOVP5NR-GB8SnN{>59# zyH8Q>%Fl7d1iXv;8Ztk2q>110u5`hKwz9HIcJLJbjK}3s6w;=C7=Gzq`A}ET%NBv(UtgzJ(h-@u=+XCCwf2V(1y6C zu^<0Kj&G;`wxQpDU6^50^RV5SrTxpyw@Le5=C_SMY~F_D@2kl=e|1@{`1-H@!9Rcm z=o6AxL=5^tFyZLe#m&~Vk+}Vw34!gb4w7%aE1)0(IK!?~?=-mcRdTIq zm&RTWqL9T|Ma(paYX{si-7I2px3NQ72X?(lY*2wW4fU<1t?+OZ-ug}7w3D8JU;Hyx zrc3fwafTW8AN*z@f2C3SB|Ru%x)O3ISBD>tgUL8mA!nm-gt{^HE7P-o$=|UYk#AbB zm;$5Rp+Tth;ddw}8}IlMV|AvsycBaL>L{jH1H0acwjj)a<4VjugdGJ3Or+1d7QutC zFzB9WLW}Z?v)GTt{IELdLIWNVvc*h=!ZJb0-90&RCe1on!PKyt0%BYTXa*MCeQ~%Z?B1e&1;c%=NyvVD`sruh z^~EaIzf5Bku#rVsz1nc0GYvI+qM`f-1Cfg7z=g{^jKJIog57BqR?i23Px!BtEk045KE zm>(Lq_WR<_kDb#$!@^`RK49$dmdSL|RC{@sJkyX4?rCsF{mn{1@6H;88%|F)2!z7m zoYwq?LV+%1;ouoWRz9#Ogggm1Z2VPzvhF1T|KEhQ!mq#sSF)w;Gd+GYo>llIiFC*4 zm;dTs-awJhbgCZt%B(0sakI%VM}avjC}(i`49vT!rPOw*-}0U=b#RP$sBJS zt9x4b$@tZVv0XpO4`46#&g32XUGOW}yPUX^ufy^=_^zhfT)JYi%`sVA{n#@@WO3wL z+I;{^g2_t1r_8itEd!<|QQ?PciTRd2!w-x;2QJu^wo5BJajfvv#{fPUEO=%C(hS-AjD-z1%cS)|~C`$=n;}O6SiGzOz zN$+&8<;pZ2%kJ(k4yX^Av}KqYEc+COg!C#N4omsclHX}{k)S4j@-O~}jQUq#{!a1r z7dMPg7{)FPWlNs*#t+2wjv$S32-G-&&x$V;A8PQUldIU%1o_pg9p7p6(R+8|_FB_v z!87S%Pg`@6r>`lJWc_|-+E-1EK1A&>kR9?}-4)cIjU{qFPD=rER6j=x=9md2Aeix+H zBVLBQ;4ero`B4NM6F%B-VR1ehf{8|a3+7PdaGa3&1TK4h-bJYoO`E6*}<{jik;n-`qfx$+`StM%d2rqJPo`Nd~9E^U?&`_@wwXy z-VY&}m0#j*5R~6uUx}54hIr|bIPD+#2tAHF;x3gf@xkoqXoyc=TUl0JFXN=wi3yW-Ko)TDil~hU|X17H`#xgMW4TtlU9h3XWX5{_N0a7bAAx z4K_3Ba^%9OYYU2+^K(AQ0(@f)_+hUbtu{(0g;Ca&6TuXUAM%|RpxK?o-Du0I-?Yk4 z9V}2+IoZ*5tiHhx31E*x?B3c^tTt!e2Ri+W=&GLFUBz)#2z7hh!_n!Q51&CvJwFrN zA11UDKYJEiuU^E9XP?FH_RIKB|LIQ!CzK%BkGR7JWh7~^^AbT9xMJZb3%C@HzM_l_ zFXEuAL*O;0zVqPTz4-3;zaPzoWtAO%IgBSWGxKg2flaXIo-)k`VrZHJVdC-aiRMMEeobCTt)e%mrT*YEx9Q z3d8+nckbMF-n+ZorbjEQD{<%chUz?_`O&x)3zy1=qxMlwakL}KGlZw)%Qr9-)r%FC z_3rwr@M1Yu)^Eqev|uRuK|N7S?(S^IVYe$j1};~4b|~D?d;_}LWA~TZWnM6A3-{R# zcCEIYoSI8|A=-rUd`9zgV44E%hQS&7%ebn*@8R|k%=sa^y za*{&HLRskt@nE?AzQpJ?0~jSbO+WsRro7-q*Q3jlmv8Zgm=@_?}l z_#d8G%l+Zc$%j(zqSHEnF0M1!R+PcUcB1c7wyaWHVab0V|JpPie7@tjPbtfOSB5% zJ`DsNL;gW!8Ou=&q2M5G^FE?CmU9UwfdOfl4-vc>^GPFROjI1cLuD>}1Uu50F9Sbz z%uok#7r6=xMCfbu70?r!LEj=C`Q}v;;3(ry@?E(5$X~F@xXJjTu}b|Aytb2m2!{fZ zafp6IKP4P;Gj^C!M%*b&Dz%6PHfNgp^smza#&V{t84miA2ES@2EQY?vScgIvr62T( zv{6tY3qdJqSt2qV!MXC86&CPZw69#;H~iK&;gI)@3vWFZD{tte6+@!?xzHu+j3KU1 z+aVtO0p(B`b0=jUC+++NXD^;N+!T>^q{6BhvL(Xf&aQHH)3dmS`a!euR4WuvDPy}- zK*k?-_`*{qU#hz55Bb&rp88|qkrimr29*JRh%_u8h1XFDfZ3&R&O2>2Hi5&`5!}}R zt@x9UqXt%EKwH4WtP5pijAy4i3xojaj5^d3e7eSqx#_WZu(1>idY_$iJl;GLzs~sn zy^lU{IbLpV#?H=8+*x0bAOHCKUa-Q#wx=)m;*)1P@p4BzNdL_Jy~({|;&+$}+)`iZ zbvj=72L4u)Fit$dUf+KFm8Sa1rYGxDjqT-g*!^weG>7ArcQxSK+vcm%d)q+kht0Q% z`*r5GP3!-JimyKw)R!>oSv`;@k*&GJcjLzte@Fbb5SnD+%K7cs0-JhOOo!pAya~5Vi!y z&G324twh%+X)y87w;kjGvzHFe(~+w8pgs1>t{tO-(=)6-)>9NZO z=1dM|oO3|YrydwJ{HePKEtSgyrP44A^e_lO{A-=OrMXNfGg%N|#Dioa3uEGY=_aRDe8q=pR^K5!`BY+`D|A@vCI)4?5x3XwSOLa2 z1!f-MpiYHfe)Q{ND9!T5o%;D`LY(Z7G4i`mAAR8B7~m1#CB2f0{nPM$^8!%Bv~fb2 z9>y`9M|!0NH(4E~I22ReZ~XN$s8<@SH?fL`!esdnmemqxI4rbf3huG!Db@^g^J|y< zw@apU69$vvZoUYU_B7y^!^n|3;A?CE4ystjw?`T(D^u&ulSfHrI`D>u2Z2c2b-gjQ z1cP+>DiMo1FVn{9=BKoget@q5l#j=*0nGiQ-vS92guan!INh{nvV^33xa-H|0vQ<- z(>LF)GhdjJ_8!xk;O$gUrg{|MV_@y8EyvP=mi}GU#Lk`r>WitG0{rRo%yD<*WTaGv7 zQ5;~6LouXMnyoq%Bg>$j^(tXV*CH$1Z`=pQ08}WKorh4EA-i}5^BGtvli}fLPCIcr zYfXCp>|g$!;_J&y#gX3!Q~9SVkib+o#tW~I)`Xvw%r0bX`0;|m@Q&so z3(w&3Tj4DnBfQ!KMGt(1=Lo9%@MJk*k-NOC092VQoD&=xjae%gSW({-PmBPL_=HX2 z9Y;D7SA4MEBjUNZKbNwja2gxA@+k@MNvr_J-agok{r$Z-K0c4h>3JVhcTGK28R~+9 z&UF*j$yK{7SWCYX)d}Gyilo`8v3MXpaJf0Bke5ETnY)WRTt=_9Ij4@-$+y9yot+)K zjPtV`<2W9T1@VsT+EZJzvX>nO6N1C)Qd8|Vqx^`+v0G=+?O(*v2`kwVK5=iCN~dyh z4~y>?Q~PlwmW6j}AI7CA!4iBz$jEL2+K)v@tR6>UKz%q$a#Hn}68?}E!X|`JtTYGa z9J#}4_D*X*Ze5?p!s3GAH9pgfy>{OM(pKllJgeJWd5|CYIWNALc4Y1|YCOtg{44|$ zUki^qF(G_cJ1sUED#KV@oT6yto-zdZ%rn9Y2ky***0MVSA?BRwfYRaR_O{E-BC4IO zO&{NgqKfy9uIs&I5s)Wy;$RFQv_ndf6ZN{<-f8p>*GN?-Ba)2 z;YcWsTV%H-JTAL0To3GOQxtPc&4zbou|RQ3?RI{86uY|{LP6M}2`|i1 zh11jU?IY@cAzV<~sqj4n*5|LSpgO-eRiEc>m9gMr{sqAtyYKkgZ#yi@AM;9!He=TVb49|^=T4Q*{?3l)geU>wZ|LhBp@^W< ztMP@a7GR&F3`-@Z=O0R61y=s*%bJU!m}Gv1Ld&?Lyyxc{v7&j{!qQ4i%{J5~*T#W^ z-EGmc?Dvex2p?D1Rt;b9d0b56Vq-p_pN9IWS|j#% z_v4TqJDQWQvL8V(?c{zZoER5Pnr5dMcqJOZQS2z)yc17-$#)*NJY=LCCb9rHx!D9Q&Ej#e0J{=d*%F#e-pzf{}i94h&Zx7Z5pcw18Fm# zq36cnr^jLHBjZ91hr?9y_LOEzbn00B8-m8EFbM7`E3|)oZQ0}7x%wyzPbMcuW3f4JSDG~S<_ssAWX zc9G90U3N_RxMTG(>c&{h7+UAu&=B|#ly#pydnMSld`zR;R&98xdZNVZ2%ankL5{&O zu(U7z7#KNq4-s7h1t$W0hsxb)DSwpw z@^s!=-rUVd+SD0_A8ht~RpAUw>I?eFCzVdg`(uoiPh$GeE0F4 zcywn)b?nFIUu+qkb2DRBZlf^U-`$PlURz`DY&>}QFqYRgqTM@-=bP<#vD1xLJDupM ze{$UKLSrtLQGkg?aK|fmq(V>K#$RH91vK7mruU7ZZTQZ(X}>Z49&&n@|FFw%`oFtO zZ-@Ib^S0va>&!Pz7xQhxzRSD`$KPL*_5A9xqWHS?vmgKX=MeM^uOFU5aER{;>z^mB z+4wvI51aZ1-EMrHw!hN&EB|dQ@Z#GJ*z-F>k7)Iq zUx>3D`5V}I7h@mNs_EO-N)-=$#$50xyQHCj={-z}PM{xb}FK?GFKTA@4>v6s%EN?$0J$~(6!ex+} zU8aepB#gIR{G9{omEM=PR9+_Ln*8~$1Gxh`h!;D%5ZH5k4Q1yNX9zrJyYFso#n$te zvGa0EL{Chz!c30mDhtA*2w)QA!9{g2+E0JB7r{xEW2mS zG^%be91f%kFaasmlOF>+f69w^1kuQyM>T2^$l#&4zWAF7xCTRxaNttwI#~Vg4JFHV z04g@$G^>nS+Ot+NVdsxQIwP9gXu#K?jq`{GJO=f-g@stZch~3b=L$On6oQ4ADHtLc zF5|j?1U13WyR}$hq_oMBcrYTs&=(jhH&(28HH+-t#tp-#2(%&Yv^N7W3?OapRWgc5 z+7#M~G0N=ryw0N(nMf)gI0WNmC7Yh?w^^3NkHi(P-cz|*vBjz&1~nK2GkHpri5}@u zHeZ+uQ>nTjydw|XxxAVQ9k`lD7-;e?hJr~!p2Iz6M%VWXh*`H%PxS+aFz1xdfZ~y< z42XA}DXpAXtK5Qt%Pcz~%}k26%}&kw7)W8O9LXJ%?>FfZdEl4yqlV$9hBB1$-!Az# zWVc_sIK3Jc51VvwdMcm$Q3f+T<(+BBy?m#lgS6{A!`PlL|Iml|t7Waf7?R+ty7*nw zEB0CrO6A1@DnIpgC~&tLS!*7=iECdwQVu?{4`!_Vy@|zdrk(a7AN^1);Ggu9Z~NH8 zPP{Wj=H*8zxNY@zc-c#({lyP%{<5{a(&Bg&0vDV}20!f1PexTTZE-l6j9OkpAJyL< zH#y`>Z>No&&-A}mvbH&H2B_u7_;vGXL-_pWH=j4$25C`dxsz87ijUrdR;qP$96pD? z)4w7JKKRjoJfu<6HOg1JUi`WmL*Lbgxv^26#0d9EdzA9ZkcP{mcX5(imZX03&WB&d zQ6gjwiJZ7x64A?Jp3_LT+TSqFPfxnkk9_k=oW!D6O}X@!0q!bm!$v=YzNH`M#>Y^4 z`BM#UgeuOmf*(%X?PxDTIfGyR>R10XUHZE_B93v`Uv<@ zWU&AT;X^JufydzZVM61Efsa4{!Q)gY9Pg5rzkvsKm5=c72UeQtsY4eZu{j&di}SIxIOn76*m=cnp6SWan3H{OY9boblfE0_i>IH(fBg6V zE{-~F@x`ODDc<@QAAe#c(oAzTE=DH=`(qz9!yRYvC_M0R7+`|3ggc|A)Ml`={gabG zxdXpJ)!BuHfc1-)JF%_yJ7^!pDLbSO zmnR(`5ymMKjroQJ`~73?{u;4Dr!hAjiwlidTUqq|a~y}av9{!u(X3vkU8knT)J|iu zw2*DsoE?wr^CK0oFGN0y{mo~}e@EpUkNFAV(lvspGkJC6aDOMR&W~e}T~^2I zVl$KCnXi5M{I2THt_BMW1?SUa;UM`a9r#@MaCTUpXx`?XNASAhjlpGFpd3N~&Iuo>jNs_WOO*))U&npb zcfIvblzvNTx8qoF2ZwYMo*I~!3jo~Um^JGpy~ z4#k@zPEi7K_Y)^v&;}d{+hv!j`!H$gQG2WM7AkW@=!V*EeSO0;ja_&3{w|K$JL(=< z`Na+|0n2k9gxRd{_fdiB>z>c6Y?P0;GB=&|eBIxWPuTwaJ7-=V+itdep%_U z!wNsDaGf-Gpu51{W75FTlhh{UUD`(fBx2vMGDtj__li>a3zNdoOo#UNTjivl^b-r} zMUNH2VX3?QRW{>?%b7>FQBJ3X~8||a8IOM^4ho&>?zz4IZpEf>8am-{;(6HV#qqo3MR?xq8ba~j@WKiD zDT_7oSX~wwv*4I96P|>fQ*+{d=&#=GUT}`egJ&)SV~St_&cPGae7rcNd{cJg6XCPl z2m^}+n!}qg#&OA^#v<(8G>TVoZwtfBF;f1S)O(E|W0GH}$A*9!&9mry0Zr zo?j7eIFXumecT#fl}RyQ7UrA89X8)4{I^Z}ZS&j4|En@t&aW=(zy4Q$@=r(ptN;9u zuU{)LL77~@&m;ljmxi>}4V%9iw%XI^UBZEC_9@@EGbQmvMV+S_Qn?97#OhZfVf69@ zl=49n^pU0d663VeTH~e#XA;6%zOk2g8l{YvIvD;AEMU;dDK;I^LHVIP4o`#(PPs5C zyh`$KlgZqCW9&dU?B$WYyp)&HcU{u}JMy$YdD@L%h2gu{6EaT0g(e=fG*@HrU;O!( z6FFo}FtQV@rl&Wd(@&<>zZm=olL?iOnW)`an{pur@Ipv+smatWO_({FWK0Z2UAc07 zdF_E_L`46!Cdh1M-QL`cjwT_T``yt*;YgF0*CMKzrIn?aZOq4|1_~HcR!MNiIZ7E6 zV$)(mU?9veieQ__D;#z5Kq1161}%HtoH6*&Sg z>MQ1yK?b-q1p6^2!>a3~n6F6

    gR$QwSc&F0y7cb+pr_bZX ztL@m{J&2Cd;dnwQ96~Bq&vQrC;^Kk@uJD0Zlv;1_p0?l^GPq@gQ{CQ4eE$4pJo{o( zed@K~JMG0-2*A!xPYi2>tLz-+Xi&<8AQ~kb$~lzI2yF#a@rUeKgMS@YT9?7`q6o_8 z)JCk(X2%smdiZ;U#vS#Ip86MelyL+m$37m&jW_V%=tBgB><&ZVNO`HJD&=;d|I-gq ze03H6pmP|TTf6acYbW-V&Y9W)IsmWEt}legD7>g26I&?g!7Qg}G3TEQv>&$MNJ10Ciud4fs`yMY^XH0ZvM5c50{fqfpKW;iHs(<$mMx&h2p0p(rb zuXd{QALe3%If)5{9;IOgn8GlZA}!CUY=<@yPB>NkEc{hnpf$OW79|(L>g=0*6E5c{ zEViWm^k`mec|mE-7IQF#fQ&Lz!!EPlK z1}p-hJk*Q%3U#F1D9Y(O6arl0zPrZUoEJ^(i5KYid&Z%L#x;~!zygI4VWA)F)a9N* z6ojP7IK=qG0t6NgaDOJp@2;&b`u;=4J`{Z%XS}|;;vXUu>t3AYD%*{^vzE2h@@XaC}?rvLJ5G}J3O}vzFlm`VBS5wfg%gP%i$TSKvE0!k( zfBG)R(5Zim@9+Ww)rm2=Dw3d`;3RnJoky4FNl%5x^hJKELYBV3f(qJ_yEBp1W#3j= zjZ5k~;4}SE@OGclgMvJjZK*t`jR}JcrKU|EVo{Tt!uh}}`i?A>nK6{RCQXOk0$_Q{ z_sHLTr0{`uq@P`~s7J7_3VarH9E-<5DGgoEu|jRBGD3?gt#DsdBlAs}IL6XDDp6*` zn+g^@^mUF}243`cUrYKU_Nvejpub zciM>$Hs#ZX@S?r?#s#9Iw<0*Mt+J(436XCMZ;Ddm=3jAhgbZoCCk&o0Oopxn%aZCh zlX=sWXilkGO1w0(D`KXnPdbJEs;`5mHS02L)X2@djR4+?FZ>v|9E`pz(x&I?y13tR?LXQQNL&$Vavz1P~$*k*I?SCfmvu zs*+7K`dX99JgQ=^a}b}td>XG_zKq^s*8wtV#f0xtnlNXqPP)>B2j<^NQhrMeGAzvG zn20pzxkC_9l&~FnQOwMW7zb}<7X@YT$jLHH6)SPYlrsTS`V1T-2O~-$U?$UyC_KBx zCOp70XjP()q9&CmDyqKmXHaBy0|U&Z^0P8W-yC(qQ8OIX!UV9_J&ISGuVQ;^Tj8kC zw==W}hB6PE#1GntFIs>W%gI%mw_^+$cc$`GLppr(CT*u*%IiEvVtRQ#?tJimJbL^j zmR6U|Xpk0+%e5Mkt>5I2pbEyC1ZfZ3#P9=iaEl`iV6I^_7-VxNRthY9sK!^dJQikIbCfd0RkOBi%;J}JTc6-%H z7O+F0!#9i!I7U9K_A#DmB0|9lo9D)>A39`I3-Tj zD$~xe_IjsrRQqLstUqb+k#=yA{Aj}x%&JQM$$D0w@{3>o*nk4ugKPyc z|1M`~A2*&;jsNyf{&^X0+QqFBlnWb)jLwPk1c^3Lf7yzUw>FPN6hoA-HcLW8u#bdNBTj%88GJ zL7=9$9HFD^lDH+_goQAye1c#;=ff1Eq z3<2}G@83b_4{reVh!#A7#Oes;!6 zFWQII?g%x3-JxJ~dd$5G>{39vB|cqmr>|cNO2wa$zlBSxCp?*g+aQcW0OOrWf~AGP zEE+pGS02DIc{S=oI};IQ+U?tGDmV9Mj9X}e@@7hW7dv|p_OQYj>|*y6b!Jxwca)*{ zJM5i!XB=&X;Bj(h#sbz}|IE9F;PVkqp-ABVF8KFTmC1LhsomhMP*i|F?9}0oT3}+O zjM@~Q4@?KI;l&WF9Uu2p2aX04k0|_WsvT*+)g`?b7EIGl&$*Y1c2Yl3*{3yknV*{! zk1YO@d5H2u5Xa8MUw!gfeE$4}mAK93Vyv&O%l|44+b!{hXK`nJDSrHeCwecd&2IT9 z#J$7g*xqehc!Yw3@-$|~;=Au}#0T%+i^jsd=WN`|1rD<#5n-h7&(Yk?yWQl+T{$QS zg#zNO^Q4R1iIsf5`>e`}vVy*bkdBUupXr71kfX!K+z;8o!K!<9pTMin&rZhewH5D( zV9rVZV~2*1Srk0c7qSwcg@xc$?$#2YEk6q;)vgH6EF4vt*zJJ8lp`q--f^tl)XbE3 zCtBbrKL#mwkU?8mC4YE$C|o=?j#fnjWltVEtbjq72dzTzi@OD)3dima1b@t97`4DN z=n`dtZo$*nzQKGIVLEdHaKooGh{hlQW;|wYfZ+S$96{ol(iA;ouB1l@=5UlN1*SQF zfX>X$&3Jyo@t`PADKm5woF)wQ>>jqQ^g_W0V?ujyPYlXl+MT%s^c5le3_E?)mhf6A zX~08{$pSZW=S$A7P(IP$pyxU7%6YQe@r=9t@(4sPN>tr)@xW-zPKzch4`?ZE2#i>~ zz%DxIJaazsN2x}5U`d@l=T><*<_;x1<)`mLe>iF$0V_K(Jf0|D%H*9ficg7=srrR7WaOyD|8I+q^CK6~m%xn68_qL-SQ0%FSHSb7T2Yh8iC`Z|HlSi`9Aa zAUDdSHf4t^ZAy63t$4_jX`u`-W2Et^A^O-*9hgHZB_)YJxWz(=)sQN2UToirE zUA@9%;pg0(=!539eT`Kdy^A9Lm?KpM3s^_`RPLw|O_`gE_aEK&PFVWBfTuRRj;82q zL-dAxQHCIAvMdUCjxg^RKCqBiY3%LoSV8PXBBFh5l=QN2=OH_P=Ne0HCm)@sHrqcq z@b1XIcfFmMPO#&OqxygYeIk#K1(#n7rW39sbPrm(zrP=6C%~Me@!D2?p^Slcx-SZz z_wU||m6a7QBw_6FSg*J!2a$n6<54#39kfNWPla!}_=NC`<&1YMG@$)0W6@X&&e3n_ z+u$#TJ3~)d*dbFF8H4dGG@vhXy3@7r$UGQ`Cj%W|7x;ww$|y1mrA42nzgm_i{HFi1 z%bx!GTKxcAga%Hje9$@LyvhRIU`G~sNFPlalX4O(M?~wO9qe}ViBD<=j-BMRCGY~} zZW{Wz;t5t>%;LVvlXYX<1Mi?q$W=^hg%{*eP3^}R`isYWl@Yj;HgZQ61uSY@M;QuF z!p>pZjvfx3g^sZ^jZVQ>v%R|;92<+Q(nt7;@ABPl!V|_z(xnWHImo9N|IXAVC&Dch zyU4ECb%zWy;VPD@r-;?pziB`}pDQxOaP1^S7(m-aCk`y^in8?H-+queo&E zrd?cBqBN)jyb81><(#KQ(V62Vye(s~@j}Kl6dI;{;U8BumM=EMTd3_?q7g@;BjDQl z%2GVMe<$9%w;JmUGwN%!zu*oXB`u}H_)NV^A}+M{#(6LJWxFL~df+ z$j_M!+=qUN?1W2H-qlY(xhsI!D#MMBe@%c&Kn4+FW@U&%SS82yp^e9FOY4STwmfdbP`Q@bZGrwznc#;<%iX*!skYo*4Q}l0o z_(jA)+QpJ#?CUTN&IdpGsI@LR*bY;YZJp^E7U^Yo%IDAy;~%*ZOH7Ai_cdt0+}?^` zefCLgZEu>WvmKtcg4I(`R*_)3a!^F^#fm%_GbTl&}4NEE0{R0 zfdK->DE&16ir6z?Q6?rp48#z`JabvZS_7TSpmdm|apWE=$nZ~wR#EfEW#LVH>U$}I z3^T#xhDi*A5llKq2l(Prj^tocpn;&(YRAi$o3XpIqk$yh^KA?zcvmbFaS?xmQ00Wr z$iAtc*R&vIE(SNhWyt{VP85STPxa@m?@gt1zOGr!BjFCm2d%Hws@obp`B3Nco&q?<^C`j z7Z^A1u2Pe%zmym%Jx>tDW_V2RW+nT{uU$(mN0Gz0cIv<>KLGx;|!S$ zU1O*Jo8gE^h=TVnTuHkYGJ_1o!KpZwulhTvqhOWM!H?>nX}LZnZKoh>hL9N~IdHKV z!0at!Czlnwa-c4xp*E~#CJb*^tGHlKSAEfj#kgK_PY~Qdum0L#eGBHi^CKN=I+zkG z!^n_U+N*#0CSHxE_v;F`0W4}xZ>F1W{Ne)Kv$W|VyUWB|acWW+eK3|dMS=`6FE59^ zi9jhyF@Mu1TQJK{8Xosbm})2wCgTsAOo3SWe#+042hx z{M!io5%!6nVbaO*JC_=hQJ`>ts{*O?@FAoNzrkww6h0i0WyMhI@HjSiTd}p% z^6`=EIHK+-T8_QLjn%^J1kqE3_3+?6?r54F6w3SJ%zPI78N38#M#zS;17!??8dit< z-Y@ap7L@WREQ$#DqNI-q*2QPfz(*tOPN6ONT6hDTG(UiT&^8E4%-2t#2w_1R3P-_8 z`6FmM;;yoG*E`h^y3*F{qT|@ZwY6oJ36z*seb{N{-Cx3!bG6-(_$lfEAIR~42>6bb z9zxP<1kEF?kVl}ON=)A;#!e&E%jK8b@$p%-IG#rjf+X6W`2`oq^M)^AC&2O1kp-{Z zV}%k3L95|CHEn(qJWnAtg5TL#SX@ZKo*bqG{~4vF?38{Ul_VBX@j~;MapNV*1a>HJ zWM%uX7q4Dz>Df^okIf50XSwT*um~1U`~7Ih{`k?Ic>mGu;23z?iXCZN>X)xJcjBOR zs5#21j}dyf(TFGS-HrSA?^s|*3n3KrP9JbaZ3rycJ#}<)9-VIA3a~TvbB-K@m!-XO zWjV(mUZ`#9pRC%R5RB)9L-3!%6?kIRk~s8Vb{nwE%6KR|f=}mE2ks1_f3T|rJOX&c z2j8G2dCyo`Yg`Py61&69NjhR{=l3BAs#fx$H1wbXzxSr zsX922yHzQ|YzczkSOJAIx0fFE-q>g`AKTMYPxV);V& z<8r9cxsP{wdBsP`Q{PLqHwxe5BlSbgrLiLf1`a+x(86Ahwi|ca%w?fdR?shStQ>dK zO&Q(@9hsMnjZM1Wu@knhblI7Q5{mf^^El?m2>zLa_;@quy66~6MDH9?JF8G!Ws38#aLQi5^bAS-1FGq+qY2o z=&0xXSe&{l*g!i_K#(>H25<)4Bwu!m(AFph*v-H$z@GX9ZOJ^6auJ@s4F1(|#%-uV z-L$mYTIprkg@0-^#kc}`;Fdd0v)*~PA@w)DtB&x8!@^f9MfFWOsrVvq z`Z9_@3c`4kb68{>j2q;QARky@_$G~{wR!(DwA${9Pk9*`sVDVk7wFo`Qrx+7+wnIy zx4dwH_NMQ-yy}|o{M5Ncd zz9>He^39zC3)N#(_%|}C@l11Y=Bny@YKS;MDYnlYk!M~^Kzq&V%>oPZX16J0Rjbp9 zm#;QW|9$V0Xg|CmyOLF?m{xyAv5VX#cj}y{P+kx1O?iM9_=3W0QE*&hx0836!3Ruh zJe~7#xfuEbFvtc$!8xL`Oh!}X;@&K1Hsk)@?r!|z<6kI0^@Vfs3WDSM#{F1S|7CXy zWoORM4s!0l+uPfVp2|Sk;CC!P5N({BZIY2`F1vpk8sC?emQCNFL$5_6ro@kojlxHu z3_dYEv(iLu%lO6)uKN$}yPuzH3+Lb-3qG{Szhp%p7-H&8t}8FZZ#t zJBg!a^{+MqhkSIP%2gM{fX~3@RJaFiLNUmWJ=%^up^b{{F%h{NZAtx*12Q&wSE~9m ziZk+n7X&8k9*2(5|9m8``y&ckXe7Jiv+si^EZojMn*H}ow1KzN0|yvClozxQIg8!& z=E0cmt6YRfc?xgEu2>fJcz2g@6g*@>546E!obr~VVM6&hZWP?Zo%(?hDDt_>%)7gI zln!{sm;{c(&!G6?x(#MUjC$1T7$uw9kbc4rIPM)Y52kX@Pfz*?!FwAk!fExdcFQ~6 zxhwae(|14RXk+k{a)49tZPbN2(JtIerXkJr*m$P#E*BWEn4H~e>L;RM9N`ErG%1?2 z)Z|{cW{fBu^Gbab!D>g*=!bV#;|CwT7q{1%>R+PMug}bz!BgxVv{YC4>`~K<{r$H2 zIcNxmwy5odF|7vqim|(%>R;cOVLOIzKjr(z;9h8TF>flNzB$x5rqYIQf+R;nVuR#lH+>v9 zD7GgO*u@y|%8xX~>H_KCXj%OEg+^Apt@?3$>fr^$#G5i=To#p;aypD2h=&KIS}68>0ZlLKK06ll;3f+X+2EK(#lex`1XeKzio_%ltn+r zD?9pEro4&hhxU=hjZ^|xzhP6qtN)N0of?ak+Z(Zd?`||SIRQSTi897?LxYfPgLY#A zhH{a#u(SHn7iY>pTZPG0!h<%(4Of^AltU-1r7RFqF$USK#J4^6;m)ia|kLXHSa6@KHYE z!x(`NE+_cmGJ*%Wj>%FokyDUY5rzBxSE@`;2n} z(Eb!qCh3vl%4tS@q^Svm?>)m!UIe4R^Nn#d|71+(o0j@tlP>=CZ66vjvwzFae-2_7 zz0z~wZa03?j>#bDs3iTHsI6McGZk=@y|hIMP02GD3D}lCvU>~|ge89Y!kr)_Kv<<+ z;|#v-uka2;_$&{3rwczNZw%q_8#vsU3~Q^+z&fyG+YgM>DppytO|VlAauFO150^Rv z@n8Jy#2;3>(@=KKv~Y9D)6wO&)gHxQsbOlJ9kTqT&HlB3GPc=Cz9dR9?PGK)DUoib zUH#HIzYJsImoPOJE_Rb&LMvTr7+%=$AB2~kWJw|MCd=(`{*{{oq^wvs6phLI->5+Xg6X2D7 zUGzN~#vI*f5wPmasuUeU=e=TVJ)OrZDL{doF(J3f8(Dz>)| zEL?Y!gVz9mK!Cq$Gml*(@Ln1_89z1lk``PUZaoDv6hjBeBK67R^<{As;c@~#f zy%SRn*um54oyL~nz0*F5 z{wYFy_z#5O!0*h*Kfw=k8Uk%(LH6{d1@{~ygpgD~4UWZO*Bh{zP&=}Vik(vMzVJ`* zuk4WWVb$*)#mR|yGPR$A#ijCMmkDKT z_*kVG3qbO|sZr%U5etpkXv}a_GlC;_a;PoXoz_H9IUAEI`t;bS@2BEerl~0uewuTr zJSQk^L^v*0A9gTtBp$~*QU>N1rX{qI>IYv)-6xediX)DPLI6uco~sVqz)c>~Kmdj?Esu4Za65u4EQCVAg_{+!C=)EanzEp_(@CK|ik?Z;Wp3hD%ubBN z`1N^=zdl#~y*Lx>;qf>YaQEOaHg{T9Jh4N7`H+`uTVXZlei^XW2u3&VEuJ6{j5d0Ao(>_hL8F$hwEzHI8 z;=GlyD~pXhs&RhKLb}Aq;{q$^f1t+-)@3={e{8N&EQpSh3g{k-Ln@qs~1577Ac? zF4A`J_3SX=A?@7x$+3UxQ;G{N!QcDnFX0nqqaPvc#JwuFnEzntFZfv*E<-vTb%`Q+ zd1Wb9*Vo;)oamrJ3WhB3%X{VT_njA4XW;n45Q58!8vDrxC#g6rauJY^<%U_y{=f0#$r=rT}AbnbS3v zMF-ivl=G=8(=c!X+U~Z8maFV}Tq;UCgxt`B>@Su#=)rD0Qk^Mt9WN+6?;JaLs7$(f z9w<9>vMP!Y0wdt1Esf9Qg}@kuA~m(O7eugd6B?n1@rO6?W?n|Qowwr@eoH^(&&~)G zcQ-)i~z-@QF{L$`e&A^ZkB3GxOMYPeDUPNyG-8aIy5Q3lfH?6~Fb zE_QPx@6mXtw%*y_I7rnqxbI4X7oBO(UWV#r=kAG0uqiR zoE1FQSC>pTSC*ii4Y%W!@&WdYr7VQmSX+rl5AMaCjdk@IXbx?+ESR!0j5;O`u>j-v zgq=Pp#3GJ+9hc|RUw;~(=;4lij!k}{vhHlZQk>CP6>r0Wk?X5-k3lF0w-o0WfBwI# z?Ouw$3dd1!wf5uuw66*aw*5}*ZNG>Y&pwIIKK-*e*m)VZu2Eu)_}FF?b(g0{anx;j zM1~0zRAkM;cAMJU5D*7-LYpN?dx@k|#M1&jk2Ndv4(Oh=Jv3LPG z=pCR6OP>c{=o8RhkGG3_AsA;n@svkfAtuq z^q_|*0x1uQ%2B}#8k2l*DyL9bK|@jM9dA%PR5qJwH>S|Z!S_4Nu%A;SyuYx5Gnh;{KZ|`3?aj1ndc)~re=}4yHLZ82@nz=g z{D;lA3HvVdRq^rpZPWi5a;U4Ti9pPXxM>Jg+|=QrPk2?p^XqhKILfE=$Sb=9 zzk1v2?a=w>!r(?Qf)s-vacis_AZP51kl_XfXT8{AQS)`^5+&2L_2!Lx`EZiep$5{A zOOgKqB$fn37GV%jChZiJ_97jUaukA;3Nk)afl`e+uoAG8ALiHfE}kZ|SoPyo6MDba zV0I}+i^;`)M@+{4t|l?bgs~HbLZ%=&g%nnfoQN3rj^p_7IFAp(+llc)NP%JtMp#U= z9vB2x04+2ZJOFaE1A`$K7sH_45;MT+Pz=9jEGZ*p<{JeB4s!M?SCxkqZLF>&FRvPO zJ@Z_5VlluGpE@ugGmtV+!u+D>fnj5H4@Vrb!jvt&Tbo<)^5rY9Z2F5Bz(9F1*eUaC zszL+W$5>@gy9@`$=$pD{`v{o$*Qmp$hUX2;;m>)?VNwIp;~#xD?mu}y8X6$S#K6H| zAjD#|Aa)W&!Nc462xnL&0t3Mj7pw-=C@pU>kQ#{1&`>tgkTcAIcVg)ST4Q|F9|}sM zc~T0)Ee|F;`1yi#xv7F`!&Hu)iGe!Spiccf;dA>TOw&Y3ZEEI44-7-DCSvy%1MHY4 z`7pGUJtxr>XS_2@--O8tIhXaqxM^}GW`z}8+!4k_)!-;C0@DpM1x)IMn8^++9)TJ5 zX)y{+D4000ecUT)RDX820Xvu$R#yT~Pt+6#@t!AS&_0zFhKNeI`BYa66~!n(Z(fUm zUTv<#!`t^`W^4*z3;fxSfnU923;6qowjdd&_7;NJN&adyr>!^bXE!m+1a}$IseBWF z3~pX&WV2fd$iJ+7)jaG&xtvJ}R}41OQ~cxw&SNb-;VnbLSyqxu7sXX1fw9mR#Uwrb zx$dPC5e6H$m}QkI;WA83`({jZMG8FZpBDe7zaIPRE4}oR#Xm{b3orOWo3x zGGhw-Yw8YP47NctmB+p%2vtq)B8}skb|+1;3xz2L|C_J~&6qF@=c->9UhmQ$>}HtO zGS{$acgd-9apgT+Cj1BZ@rJoct12-4!cA`;3_R9w&IY4C(xu>l0uQI3QA+}YkeIA> zO}x4bWUgW@>!=(UgMs3p?eO(0%RETFSnB6+UVK&GL48Ud^VhlK%l+24@!J>SEf9XSG0-!Ao+`vfxx&g#lviK~LZ()$6TAC| z(eC!G;Nkc^3(^?8Nk(HSb?~AS$4i47V$@&-JtPz2El9!3rQ88korM8yub>fn|Om1t|~pnCm;F> z0t*aptnjc17TH}6pNk`7Htrk+(`g;%0w|5ylz|Do6v$F~QrGIiBt?sd((~A^zPj=rR$Z_ z#~fLPawm_BoKoHhGM2^fvBLdQ?)&@j?=ABu@M20ldaPWA?@&Dum?K!EoEDrHI8a{r zF85~DnI4Rg3jy6o*|9(0n2m>z9>m%ztK?ZF%uX2bZDUGTb)?)V(9X^;y))sk+fn`; z?bnoF3gO{BSyj#n5C{s-F2rwwceD+BDT+~jgEQ=Cp`OMum5Fp&Wlb1%Vxg>}EfKKv zkB+0;>Dq3bQ{7ov&PrvT;K#sUheqf{xgo(>S#U$Z;voC1%@niRG%_mpGrEnvG`oz z!|p4TR=^Pc7v&sqf@d}z66{8m7jTw?K&kOt>ExUO;ibapn>@isgoofKb3Ld+FD$RDm^QUL zEzdnsh>-?I)TCKq2iV4#w5F2^oF*RC&~+G zPwv3eTt{gEYv9arXI05!=z0#4G#k3ZJ#*e&3GGt5A#jIYwN&1xpM5I$wXJaG7`lfK zAIAKAvj{qKM;V~^{cS2M!qHCaAlmJHwUhdf@oHMMlDo3bTz(WRD9&huyjLsxG;}?M z;V5fTp-Vp_j>jq^2iTFu{7Ctuz3A^e_EQ@YFWp(Ns2-uT$8I6$RWkAipQ$JF#%%K< z%tyE`+>&F`ZTTZR0ngd>Ntxi%6u|r!b6(ncb!}aA4m{~co1-{IyTDWMisQf#I-^7d ze-94!-Nv*L=>vOYCfvt`|MK!uJbLuL#<&^prb0-M>>`Ef%wG{wqsW*S4dG6prusiZ z`x%u%?W^*6Y*&5GPWz_m?3#iWk54l8j>Oj1Ui|vkpIi0;Ugw=n3&Q!iIMWz(baoZ3 zc2{(r-T|S!rKI@90eQMg2}?w^Bs#VQhnLb4>7= zV8|R9;W-Li#_8Ts&tn-!$}!ibsiBc~Z)=WxZ`}fSdMW*w`yd%ltT@rXiWHNy731nC z?am1{uhkaa`1IGmia-1FKQjzj5VO3r;`U$+p#O-(sDGm@Z^Zrk54_U~#R9wr%1USy z^iCiVtkgHv7r6%s-i7gaV`J640kj2p(J$!Z(4|u!pO=dUyn|G6xbu^pYHjtC-Q6AU z&fO8L*g4)7pT=FKRO`n-`eFRhAO6IOmUE2@9A3hc+}?^bs0unF`%fZ~p-#dZ6<4F|_JK-uX4bJ#xU9-kH158QUlyyPZ+K9`?Fk zTymlQgo1x#V?%vNup|TJ1wHqXj7krD>#`6#Zv+sa0L3r5xrh~ zuCbQ-F}l#tK~(C^4lB|CM)c`prGxL7X)z}>h|{<{i%FHAqm~yn{&UwV_2bCS+|7-$ z9Jro%Y-95R3Swv&H0MHm7BE;+eB#n)p{blOpkgQ-JNr&lc4!ofCK#{F!Vkshj99Ly=^T)|_k++2Vm zQ|A#j!*-crJBIJ-M!af%BOC;wnDnd9n`SuPZ=|8`VV5lXjd?r#+a~ezo0+dm>+8%{ z#mDEjP5*agvK(JsmOSe4zd-R-gJ$RP2OSWn^hl?)$_|oMRxaZVzV(S96rUWr^@p46 z7z*ZC`r(bASqWJNVe!C8VN<}F;fUaL^y47>*dfE(zxcs;n8;wazpeJixWpO70S0#c zmJ<4@wZsh4A$+y#vBHS3dS@||IxxVUuoiTtyCYCz`Q_^6;zW?Q%WT_?aTy7xKc`KA z5_b@|5Ws5cm*G=B{K8R|noK1jHYMCmTjxElv(PD6{H?yPnhQ3vZb}IcIgj zp(b!gVn|r2aBQJDJQMIjpm24a00Ou!C%!72!s)0aK1*WXwzyg9!>6 zm;nei69EQn1Q;;kKE}&oR97+m93jEP5`R_~u_~718g@A6nXS-9^fwK8C-lDFWE;}@ zeCT;cL`Y}q#Pq|5+eUR%U1?*EyLh7VON3nVEhg0DQBU5)JrgV)!*In}LA2q1Z6E zOd4o2YR!OaW=8Ruq_e#|g%9{MDLju$4Zau@QZOc$Di8OBX|`d;iQUjBU_d;=u&NqZczZp^JBr~T9$+Ld26EgH z#F+`9+;&GW!zIsxA9;?k(p&I^5d?1pYb(Qq*OU)9AiOfO2Cz%|rVD~%U43~i=45GZ zG48G1iCIl>gyB>|p%m{L0UvhKp>k^n-LV&>(qyoUeY8&Q=Fo%HvwN9+?+@#L1wx>%nW_=b!u-q)k*g5zKb* zlyvn$T*Irxxk)E2Nku3_zWoghFrd2OQPM79F`1l8ub15U$7)wPYNniFhWu-p@!>_? z{guBMr>Rf+yMyRw7#{p)dl&yET}|fWeP+_$*EXQaUbI{irzKE}#D0 zs5O+{?u$5;Z`uE*DZWgbhRmS9RrtSUzAXHg88^q57+{v@a1$s$lStLEq~=lkHuF2L zh}VNc386E>ZFU%O7Z6AMuyXpS%h;|lm3)NrjB8$*NqdX;r~*I?EtrcoZpL%Qdd4uu zUfgQkd6PGVaXRA52oK+oM@^~M5ncf(Cqh1i6bJ^GaOb7v@C2kIydhmZEM}?YO8$Y8 zBS6eu9p0VLKu|ZMwAcxe0uzqOL#Tu>m%33dC8Kd){HY#b22bG0zS5;m2y!^yh0D3Q zABP1olm#L5+R{R-X~Ms}$lWY68vnTm6(J7%B6osJTR4F5(7Tq-Sj3aUX5dX*u!G2p zwOk&KpXQDTjt`qw*-~jnA-&V)l6$mLQQ6u*Fi%c7*`>rvT<+v(B5Ye-j3x2c2!^;r zBJZ9MeG>1{KI$vpsg+C!FW~d24?Gj)qV5%sfD!OV5tFq>PXcN_+yFE}YAY}7S4Z%W15j?mW z_*&r@`@!h(4ayAN2zhvJE&7ug-)-GQnb0(sJZ^zcC} zD_<0i2z%j85%{7cDp;^49EGoD_bEF?yhB1|z0#cHxZg88 z5u{CwbFU2iv+zdcP;{k{v<4jUjzqzcmHq4}L^;iUU>pnTBe+!0E43dAuhZkcV5o9Z zCe?@G3%Ug!Qg7_w6bm=kH&#@B(Nwjq`;&0xL}{NP09IHOT(b&U<*y-ct?)e^1anc!;9urce(>gN#E(D zewB*|RUF|wbOdDsb7EjaU&b)EM5rmsXF7F^B29QOD!8yym7QJ~%81Yuq3pA#&wMu& z3W`S$Zut!6X+aIX;QAoM3cloA^ocilG-FoR$0ibdI2 z`z*>%cB^m%;r#5l@BF%ZXDt>QGZsd393RKsdH#8=I-K`~+vgVQudm(_o{h!JSFhsp z&p)#w=HbIf@&1#KqOrId{qxuA*L{tPjEy~&f%)&H$1?B_JL#+~uS8S0&W@C3W71>L z?%rX%+}e-bmc~>s4w#Nbb_1!rv-XU^6wLLY_wZU^BjW_PN76e*B*AQJWO~LfJ#> zF=oJr(B9B1cJ(w>R%jq`kjx-M$gwkzS>&ie@PE|;Di89$bN7yTm?hH`{Py>DV{7xJ?Z`5?0}Lf2#1Gbq zo&$YaUtf)T4;~7~7JanhFMjc7@x}A!Rv>=wyFZAf3rqlQ9t*josxHj=*~`ep%tA zK2F(bzv(HI%IwC~xGy|oM^dZZv7)dq`sZCvqBF>&*y)8_@mM?;{PyBPBkqV+F(yL0 z8K2xOxjA4;yaX_TmjY&c!uPiN7qDQ4 zNk0+TG?pBi&jJ@$#T%duA62?l4wd61JOF$Ud<^sw*%rKL){WD**!|2RaPZMQsp5iv zj46kr@dCH~=fvZo(e0I37Ja$85TBuZ;q4mYmAR+) z<*Tju^G}~fx6jeGil8>*SjDO|qL0wd!%8H((4f3k-+{fnG4HZ}JH?l6<@wF(!X3}KikiiE~B6C}zYcLoq#0Imp698ce= zl!A#tV8$RW9H4#ilRL~h_PR2ZiN1wzYFn6HCK7g2`jru2#T^U~d8Cj|1GeCSI}<_` z)O7_v01y*s^7SN1-;|5A5e|8>q;x4C`4W%xz*D^hM;J2t0u%V0AQ={=JnkoMfK0o# zZBAV2S9vr9cL#VEBxL|6)USY{e(AD?0fn`nKY>Yc!!CD!VJGbHLm2&*Wb>_W8{+AM z^7?Ji6FviF9>uM?^MJ2J$S;@EU&TA|T8|y8Aq`&oA;aQNx(;rav=~fS2YIHw#2Tst zY09Q@)-o1Xmyvh%=WCFU-kHX5-udwJMm{|Gm1!APrN%hR*f#@~?~H+Q8pN>+bttLx zuQ=J>X~)!dO(TC43^i>#mz0Xz%^2zr0yqTLEM?}G-n=thjc>)K-q^G6W;nhp-c~o) zQE-*(P@OW3EOz!?yAI05li{(aQ-36J4j(@EI!Z$2Xv(Z5oG=J>O^@hHO3w=DSw-qt_-oNhJF z-GBbKe*&>2?=I?}c{Z8Ac{>r!OOh5-VOtAm? zFMsiW>Z1;`Ex)<>>d-*huYpOIbRe(fi3$#AJoIsd8aGD8M~&#Y6ahy7vAy5*k!vqr z?O6D9c-YrOmPI2PcNu3C*E|@LZ!1&kn8|TZDOg}k&9N37(W7D{4(iW+n|JxvAG~07 zV_Y|1$M~ms^hI!jG1-rJ0IC9ikzpAB89!N(k5D@WlDOCUW_k0drh24~?~a|G)(|;T zgxstqKQ^Dr0x8W-{gyuh9iEOjag0do3Xai zjN5uRJ`Oe+p(qb!V(}EhkaNN4`1m4PouhcQy%!vHhtL5*1Y`qaEuzO z!P!ZJ5&)qnJdl-{l%FIh0D?fU+z!gXe7#q;)0{@ zXunkMla3ga>nr;;8_k#$FT*m6OaCj~z)h9T0 zfxgGQ34RxWu2-<@oBoL+gCnCjeu!Oso=+)V+LGN5rz%@leIEhZ?tVLVclTpwXHWIs zx3G@>jN*@R*?o=ll?FTc5Cku?GF*7W(T~8z_kbbXR~`5!Kj6kOcQfGYsCaNzh||x7 z%NAk_CpnT5VIytJ%Jw`iT>VP*sK*bYc!Y=ceKdM=TqBA#gpns_98H&ZgY`OX-%G^K zjl~A{{IKIu{bhPw&!p@#7I1UtA9?!tJ>`qxC^!@k^c4*K1)kkJynuml68z@gD$2x> ze?AIJuw{25igouTm3dP1fH?xRf;+-?wstHyM!A{u2-<<;>vC5E8A0dRT`|{am=+uz zvwJhk0v%_*i4v$P71@o#9YfF*l3rcmqFnn{u}jN*WfL(05QcEG?-2>WxAT zH;yS>Ry(m9#XByQ2K}2hZqAEds?Eqdh02=m3D?1QlrWTsT`MRv6R%Nhqi~~7%^Gf2 z@TxC$IxW*E=o$Tv-KqV4FX_74j62G{_~L0C?C(aWwWqYYqASbs`0@L(wAgT4fjcP8 z_jWg9Z|7CC54PgyuoWjt=S2PT{0xEqvC~J;KR@5J9DsPK%*lCH&h=URp)o>j$RbB} z@StF%ZP@`hCK$3fgdJ!;vX*a+oAd|d3cP7I7EIPTByF3Dd3MC6%mG^Nc9%(63*7|T znsNr(FOM8cIYcVym}k>hL|4>K)ThovJx}#0#x7*$xH*614keV-&^pF1jtB(y=c1R6 zt8^{@(1VPFahr7LhumX@ARpR~0)QiQp)Z`8!cNZ@FSbN8&V^62K8llZj~&MBe!dj_ z+Spi&+j8fQKhNd`1M+8g4+=vB;#3?(kFw1%QS_i8{9+dvG#Pw4(f9}+?H{lUP~$KP zXOw_~|I`#^<7i9KA^Mzfo1Lw+gQ}f0eH8k^aePgUO-rT&D9OkR`h?Pn^_y;xbltA4ty3@75~ zg!?CRj7%PZov0(Kw{TuG7CwrWx)v`5&qcNO_7CIv=1#oW+>Nd6{pg7oVOQ8et7Cc$ zU2cg7>#+O#O!zLCwAy_=z1Z4o$L7|q=yc0tiLVl2*@o&3UPG^GOO8jmE88dB>T`v8Qoib9*PYm0wT&pHp!rCe<${G@dAr z$*Eb@Rqz%chGNaULt{aGZb3N8f)L@Gij;~f79G<^a?FLtQGs)jh}txd44n0tF{`#_ zyg>=n;}}5EP{w4&251lp_T1rhV*2Wng6LoBSL`yhQcG#VtI{VK-&3{&tN;sPzHygg(sI#b_#&l8pTKQtaY;A_@0SZgObe7R3PBdXAooOGcB%g59aYK` zS^yws#T)quLZzF>A5M9kq#s+pD468 zGVY^2k(>LR?C=CEzCc07A|)0~F!n7d|Ai(;HEJwagwAtE9^+Q-yoN>rOlSr)8v0Co zsLHa_kFs9ygY!xYUKl=u_O${}0D=GZ9lC;1Dp$M0Hx#!h#5qxmzM)5buGJHsQ-7t& zSY@Q41OS#s^;5r#OSS85+t7D4_8aumrs0OoUnEX7#QlrM{@t5@{jdJ}e|qbWe)_YYyI@ro;UZGdEG#P)uvz$I7rfIi zzj9zE0ShnO2QoHs(yxYf=m8+=ZyLhum&puHe&>@81Q99@xmht{D?bj9k7onngGES{m{R5T* zp|k!R%Km)UpOQE3ywho5YB-3WKT7->FhNt@^jkpph8cXz;s}{n8Z705xPoI9@@JW3 zhoO^~$X{G)@XA$Xl!w)}8W14L5Zhx--cL0kDGW*Sa+V6mVB=jiVx$mEz<@GnK|~oq zQ3{YBgQ^t`dYlINQ8uST@hBS}IYGeBZLjaT(VTi;bEnJYfo zPJHcwmDMp2d(vWnYl$I)N&Ra#G{Uzqx0sBwBKPjyXzD#7rjZGX1*)pICj??xFU#bV zE`u`1OocL|je!XRp$A0`$|%Onb;?wCgciiNl8AOJaCd_NcHl1Nz!MQU1ACZo7he}t#aNEb$h^3?WsI>ZGJu_+Th|pa&N<%D_@RlrOObfOgJFON-MqU@*}}9?KChG!^TPxQ;arvp7y|E{G$j)Q zZOXb`GBMGgYfJJ}NQOAnlRU=6z|M)`oZ<*i)g=RFU3sX7f3c_6z@%@rDBlvqZsncH zL7VbDaN~#a=$+ri*JaEymw%f<+PtB8RNrZkwmm&D4-|A~Se){3LsayFYPz_iN?s%kEO&cerT`MT#_`GW( z`GHry`S&aBE*a_CG2i*%?*9y1pEnwltTVjda?J!~{DC2y;6WV20T0qhTRy_OEJ*%2 z{hRNbB>5|L!qB<-C-1>yUx&kPWu)ylaq+KjhbvDS+{lqK$~6;ld@BSTB173mx;5<^ zPyZ0LzBA1Xn*r=OWGnb)TXAtmm!1C`PuDxszA;W0H(vHDWwN1P4?NPR+VxH=b+iKk z`1g~T9Dm~!U)j%ZOv3%k&DZ(=hN%F0`|&GbRz8hN^ildqEfouqJU(fxVfwHmc?!t9g<)7-=3qZF0b1VtNRCm6dL#)JE_I7)_No1oRKsz!bzF9+r5Ep`EMaXh;M zI2!BdW(RU`Odp(U_0W zb{ws=fiQQ0BfJoH3l0-%cf}zs+K0Y_@Qk^S+p{P`*y-pyp17;dLa`LC(LW($pc8Lm)xA$7Hy|ZtDDvGq8+`$zTPcy=a z@e$Sil6$DaiXsGz3&Nju_0M~^SK_`Nj&Wr5I?7r4HthoLp~TExOzdJoNv(EMKV`t8 z?g-`b=)G~@DYx95joWKW>W6BR$+4Im8;KdcXP^P+C%(T1C5m}`^-Z5pAzT;{{20T4 zrRR473`#^4=Iqi~SX#0|2q9ymp|{!^Tx8B9aLUfShJMAONsdQ6i@n|5*xlX|{-yGj zxrb?9!8w%OeDj&gJ$51{U8K)YHfS<*iHC)k>>xEBBNP@aI2Mp2wcIb&e+*we91+Hy zJd~;1=|uZrUogECKBo{FT0z;_v4W5np=A{i^JYgVqX|OS%~vRyTAmLxpJo>g3WS#W zS{_^4_fea)5q+6E5xEbBMHbM??VZhd@%(ea;#Kr}?KnGTXWpTe8;l(*tLw3G=eBp- z9k%ylZ|jB2{pjJNSYBSY^1It@Gec9ek43Mu7rUEJqpx@WsH3MPc=r@Xuva{xo)uXr zOjx*jdZIbJ@RlP=HQN&2q`*5BTdA->p@Og+#TRd64;*)hLfJdwn1_iz)G-V=@nD!E zvk;WsA1LAE;{FUS`H?@yN@2m-aun6WW31W^Tqg|U9Jl~p<}YPcIQ=F4$aLttl$$s_ zo|7u=Tcf}n1z{?~{HOd;uyX_)N_KF-$HfVs&b?rOou|To(W2Rz@mNy-K{<+|_|_PA zT8@iv2-Q#FR5$Jc{OE(nar@3)rH=clh2|T#*J56Mu-|RT^>s{%9wHw?9^k$zSR#z~ z*s5=M1;$72NF`^b_#QiqzgwDth~(-@<+RJ<4fz^FUwNvB|C-6hH{s0h<>t zD=b4V^?(+vtt_a&&KR#*^n!AUyAk^c<%P$LH7t_YQGacl}+Vistpt;-GU9JFO$}O}*$Gv70Y<+OQaag&Qa5*BaX*PSji{7bBtJKz!G0jR*aB zwWGZDJ8_^ik2nfZ4|jxa%bgu>2OW)LqMwJo+=;`^aLURU!qJ91J3HQ)hcY@BB`5v> z8~P*T;K{kh>RXdmc(H&4UZbya_WGw*u#p|!Xb7h!9RgN9Mef3_AaR| zM{J&&Ph!CrbQ;A!%3^vibOQWl!H7=~P+8cG4L`@5-Qvj4SO9?%2>t`!6}}Cg1AK>% zp{-jj+N+~>fcHcu2TjqVdZU12w=s*CtZY}+*uBf5FK8Sz#tW@Qk637evUpy7)4P6E zQp&}`6KD%cDt3gECNP5jLrWQhqc34BuT#G4pa%~*dbck2;^R6Sd? zK>nr_-%r^};Z2lr~sv+)QJofM2Sn>6a>54k(BNsu*iG2%FzUoqgw9e0OoYgA@)M?j_)dg)1hgS60~o21SGqYNUif2i zaNf2Iee31EMc#?zIP&K#aMufG%7tSU?m4ZJp2MoQxDGfB%9LRcD$7#*N<5q>v))`> zooUxJYMkO%+%i(8!+}6QVr3nw3ltYX~`hM? zD>S)au%QfjNi3`J#NfM9e~m`f89eVY!+vVFDKV@|x7TA?&kWm?)wZ-LZEvPP10QcD zeK6o`I|qxoWSIfff`Nh$IdRVkJVF5rrj!k7U25Qi8E2qHxdg)kTn$sT5$#k5O_+0z z008E=BXFVpc$Z)&=JaHbd(*O z_POUO1CXU`Ua_aN5IAsTB8;q?tmN&<4DBR4aAilv^aLy2#2ks)gf?-^VQpwo+*XBi z-GL8pJ7yRR>G7HF4r0Rs0eX7zbQ)M7Q<)Z_^zAg$Km#03VSr`zxCxQ&G=W{P5B^HH zwB#3MCoda(Gh&vdQe*N=H#_slxZRu??n8bqn4MjB%Hs0khKDU`+XO(y<*$Up&Bp8NWf<2y9OR`CsAeQGU}qKlH=D97+{soTE%hTaU*{eYmWp zp&gW8`56@Y;gxB~E_nM72OdY$PlbmZve%I||CFJ^8h7GmUbYu^zcYZ%jm?;wR+qI5 z55SwRQVvrU-ZgFgW2@PwE4G{Or0wZ8{HBiH?d!VAg?>mrHaT8rsq{yFC7l|g8uF;+ ztDb~%yUEQ?L+~s?N?EI^d8J!ExasXc*qxK@4#3YKk&5=(+}-W02~H|$*{I%#B`;GK(&M_@v3jeDP`32H+{#~ z4KBUge4YQdF%^aw+tfz1D-dUi2CIGRD&`}U1MOby?sZ~ouN9j+2k~-q*8*yU9VeQ6 zda;V0lA3;#Pl9|TUyu)i0q^QQg(qT1zj!?HVjPR50E(Gdz#IDKD!bodSE_m}bk~F3 zX(GH)G{WR~$HPi`?p@G$uJ{y$KjN6K7E}2;`g95o^3;IUmBmoE2#1zNIO~lILTr4ll z`|c$aJ*&%$R(RAf2rCcvTNZ)|kQUG)IAj$ud;&*hArM69JvTERi?b84prZGt(9f zX&xYc=%g<=vm1xJSe4CNd^ATonqOBrS%uEghTPu;Pe_?L%4b~d!n}ct{Sjbu{8VFh z%JuOIVxbty+oS$j?6tb_YPS{Jd+pd4es_B(!s9C+01Z!i44x{_T!e&BnOzp=Za;Qe zU`NoxPB`WYC@gxtTuqLUJOy5<0HnPsAFI;|i%_jG-&99oCB1k*wKd1BUA#^OC%gH! zclKh7)$%=#F-$zI{G5-jRynP(k_Fn05FQ~eN`slX`B++6^_?sPq@Va+uf?X?Mm(k3 zig^wKDHN?JU=VEAx*Qs03G43oxQyS`R&KH+__Vx;~hzT3zt!pu?qqP z4W}1?2f%{)-x302J?y%fR{x_c;2{E8VCQ2()#p=TfbxK&rY0<`SzIs!?p&LMV z1E87M8n}@eR}eQ^5unj%YyuRtkZA*%;Xw;Y|AZD2B|s9fp#A|Emok$Jufrb6?)+tF*J>vQq~7<_;X^SYOh@n<=AdK6(1AJ*T}@K;{$|${j^GWP8XRl+tPHtHQ;!Z6D*; zk*KAFaKV6g

    MweRQx7zC3G>AAXWMifrGdrA2Ulkua~a(^H}O_~a~UylkI*`kVIg zZ$1Y9+&Q=3jt@55$-y>b7W9rbTwGd;B4+L0J2@)RBSPor7b(wh;A33`Ym|P}FT&nY zcSTOp-&8Oc92H<2&@{vMI1U15cWnu8=exFz^w7utWV=gKqhOPE(55vO)gqAy#)Er~ zZ{nMa8(fSaEmh&>t~}?hq(+{?E;!(L$8Vg4r|AGc>812pd@}u7xGSl)Pr1{VvZYNF zXxA}rH`A*Hsn8$FV>_xu-QA-PtMma+9OH93${lx!D)=u&g7Fl5yA$y4+FEE+jxeR{ z?$(u7N~=Ep_}4j>@!tJ4(s9S%Y0|V@9^N&A^`_3^ zoOC2ReZVKjbaw&?9OVo03BgP7*t;1WclM}@^jtyx>dJC<^tywm>X{PAl&sbN7lnva(x?Cw&wAu$|rQL}#GB-ThI(I=k(K zJMCtBOJ{Q>1MarL!G7^3D!Ei3tDKYf&@K(AF{6|?o}yHJw(N zu6MIR0n>+a&y)B?c}f;>2iQR~dCTYvKk2mLER$`PU8KtABI6q-BV}za2$Gjj5${gf zQp}yx*Hxgp6IaET3PqJ`ey2{*Lc^=9lJ2SOsPWld+KlzF;3A2dI{si z#o0;53&$P%qzkZB7&{)h+ff`lVtf(~!alu=elHH#S5%~%k95MmDUJocyrW?2!Z|KG z4k{}%tTfZ{K>W^*O4>N}BMss1w5t^8jzuN=kuIpvlJ`}HW?l4mho%cj`W?yUBOY0v zPy}d-=?CV(*rPPvS!g?u75&k^Dx9QO%4qAv0Oe=>aoo0JXdn2f!rHfW5GGJE@DDm; z|KiCmet0*Py=Rw0QGl73V*;QHJ?QBl*3_+Nmru3vO>^_xc$%ATz5R>geYxLP3#;+_ zbr;<_%Nss##(mA;HAv|Tf@!`mov&!VP8y$A$8XM<^Xrd_uc80^KmE@^mqNHQ!Jhoq z{aV;8IFE?c*S8NHOCQe9dg+uj{mk(^e&HFn_*Ed&(>FebGp`#N`5Q%6LgbbB*Qu9} zouE%6rVC@r$wwP*+WOxlmI4^3!gv;~=DG~Vk4yO*v;NCDQDaL8y6MEB^7L(bDU&cSL7$91esG_Y!vpX^49XNErB3bV!h`8;^>MFbLGw@J@ZW_I6a@}Cb@#rB7dMUJFvARfOAqe0`yafY9baQp zrSu82%)69ICI|B*JZM`Ph#1-!{)wbsg-KAv=49pt43bQ~+o)fOqun5S$)wqIJ@&wM zwfz+;cowq)0t;I>@lw<#U&Wucg?4X?3+e?@zwA3+9#X(pniYaEqj zG8N*o%CZd1VH{p%<(|h@sNgbuCTgT3^I-j*bYA5c4p+F8Fhn;Q9OKJii91eoR8pC? z%4zTT@Xj|GXJI6R>tv+wLmsbUouXX3HPTLn7iE``kSUholgV|*ob@wb8Dtq98JIgv zW@LCSU>HX4jJCTAYi(_LHA>>5MKV7kfyQ^&=&u?3K0bDOztR9=K%KvyUFhzo_b;1a zq)mljhUubKIN$!*j;5t!JSx?4Pl6XbLT9>wwtMemX8pIOLTmV?)5MqMMn=|^wZ zou3XSZ8Qw1p>v#8# zwJT#xm$p7-wf-GEfPJOTx8>0_IN^7nq!$0{U19h)fqeJjX!le)gIBrd-3RRQOk}=O zmkJk?Aa91{i?CIeaw+UeDlxtN+O6soJ3o2H^Jcs*1a9Fq24%hu@wrA^HD(9XE?KOk z-9@{G8)@?qSQ^B@nuP1~(XaE*UpxoK5~t05`UDcB4`*hb)r{j#dItBMFL((3@lILG z8ox4zE0>DX)vNRSzx~U9>E}0M{-Sq$-Rz%#-KKBn&o%H-kjKE0p`>}-+X<7&3qCx; z@Wo4&Aay)etrk`w>OvLAQt_o)EA2;nJJzIMnV9V&FGwDaWmwZlRd>c%_?`iMumnjf z*8V5y8Yk)EWEjWX2u2xi{q|0z?5<$UOB$3T0tm+K2o55Yx&_~$;=+kEWh0!6tK?Bd zQ^$G7i(JBeFZP-u{$cWrr>*~JuYxu;k#vbw~oRyk4zd4%-n(G zD(46^Aioib|gH0^0*xz9JG6@D{W?BslB{4*7o2T zJ<7!+kEDC|X>rY9oke+f^%y}6MicZMnJ>=gVp^&Fvo@;O(O`b2*ArMs)Vzf`_KZc2E% zBk(E$J{37LQ2>%BaQ8Slg^A&rzy*?nN4XWjj>?B&9OTs$8Yw(EI&eo-9q*-LDeW45 zUg5vOK3C^c10EF#rYAKBKd8cmG!%vy*JC90>sJY%p1*|Gy5Lc8Ry)@86KgF;lpyfB zDq^#$Ux69Cr+n+IN7MmpLwj7BxRs-Rcogj9=yuvh!JM6H#Bz~N1oea$f9B^Gf(InR zzrAlLJ8se+0M6;<%dC!HfAYLN10QyFm=h^1CoTJuJFdL9LxG|=oLwl!#W;6SP%4k? zT`Wt>OTcTY9qjG2mltR4{@v9ar#bZMisW9V4TO(vq4heR-v@Tv&s@ zw6(&oQPRGIPZj@4>7h{fm_GF?3IOL$-fLvpY`?>Iz~N(nTkf~tb%usD;%GgZ0<7jULJ*|;m|2}cHU417Y+zp z;g`jswm+I_L37fA5od{``5{-Pxh+mw}OSoJUPg&8D7~M|yOj;`QjD z9Z_c$tI|&Cvv7>EXSn*Ccf4Gl@3&7s{%QO4Hy_is!)kh@nAYvv zE(Wzv)_Cdom>q4@KV?kXqC0&IIx9Wsh5GgnX_)xv!d=ILQf#R-tKB2gIgh=BbI2l! z_ush>y;;uU3Eix_f@*2l3}fut>SFq}yHZ?$AkB8ihp>72`8lvG!7a6o~`fD zrRiTIQ&Cz-158lmy}Oz{8gymBV^L>QZjT$>*z|bVtt@I#xg>vUFAyH~193tHtGjU4 zR+e*5yvmj*S!i%X`!Z%xXBV;FU0rBD{QgJny?5?~X4;2UG7T}8hAY8t9rkj>aqcFh zk46DXzY*W%4OB9cb#Ov{B=<@w|G07|-37GlW$HCQ=i-FIKX(VYSY*_rUZwYxTfu+N zU%0E;ezottTIcjF;9=WJ*BrlUv5||tN7~}TLXH!bZd$+R9+A8cE>jk1LeE!uT8}ar z<0?z@&U}@^?oiFq&BXT@%P6~)ml0RljVBy=2c-(XqsY0u)BGZMse zz$ZJ?D33A_`-`$e#|(E^XMqFm*}VtvBHgx)dikmNq>P26Leq}HEfr7FEcq_!-Y|4Y z8tPH2476=wcB1h`oji-H8JVv$#4Y049 zUhp+Mvq!eN*uupda7BbEoP=ih(0PhKV7y~IlgG(okcrVY{OYm|x63wuhde2h*EI;Q zGS!atU2eT!Tn6E=1NVX78*j~<_Uo_D3DHTF>+yN!^U`?D;Qggx zZkVqVwl`ll{jZfFkJ4@3;*LkEe(gdzskzNwhu^ zMuE4T)X%J(PTcY|Snh|Yuf$Eb`16&-4Bma~t23{p)BjeaKG_&kv$}MbeEHl2{lMP8 zpcJN?g%{Wr+8fO@OPEj=m0~jAiH1F;zTuy+5>VehI45*@^OD^o6FH8=)6vdXfh*nX zGFzysZ-(%SqDcc8nzv>0i%u+oOf>(Xtb_2HK6vb183QE3m1F$7f?|&&Z@x`eO5Hi> zCv3>Dyr_?>K6NW3x7;tX!|M{FbWWN_FrViRx)5LohkXX&O&H{JCiyD7JQm?(|A=u! zfkkDLRXn8S1k%CS36KoMyytf_u;%DF{G3Edyqz>jTCMq>Hs-^Z>`uoa{WS^@k`|M#uCNH<6qcVOEa(-uD}W|vqpa(ofC zx=1mL0(K#I_qO`dXzPD9@yQSVUD-4l$3pWux6~s60}sQOfTi*``BIvhPvh@M zUD#NOn>d=hI(TU9YZ3?F1rI;t)RiHx&L?e9zHzy(PnT}I36(OJn?Kr8U;HXY7eAgn zDPxy5ucCX`PJRVHOuL-Q@45*)w=QsRk`8Uw!O$;zbS2maEsJGzyfulgB7<^t!C!m# zCf}W7uq6rfj=uTEnvw(K_?A0sKYsHu=e3;jsiT^W3(u0*Q0VWh2zR3OJBbi$N>xzumignXG| z@8i2{T~>o~b)PYVw$ zlTJA9I6j%DU$s;w>0w556PZSeRe z6;NjpB6zoitK;Q+vU=IFd4d5j5-yakUGlo%Ti)>O)tu_IlHwB-eQ1uWV_QjC! zCoH^m6l!BCeCp08@#w%y&MEKsg#MH9bJtGp?I92Op&T_x`l`k4b6~ zeo+Q_c(Ncx~^aP%vY==Ti3(c|-C)J8v61hdH*;-Cp9o zyqCKq!p~#BQWyncGtM+^5VC%*<1-Si5017_c z!8SKN)x76RW#-2A7GU#Ou7&WdFDS$A;Zc-p9`_ezS?Y0_Rp3W^d+qq}fH}lTaNRZ& zCtdCDt_kmpa&AM>DUVQrFCyLWrPQB_rF<`e)8WCcf!aKAW~RK~)xOkP9UED7R#2z_ z@|<#b0*3;81x!b@#qNQ}gt^NRxRPgf^!P_#RDkRK8}5b_A8!LUcOv9ot*)=y_tWPn zL*`$!we1)BqVj|^ozt1Nc&K1dVVsIY=NGPecURgJ&n$g(-lI8F|J%ve-9VBZdEQq} z-f0gNq8VTLzoXKPGD-bxZx_@>NlMvORC!`VuT&Ja_Ty*I*V`wbJxae*$#Z&q9JzpV zkgJD+O4 z0|fAw)@8*#_)#=jdQ9DDC(~7cYTQ!Lc;C+i@RDx7%!1Ct{eviS9T#%1ALX?T-Qj5a zc^s$rky&;X8qQA?mWrd<6+u{)Huf=TwKz=b&`bLMk#`LqCcK4EsW>s=BG(eWdI#Fl z;!J4M)6ah0)}KEK{KdKZ58lhuADO5ULM5SsUh}?GNpopgPTI-gHt@P^v(vNmhv6vc z_UU({D_I9>N<2?7Z-FxsZFqk4gmF-nmX^F6P ztWnwKJvX`q{*=}7+U6>h?DN9Iyj1o{$4py1%8~iv4sBsS$!>@U|D6k}Ocgeh(0}^^ zu*6MzcYbE@{|)>4zQ9XMgDxw$iMOS-9I5B2>3cJLQ`5VR6NJM(GD` zi)Z4Aam>Trx-YL>@Nq_2hT77?Y`eF%)Vv?h1p~8l3#qGgN2QlzM;44`(S*n2Ro&z% z+y(jS)m8J(KzECZ!_rK5^(mZpG3P54+~nm#P-(C`cpSUEo6V;4c)sTw+wIx<7IgMJ ze2q$oz=IIdCF#)uv}AdC9ye(6-adJ5W-M_5ZYc%MGTtvQ&PO@mahUdrd-v`^H|Ill zcZj!6Ja@%Q({n!+>AT343W4j;Lttp#a?~qzwJ(Vqmshnw#xf~47y&NQsF6GFD!QGc zQWuw(fY)T`unS)L1qb#s$2?DGaED!FQNZrX1-$ZRq-*<@5=*7=Jbi8yygUs(+CSRQ z*dwoHdjrPMgOo?yWGtAOnhCv{WW1l49LxPq9%BjlWt_Xi_))S36&L&T-+lN1ce#1A zt@t9-e+PP`f?6ef?$tUuZddYUlsAh{$WJ~pJRa~Ars9V5%{~*jQP1;>)9|(K1dI|? zr3!JCf8_W|!it+7Q+@aDT9k*z%YBa0Q_7=)*|u@Fm-ysvzM^rBHc@c|Olc$gOOGQt zx|DYo@=#9~I6Ds-8F3_h0quU;9zFUrJ2rpt{qMCu`lElp%`Yy7Mmo1KJ?WA3(0=0) zn#w)5wszXnryCh#FW?u2w~w&54Z@d%W!{7vXQ zxCih9WBYCtUyl9MN1nLGVfq{J^Eg89-7=muLwrz)FF$w$j6Evz5V|6dGDLeV=AP0u z_{*u#ahjJhI<`vBRfO9UU%|^lkEP4h-*RNPIALlbn0#8@$>!MOB0TvD>5A=ce+@1W zF1&|)n>zBsQXV_C0Jc?v^o5Sptk-(?1V1G_Afw7KlR9rkrMjo-b? z=lStNF`&tm|EBreus6)jbZ?rz9&egA@q=#_Pz57d< z$tB^~g zDnsT#7~;p^a|YA=g2}Xuka4Sy5IqQGzpBm2fvX`L@Lg3SvoE72LoI_9qH38eZ&ywS z1X|SuLsTtmR{P=a#M?=WgFz{|EW7cTR54JnHy&$jzE3Uv( zph$Yc#nO|W6A(>>p_<^Q^%S=POCDk9xA-Sqvcu7`l9u%s=S&apf-UvbZ_bP1X(M5l zUXnEZ(sY(CkNoAk^RgpjN!w!;)_`g7t#AGK(o$&~U~sHq@1A}s#44@{Ro$^08++V4 zdji(i;I~ZgVYzg#-!3u}gYrwBI{3qPSBt^}%aXs&V5wr1OAm|AvHvgklv{iGS+AJ* zX(1mh=GIvg*U4MeD_<2R_VN#4vGvL6U%^w7c<0-%xYv`9&LK8_qV(bs7dqea_n}Se z&$cRCyt}_XTved^?)@lSpluYrV(-HAj~7L@ieDlG$;!$y@@K@eH@nmDKZR{SmgHw-E@y-qK}C1i8rKN=yY z3ygBF<*++TY=Ij4e3Euds)gM9Q0zek_wm0t1<_Ms{#)$VBtZ}|oVi<8rnS^2I&%a!BP(ek!M`$=Y)fREm~Y*Vlga~_{Iiu=T98-*8= z$503pz5t$Kc4nfDQ8!nRfBebQcJ^}At@X_d@4bY6YwsX!l%s*DcaDNNIg5}(UN!e7 zP;SdkkO&r@Jlk%cJ$l}@wsxa{bM?FJ=^ZC~yZhKrYn43VJqi#|HIM33(3!g=;0bQK zk{$S~8dT|a1=D^Gs4rgF&XncsxLq6{kjASv0UXAt+lWFiVBij-9Fqtv^m8$ji`u;R z>Ue**UBc@b-msHIx&vQyaeCB_5AcIGQut=uE0j?vo&{`#^O!)JQLfE7f;$a#Q^BNg zB@2pxi^4PK0t)18Zxyr`OyW*mQ$*QKPobH0l~*evyo;>rxJm`h3X~Q0XdfN9RYKe8 z@#ft$Q&TE8NSBh#f)m2u-TNx2NFpoF$A@q69w8oSQ)YM1je%2M+^=#+VXepfee&o@ zd$zHYJ1X4arch~neWUGfZvzVj%$MQe6mE&P3ao4H;k>1UNA{@*k`#2xSMo%$N_qBo zw%g|Vvv#!Wj>Xd`Ok5GJ@|9j4cpM*}XP1L3^;H07Oni0KZoN2fGZS?T;4tvCAK4j% zb5_T90<0*xcPj&E^vJq&TtNs;ad+egC*B?K5)}B0m(suX2 z;}c-(ZaDfw?TjtFdO_bXp7+y~lCoCIdz`1V_Yl}005`zbCMKub%-mcA;R@GXn76mP z&Ajk=^UkU$K6!EnSMCGskA{VI2shgu+9!;K)BM6h?hu<_tQ}XYYs>BK-4*PMQIJkg zsg!fq#aQq@LQnE`p5v~E#ijYSvb>aCuF|>@+EIVoWrV)sT+5@+o;_P{JDXe0qg!)| zhFIB=?+A>A8Fkp)SjWB_`l#a7`BCAo^F!uh^iu`?C&&BkU~jwa?Qeq{d(4#&GZ!Ra z37ers!fJAQCQ4@-?(ErhI6`}$(gpW zwAxnhzC)dtnXgVz7REnt$F}gUHSZAn>^C2S15Z0RtHigBsSDpK0vIXO*z7Qka@0VK6ef(BQohi!s!^__cbw2M0qo$J43{5zq)GL{^>sMM2B z7$2bb0?1=m9XrK|&^X%1v0Wj(IAxutCdcRp&=%n5&Tr*Q)6A16re>+*ZSd+M#}uw_ zg0Ij^`+@YsKJJmJ9tmfADdfs5A}|9^;CtV1Z6|TtHt3J^G?%OUe&%TJ>+W~M{@rh_+y@t3-A;l zRXmd()voeYF5;~+D_^jk-6=jbC0{g=9ZqvR-W};8bdOG+Uzl!-&^Yfblm56HxQzK1 z{@4KKD_wAbgV_o*ziki4kH~rqi!p!el6uh|;=lAN_mM*1s_wOeS~}oZrCdcNYj$!I zrdRYTpOGh$ZrMk~6T`U6O4*(~YWNPm{KVj+!J@D0pg-OohScf@pnfzRXWyDf-VFvIE#BKmE^m! zlU|`WuKL?I>)1qj3a@Y}<&miPckG5;%XCAdpx*j*~DGYT_t=LjV zyK#E^wdr`BICgVbOnwL9Uw>?0z3KY7;V^G=9~iv9G|Ub2b;7>Q zd{G+u{pEA`iU?NB%2_Jd;jnzLLlU9Y*l$N*L zo#TdpmRBdNs2^7pSM>7L?w7Gcc{}&s%`fxSQot+sO0!bw)2lE22-Ev@zp)uE*5376 zfK!5*vX`~sVde>)Z@nrVo$^x!FDo9E#C4edyB`$ej!9Zj{R%5=u~!Ch)1?00ca<}? za_hro!y z7X5XnFuqJzcKMR;6PT+Dh^~W`%CDNVLEM;tc)yq1>R&(*omnIaa+K`H2BB5>qCmqz zWm1NTLBmx6G8Hn8uEI5}^(iF_<1Bdyn-F;t?FBoQ-!f+~Ait~{<`Hl*RMt%5ZXz-; z5h4-a0n|JdLOA(#&`?1mL3X#7X}W@v@hXFoOv)Y%i;n}wS25=8^H*m21bqbO=NaK; zV<+RGHnlL{-uvjIwy?aMm7K!#1(Rc=3)>PNs1!6w83qLk#Z)Qe@dyjI!aL!=qJ0(m zx=L3jRAr&7@^qIGqLIUBXO%1X;c8afC6he?2~5MZTL$77uhR7Ro$&}3jO&UmajLJZ z6I+F4W)S8HX9rUKWNK`yC`IuIUeW$x9K-{{*q`fO0GUgVvFI7umPtmPE$-y21aq#! z5k>+btMyKfnFM)+KrwnfQzy(ufnC2E%m^yVoD5lCk3*0$h_4z!6agQfmO1^0cTKoF zT0sR`t%ea-U-*dQ)&YO%f=3_BGNJG|#!wy7;+G%cYEZ*fACIEnxTYxV4VQ;+UrD-L z{fUoWy5%W*e3Dj|HhC0X=C2~eo&xrEW5te1g?SVAI^BdQKhyP3Yww;S^3%nsFnZ8j9(>HFzem?>%vwZ*nG#k^E3Z0Ts;E|uH@|7#4D6ZT-$AnxM}A< zVe1`-JoSn@*2=oC(Y0sdcIEcpx+DZno$KHyO`^>(iC5t&zHj~rWE<+ymnZ0BfV{hS zNu*q~C#>JyBW|ZGapq4vi5qY8OkE6Hfy^UzUwOJ;z2n%GBj4D{yUO3$yHv`KdtZ+- zrs%iUu55lAza06qN5ms;$&06lx^5NT_+7fD)wv}*`di+(WwMz_U7WJSBz#MCUC~Vl&gSRoQgO*PxvY zc{8ofk}Ucsj;7sxhu(E|{>yY0Un#eEQck>w+MoXP&%Zgv*Z<`2{iMpBmKu~JpYfo4 zH`^no++)L9Uatj+=~Mh|pKB8+cL6Fqh74_9A#L7$0$L-S#Ub~0G0f~8p0%yrVb zlFQZ=;=)*wrj2lm@yDGbciKpVa6IEBh*Mxw=^P)%+noVX(v4Z(TAX5@ zrft2fk4GC#xe}ep`52St7Z<=`cLRR&tS!#ZG>=yEt_J-_?!eO!=FV-#;};54UbMr* z)3&~S(Dn{gBsh-WYLlbzp2L(C-d2T=W4MAN^R>Jsz^L6N5o$92dUVb{ZE^7mKI8Ui zgz5+IzNhdEb>E85?I;giB;<-_6?XC*9<}39UBbbgFCNRdf8d4kb^j8XM_?r%p;F9y zlXiD^vXf20nfEccYt4Ja?vS^NkIPGV32-4tLjiJkjO@91>*NAHLcR#TMBc>}`2=v4 zKOgNj?cz#eciMO~v)uYi+{K9t()8#XWyYf;3e0ArU{HA~=7cZ2xQq~Mer`SjNBLz1 zL87qyi|J&=@`bzQ_L&=;wE0Q!lDtO2rI+xCCx^ISl9odC!@aBq_SmDIPmfYdq6BPI zoJk+uB{2%I49S8tb>6-O0#yVBfy_1sP1v7O!pq!7=e?H1;z;aNSh)79(HFzTSf za1UH}C!&facjS2Vn7akNFYVUwIJi9$rROEM>-}l&VB4{exVsg%Gm!F%wmG|a)sE7%Ak-{V>2M#|6^QhDXQS_@si}#kO{LwXLqMwmHg}#dhg0)mE0#ek$%+E(O;L z3SG^w5=Euo`uci%^5iM+=WR=6QIuZZWux#Ox)K2;bqXD|?a2URn$ot}+1a+bw$hfC z7TVPGc;MqbZcB@^Q3|XrFXp~Kh0_Z4rzS_EkR1o%6~4M#!5tj^T~9gnK^owE1$c@R z9`AQZd3+RrUI7>r`K4g^L3IO4R*4;3r+mmF2w%}u0< zuH^R`0~I_ju#irKR?z0bALFRhRq-m`AF3#G_nS1i?#}kggv_;0jsi243z;X<-^Ks* zDd%~Z92@Jd9v2tT4<{#Q+sur|!A&?4MX{q|Nm+yQu)SUH3_6Ii)g2q}y?Z~f+~3=3 zd)u4sh(33AyicDyN*(Qc>3`I{#=uVL0!%DdDRk#^q@ncOT_@x8HQU2S1(8pbzjN+n z>J^xd#f)JS_^VWa=6HgL^het3F4XDCso;&{MnCpOzCsx&LdM0+Z8NNfW5_rmtSqZ@ z=g@hdv{B)m9?ukL0o14(e+*e5u7?9u2{$cJC zJai1DKZ{o?P^C!#1pK*(LPD6>SMB4L%i{u-QOK7}t84{+eO>)tq`#|}pJ0rVF4{MZ z;|{Sc$JPCVjF-mq2w~^9;;XdJ-E{pi(aIr&ZxkT(VUp2CP}DiUmO+Y4eC8lnQsaU_dvlV9~^$06%n3RV|J zSO((8UFB@aL+sAxUotW5gw#j=P4?l4n<9)1hE$KmC8KAtQj9x3@sls&-IyHRJL zXDaGF8gT+R3L77f*v%pc>L!n1o0w;4EwGgKdNgGGfoa0?l=4~miEt`;oeP&$G|gra zi+7Ky*fNA;dhr9M`4T?w>hgrQ`0egL7am9p4|4yUigo!&cONb;&I42N>auNzni;3RlDA}9l@S8sa1{KoI~u)VoyPq@yidCku<`0f8qXH0!xJH8(8_3z$x?ezArpKI`bt(0FD z{L9k&3g(N__^rBj?{C6_X?OX=!(jQk z_BTl4^yMqwj7Pt!yPq-)2^I&_;;lo{?ciZvl)YF$%hSOKLg2fyz}9^`8w+C4nXQ8i zm}%STWBg2B*u&4@XLvsRO=@~4LRVI-iQe1!=~&V@RJ?9*)aVe;Yh#|)MbDJfdevtI z&5x5atS;ziMO5`y*l#^v-hS0ia6e!$*=G>BfH-=VxP!M0*C~_t!`=P1{`hIzeDtK9 zA46=JAXvvf3l&R~FoFw<3z_s!GgvtAWCaxyH_wyJ>Iu?SfNH+3rm`Rsd>KOrX9X2b zz$BV7A;LXJK2RxFWjT-+!&-_G(>IMANdob;%!V<%MB710B5XJ(3o^(WnX1zh34g61 ze)8l=`{XyDWg)DpMo@pXkY8p<$;9f1;)6ugA#F<;V}yrDOGAz_$ld?&gDAeH z7~DKlz+HPz9xf@rjGE^pyUJReX6Opz=Rj%})_9T49f2Cl4((> zZQIqPPlf^-#disxWd*2%JqBjnqYh*!Wl9vXy#)U~9>}?i!W!|&FdCTv%a^u*xwiSl zNtrvq!?zO|07yPg@`hYd!!tcP-QIujUYnnpr!BzYm-dn#yNu~mWy`yJy@snHEIMD) zk3OL7GoU~EThBz*A2$$zZuutA8N9V|QQVU%5i)%$UZTy8cT`X?e3vVkd z=#LExZfWP(@zw-L{Rc*`4yHN}vP^yHR~7p;qffaTuii1nzy88>Ap?)(P;R{XP^l?a zTS{wi5=;3T$1%TfOU%>7N0a&+&N}(-+Ni2nWh)ryeO-cU)8|oX*O92E6Q?BCrxW}Y z_YLxbAN{bJSL!E<@RvNb@v1henxu^k-}}c_?{dekr5caN4-IeJs$bq}|KeZ%-}U`Q z%>Vj-_g_&w%UERzUuto%J1$i{^wXpKQbT}Z-xDrry8x|B>ib#^bh$QzYR8az^4B;H z0)ObeLJFyyF`d-OV>o7bj7oNLF~)h9m&z{hipUC25(&>~9LGDJtnzg{!`bmFLNUTd z5XLwrf(iEsa&XI7!`lLxmgBH)pJ%c_iLu^s)eOWV%OAm96(;#HbaBmx4^O!If?fXCY zPWvDH`+t;G=N{GLZY&iHSp+jS(M~QL+ug--$@?OF!Su{TTUwZD50tngK3 zocyY*mdA!Y`tVL0x&1P`sz!OwP7b$ecy0xf7(I zvQZTjx!db#f4dEX%ggZemPM-Ojzo{YQ3$Gl^%#Co;m^nre9`GKbmpRc_};seV>or* z+Vswn{pLvu@{2C&`QU>OavYU9i$m&v4E}qJqP+SMZK{$`9!({kcSX!hPPS#*(eJ(O zt#+`F|Jg}!W}dPsoOCC`$k;U0{}#BQ5=S8!=~7=6Ztg~!pZ1QW(RL-`QofUu7wzfB zR(t$xlXC8aCw4)cE14CLDQHt^r7&L@;}E#px5RbP-rklzo>nhh_M<33_1&9>=;2G# zp0u~Ts(r@pmHXDfjg{r)z{h?l94w1>%q%TTMH#5FcS?R3`)%;?>b7?ty#mk9+q12m zw!N=1r^dnT0Hv)wCec0-o|OJ^LR+cikPj7ya{N2>s*2DHD3iNCJUVb`X`a02nn!ll zj=728vBK&sP9vWj^(M?o;}XDJ0v`qJ&gE22NI*+rS_)McP#*EvcD9Ld6;#qE-JEx3 z@gj~2=ftH8U=cwnVXjCsa{~pNd@Ee`cr$TTrIB?|N#rq~9_wY_>suu|D5;yfS=?o3 zqu5H8b!U6KZLP1jqr(I0r$DmWT6h4+ylrFodCRJwji-=Y;jhP^&CX9}o_h=pdGXR6 zkS;hJ&JKt7?%#{DQkvloh$!8iOW4OLgZ5M4rsDm8dD!s*^yifMaKftiJEzf|JG*np zod+k$#~obq&PA6MWn=~AI6s)?_(RQ*8#TB2#tXZ}_ciS8sW=vUGS!mz+_P0WRJ>u-)r=KwA-=j>I%qtla z<`==|)zEQallyDH5Br!3OY`EG%& ztd*$<565t2Pdl`Wb(9|2_O|)$A(hMWck*YB@%Axs&fX-33A0jgnYZn$9K*hBeQbZr zP~(YV?8}e)YAaGi)@~Dldp3Dlzft7hP9uiXLbf*E&pd2FY=gyTzi7sj^S?Fc{Qv5oRNu7f!_K4`!C`Jc9zr1d+$ z^CSBG8vY*rXq(f1;E_jgdPnJ@$3Q|yM{m8%F`z1uqF^WO@rh~h$uYBVRG8Qccfq6Q z8#__1x|8zuE%K#4DgafO`FOOne5Q&tciRus&L@=Hqmy0yEPiDngGw{_fA1+%j-?EB zl1I2Z=6RgxsrZ7QbO;nn+^Z}Oa2GRUvouG(h0=*9;*-1oJR;iN?ywEvA?4>ccMj=~ zTl8=8rR~hy@RNkKJ#ybF_#t25Jzwr5vmP$~PMgtQb?;iuW1^IIyy?m>z06%>6T|J> z_ZM?~cyUSeD)300&REs8y~gj(l0MO!-aYS|_8afs-2B#l)Au#Mj3>I~H}>At?zU_5 zW*)t%{%~z>*5#&oTl_ao!hK25ubS4|%-4zkX8pct^OOJ0e=>CY5C7l~e=#! zEt?EaXL;Skx%~1nMm~$l@>|6fP9Q>k_rQ-G_fl4M{`mFGRRyY0Ri-XZ7bXg^xClVG z1;cl4UHtgQt?vYJ=HZ9%_3hgZQ+3s;>RIjyV;OHbOvP893fMoo=ww>u5W9{^T5IQC ztCexQ;imK?O0>9_t3D}p8^h*b6;hF|g|ok#k~CLSec+(%}$B;b4bJAcLZV zZXzZf80!qUb)T1nzqdOOc%(sXO|FT(t2a!yRs=Z-EM-M8w}lJ2i-~e5K0g1lnNaNF zd(|z46*hib8O#z)+&dqB*v1*4MXwAh_zSbDJMb|Mb-B4KD-#VEy_`1;^I=`nmLPTjiI7nT*<%gBz31>{xR0L>nmR@+d&3Otz7Owkx1aH|g`|9R1iJt8GQS`w$*=qR~G(QlN+IuHjl;bie7&FYN?Nb>HR9H3KRQlrr;VQ zA?-nuuwCwP(?;0T&CiPEsAQ1(7+CUOl(Z5|I`I~U1(z7?y0yD;>Dq>iIJLZ6P&(xVc%!XyHALnY(hiNC=P zqb^KL=TLBoOH75Vyb`E?87NPESB10_lD?d`pPgI1`gHv0${efjf|{leli&WQ{$I;7 zCYJh2o9F9B-reuO^ac6YqyZ&N$wM)H; z6}KC(`Ll0u$Jf92AN;+aRDG_E-_r7)&Zhj`ld!s5WSwm5w4`7C)4%j9)47)6!|yIh z9`nM*55}8PzA+w=?v)eRb9gN#tcRzUZTH};?eOd#o@Gaa7f~y;H$}^=i7-sT2YgKg zq&y1WT)3jp&J~tE3N!6e#!C5!uif#_@hl1y#~%Ip9=yB9ajcY89iPV2hcDhN5t4x^ zm(r^f0ODpC6O^n`Y+Z#{Y zFaP}Cv}d1w49~emmRIea`)lokcOOI%_T;SLR@P8g_cy)f9{D1yuf6{iho@b}l%*1#EJL0;#?v9Snb1#_3ysd9|f6HcsFvXLB zvv)i;j{ZV@6`D>?xQcu_N-+gJ_PyiN7j1k0C`aZg#k(v_km{wcsJ#YsK(FYm9CU$wmAf>W|lO-aYt(|Szc_F<5M;zZh&19dxx&tmLEO*zFN0kw% zjf?^B8S!^6$_01Z+Gg_U-p%Gt8ShK-nVTL1QO??57W3+{Hvb;+A*acwFGd=1zP3h(7jgJqi`WN*|_X$ZwYZ3~Ut+d#sxa6=|H%76p)w z3%S3FIZej1q^}>iD*%1`>6o@CqiA~-KK31z$fF|)s8v+LgAm`i!Fdu;aGE^mx9)Jf zyf|e(s35)+GlWk1mZxajZTxB;YCRN?T35>#dP&>nP9+r#Q7+(yy}n-z=%jrocj?W{ zgPZQilAd^!4eN9CVN9sO)`;cS-H(0=ExzsqhkW9_2STlbt#$^;E{Im^U5UWS%~ht2p|3yKPJPRWdlg&vCCe zWEJAP{VM&Zdkf#L!7|V9ce#k$GML%XM0(QdC~2Y7WEVI`>C9Nvaa0)Fmy+;re&>Wy zKH+h3p;e|yTFS_z&7sfWyY#>|la@)>Y{!GcLwF3XM>&m`lF()H!7hgfth2pW0Cz>#nIuR zi>Mfn=@;@O#b?&yrul{0?8sUIFV~hA+G-Y=@a^uf85No(%ary+`6Rd3f;U`AOhj3olfv`(%NL3Ov%Vjm#r-g2s{q z3az3^D{pYZFog9H4@Kkj7ydGrp#C0lI5Rn#g;@p>$$e`zPVbiA`T&CGhCN#+Vd^ zO)ww*eY(H;_lMv5B#kOeUmxo$!AdaFjy?XBd{QbWOob!R4gdN{nfXs0D$xqs{h5*O z$;0rv8igMpqa?PGFoU%H?c97_yLZO=RAk%@t8Z-e)+u)0UEO5j&KPViAh0hatPBd4 zUm}*G^IR$nU@~&Bv)5i;I3Xwxvy%wcQ4tJmFqE}o#?`ySVPM8%cjc5y6w1J(B0?ob zw)`sCfx!1noV8K_BjJo-KzINw8NK9dp2UlSO9qNRp&Lb-L>PY+95Uz$K%A`Fg+Y-m zmx+?VOYH0DL$}Dou);LRSXmB@S^alnC{GHNij>o!;e-eETzl``_Tatu+6aT3jD_&% z&ms20QU^-m5k}dEZzt)lEDIy*d3sAc0B{3ei<0~wrzasT>Ead zwn$9-DO9Pg^0YJUn#nux)?~s!7>#*^nZw_z*~SVdWR`Q>0cEtRR$t=;&pJ7&5f6$1 z@Tdc~%$L&36?0CqWTZ5u@T$p(tJj2w6Dn5}dttV4keTf#4yIubv5c1IT0j_p2X9;z znRJ62uBdd<%4C%CdC9xQ4MUvA<`U0Iqf4vsyzsaBc$YpA&6k#HBlHRHRG6@CPCyKo z2nptkepzpUB+W=y=O^?d&K01@n)&3j?EV_hJ}4gPslET>JM>rg?mPY+jf#JKG@V=Q z-CKX%%-eRgj(s_N#SJ@dm6z`ISN{c*giS)&`!L4UnLlCRAk&BQuRglh4S$o-A@=-s zZi#1IJDQ>s->x820ouF85Vqi7?+CK-_q&1>zWGsU#}T`V`J$n^^=*{639m(m@~=-F zy0GTcxuni1Gk*r`;8DVbYxjboVdGuK@Ck9#SsNL|ksmVa)5y3QzplOsWVi}m<8ejP zA^x4cypmGVD)+8syKkK;4MU|Ad6$31_1`*&htTMR!}VuZ&P3rSZk_4j5f~YOR~I){ zgLJkE;qSHSf|E>z)WO(q!X^QI#jU<|HtoKgwtb)eH5`RUUkcOJP3J*~n55d(CI9#* zME&zrKCzQX509j(-9$P(@k?AWK&7F37n}b+=W?mPxF#J-TP}Tg>4b0Hd;A_49B!8D zn>_09@BRmW?Ph$;_AWq~F2m}h zCg%tLJdV2xb`$`6w492qy%W#SziP*4FWSi&WAc@|NEBWuP_fCnwjvS7Dc_El8G9Lb zvl`a1jCby)%-96cBC@fpU5_h{Esmk?B+0mDx?O!WmbGX|wRMCTn3RFCS6ze^{^BC( z)`Zv;s=UTAMaQ?S3MDU(z;UOD_gy`E@-V`TwYAkKzbI_tdMt|*^zrdwU_{LC_?jhH;+3pZjVf~SMU*+jDJ^c zxV=*80572+^Nc(d1fPO;u6BR;@UynF@w~k}J8YN7d+pi7-?UFZ{#o08`lwx<9%Xg^ zz17v=md68a5ccx?q@5k@NBOwFvy)mK_@p&f8yq%AKkMpO?-G5Kxn9#Wr^tnxm`-}#S&d*M=gFpe9k0$(`7Q2MqEwhQv!G|_0MoBas8!m}Kc z)%7(~%+3e+bOpQN(@&0prFVdof=*nr@0*u*l(`@a1V|tCC`{)AuKX5v6-Lj_PPXOw znKolTy93yOv#akFM%y2~2WCzoaq9Vs_8V)<;`!Yb+I50)S0yd<2m0hnb&ulQ+}vo} z&Ic8y(q|M%o}Jb%E(NYCt~Lncy~*|kcm65BeE!TM1lMz{XI88Of9E78;Bp@7oI9u@ zRP_i{>OmcItlTVh;IThSJ6x6T?k?$q$`jKSryoChlwCF|09Eith)vCe&7iGl8|Qo; z&$b61ZxYu#$xbML-%rKi%xl2kiRsxk2@Q}AsKlL}p2;eHsfj{vl|SxKJv%vQThOrm z-CbzP1m#_XR?N4hRe1ZFO9cWSzxGA#=?V5nR|c_y~%tNaci5$Rm7{j9UB!745)O~m0q&sEEtDidz<~_8Zuy#x^P8tE@{L3fvAxxAA8pr9b z-0rp{De9v@*D{C?_79K0ylO|%7W*qOke<5WF*_%r?ZVNuBkr0RrY=Kwcy8CO5ErPMI2J^nGUnpp5<&|lI;&Ra(*!`Rpq z{+H>u9+$YdxDVJ$!7;`;Xp##TROsAdvQQWzOotdhZU@$LvvcXUD(K`# zJUTApx{E<*2Whek5ab;^k}v!ra23Ax6Bp;GbP(3Uv3A}`?hDsTwn6!oF#w0qvlH;@ znEojYY1q(VkHn<@(za5r+4`lhj?xxbt8_H|moGb63*%CDA#3LmkGz*Fd;{f4KjR6F zm{DotU5wR##if$L$d`?flYK*lTnip9E>jsRzYl}F~u ztIfiT$@c(=lwaA9?P2@7Xqgcx3jo~tD$N!jv)H4197A0M-~yJ~3177Tls+XLan7aO zNhPLv$tzecl~F2+CV=A>e9)i#$-iws|Jl#mXP?#rgDu9It&I)FmnUuG>0@a6R?7W@ zAN-*G=!d`CR@d%<6C?BopkZ6nx7-0ZMP1z4K15xXmgn2N;|nlx0SFBO&esAp7fGE$ zlT{*Gc8^!}q$ri_!nqc9yF;$*j&0H>mBTwb9(T;R2A$DeT-OB8?DW9w4)s>?HU<7! z$I(&g8T?Skd)US*9o_jTPPt>dr(5=a`>?x#-3h5&&-U>YB^MKg)<6(9Hh06@4gu%8 zOOtJNX@+jjNIRoMFC!987|bBklgt7z||mxso%_3DjQQ;wZiU*@WZj`^$**d^+|bxxozYI>X;pSJulR)D3j$|5`6(B1N1oD`{Xa9nU;47GJ z2-Hg&(?Kn(JRo3D_qM&U)qeA{U$p1H{;a)V5a^9b-G;$%m5xlkgHwO5?*vSTXDerd zBEv56q$~L+s;DDp3%b|A_z z0uIhFtb#$~>eX|ZS(qhPImqxj>D^-D^YF7rQHE){Z2o`4*dGK8?KKKh@SPw3uzmQw z@3vRK#p6B%qbpVeH%gtsD;0kIu}&r<^W~9(GFiI0>c%Wy!Wb!N@rW2#Ex!PEQ5gCF zPnBkwn3BHC_l&C`X?IuM)QUkE91?PHG^0#Ur@Q6L zDm$N!>37?GlwdGYP9WT+=S0W&u8uWsR%=n82w-4rqWB|#Omvi>l*u}~a#Uf0#6Q8{=?G8+d>18!N@TkcjeS>;Oa7BLNs%7fynDg$5W7V_6ki4yrc?*5(m9Ccw zA>p+X#@$_a=$oUrMqx%)+v40ZOgWPy8Kaj(8W7uRL0!sTKS|Q`$RKnu-~A6S-OOB% zM8fzT(}lJ$ozu-cs=$~&9zOjsbLD1!d|7GDAmR<9SMQG980A#u>a)=FWV;Jc@7^E0 z66V(qubV!KKYb3S{ac~Ihc0B9-a1Ht*d53%kEYtK4>AZCle~0_(T-pK>z&YPY`+QJ zR}!bb8AAIibR5LaNB3LxD0}(p z<78yev~lDk-+cJCE#ub5uebi4PxnobdX*`UGM#%LUx&bnv@6Tk%ce>61nqOVkzC?x z$yfgW`G5V*9d-D>`ak?%C=v+5BkUp&bOH&D&cYCQ4r#p#r0ht*-HEESJ1hLVHp_5< zyM3c}3rNEiQgnOsVp>5f+Y&CcXWmvv$B_*-5m!lRWC`#fza# zp0CIwf(_oTq;>q(t#%EoEKwlEpBZ5WlM=p@Hy*Z=uKhxnOjtWV>*QEe<*l;cG+D6G zB`z;z`U?LP%IIEos|j$@=G$>mfr(`_j62KRMKV1*ouiB<#)sR+($)DZ)>X^AMUsJ-hDU1VwEQfjPE^oKz`og+K43;iK?W!HxA->9x7J6@E#D1jZFjyY@U#tFE&ObAGrZEw zfLbuxOW6uz`6=o@XJ8mB3ZT}NDg^yue-EK(Te9Sk(cwm^mgs1J5 z#=t~C|+#RK`F*{D^)(V2%<>dUvBbZ$HwV=Qf_-W3ludCRpO6CmqLyxQcH~;!yw}%fO zw!8Q5wRhitKW%T4&s2`{g2y>(YeYJYa+{NloVc2+4IHji3>=MGoffH?_u-P_%#|JL0t zo@ODuhdg>}6#QpC>JBZ9?P7lvuX4W%^Foyxx$B4Y(lWG*&6GuO;NIAzX?PMtDG^r| z=i2f9ZhQF2Z*p&-b%^o}xZ0ns$2jv|k9t!8?Ltr$i_1&%QP@pR(MK33>U5D;?FiU= z7vM2{!M^Fq7LVanclE&hZ~?v<`*5hm38g%8QK93U zw9CHaj*-Bg_KKp97`i*J>J=#kmpXzk%AnyoVdLz~9kR#ST~UiJq$i$)A#CX{z&3*U zeR~6!b|sMzvSXT`hy@+fKIa(&A!!|J?_~9m}rZXB+FGx6)>nGImDCg-O!A zLtUeEt}JKKig9ee`MHI5_wL=K^Xp&!Dr3|SzyEFOc*K~Zg5-7-g3^9r zrxHeiyRhHi+t0CjU|z=TwEOTFJkPDr6KTs8?IhX;VZZ?Cg=pia_fe|kS0NXAhTV1* zZ|rNfqdVtZII^}vyG@N39i>g>r-ZpOBNwWS(MIn28XE_;w40f1?;W)#n~eL68TJ?J zFKriJ%+Iz~QRX{i7j58iyei;SoC|x)Q{zeTRrWXggf6D3ENp3cse|jHuG!TZp27R@ zNarQs4N$ly^}U(k_N^L2`D~ zG2nYo1_}f7)TVjgYr| zzdHk!r^yFqCl~GG7$e_SJcma!-eMf`bf>~wX_kFbrKR^pt}LtES6S&Xm}6-N6^imm zD!JXg^ow8oERXz<{csYV&&4kz6Vs91y@0N|<9~U1v8}G%ZL@QW=}Ynj&*2Z;8Rt&! z`)l--yNm7Yh`vcd7nT;_2f<7D2FD+Fm!4k2iyfc0J$QHVRmD&i%)^t}Zr=Cmf@|l* zF1pE%V(?MEO@G50$F>_Eb1}+zo088{NeNzz(s$eyb>;Dm#Fw^tOr~R<3oG0~Eo|+F zrHEy$1_$N8Hn;b~E4iRUnAu+T@$_?$Pu|w{zPr2tTo-a`z-OO5hA3aQAAj%t_T6uP z5M|z{k2l-1Eyfh!=HhVMspgh74|1;J7!*F>OuQ6dEh_vB<#p^92aT7wJmRr;oGp0A z<=Cq>^2(#49V1A!x=QF;ZyYmvBTcJsF}%Ke_rd!OH_c7E=H|C~4Zd&MZq^gl#SM>2rB~i-!^bw@fy54tH0%3jv~5tG795W9RRm3!GZA9Ss?l9rpc@Ssi2gp z(n@$u7dB}V*KTFnw@5p8gIPP%P5dgiQB$78)D^>r^;JNY&&0LlygK*5qw~K`h#&2m zfwlXNNuV3Qx>VgwR|QS%_Vx0_f-SJ=(n+Qjr%&VaP1VY-r5K_FWfeE+QK#$jcW+F< z(|uoicky_%%kui}5y?2ogYUSIwpsXLzAs)~G3cMP9hli8?5`$9+Dn-h23?s-@8%j} zBD3-MY5UdBe%3ZWdE8z(yXp%-B_znxObiy7pm=$!m%aK-O;14VJ%8C9I<+#&d}U_+ zwoJt|0}BX^3~YAxh|^@yGY~3sEWN}uXS16QaZ-({X5t&p`=E^H01<(alK~h-CndI_ z!mS-9EfRPKZ<(882JC$pke%%vCVr1$KADVvMPv3oDE``wZ3qlz8N|N#qaU^VAAZ;_ zROB#d3X(b=L1mB%9)VcQxzK#UU@SwWpUj<%hY)mkm*=s|ZOQ~?yS|JjIB^18WHkEY zlw`sp*a5Ci9-X9m)WqBZ3X< zmoF>R!70n>ZYnD$J~+v61(xZF12R_Pge!JUFOw|lB_lFQd<8K5q}oiAFZrE<+tvqc zBOiY02Qr5_DvHK*E4p|4<>F=DhBN&VJ~BZNZ^B@~_&6z}-mVVMgp2$vlPg|KQ^xxW zH}SK_72nqLRkthY4wE&2)<#Hcd483N^-7zbn86QU%4U6gS}fk1LScXX-h$wTcAA*8 z2JwVHVV1l!SSr0rOFE`qH?r{8A{E_E9-T2fVf9P+BvJYI#o<-PumRvT^D=>?sej`6k%;UWVGZP?(KChCR2n+n9Iui>506BQW0jBpYlDA+cIkEDEki!L z`X(H|=21R|2cU-R{Ea1^xY(h--Fd1FD}>{F@e3H-(+}#O?<#-tGi(y-%V&D{8?Y~vVd5{&=v?;l!AP_Qp)}X_ z9v(h7V#K#Xm8rbDaOSTsZq+3GC7?fs&~%=iwfl)lo|Y-)toW6%zF4fIMedBweX4%h zu9}{|@SRkEsRgO8o8>Q;e8j;Y@Pm9R-HvGRq)uh){K_O+T)VPh`M>@@zDdQ`zj)>S z296ybE203%)xVA@t^gjv{Uvn#f(fJdySxCl3RqQ$xopM-50?D`+MP)`<3%3etUyGZ zQTU+HR{@kXKf8z>KdEKtynZC&E)!RtJCS9eA>6C1R#zBZJ19zcU_MTeO~+%19V6vU zT(sl(k;M~^VVFUCixYX#J~*1c1`g|LTn6 zSSe}Mrhix7e$+p#nj;&ES2MAn?J$OT~+P zs{JfS31-KFM=W_lgng1c317STOK7Z8P_lSiUJPST0mRi;$lHD;FKGWXZssj~JC4|Q z2#_#|MELYOk;8}fwXGP?%g&Dp1y=9Jvn{R_Kz>xvyHvBL3(x1ufq2d$X%QsgP(_4G$&n1 z*{PF90jk`!oS~Va8Ng5YKo5mW;VbPbo{*O?R-t1U5FznYd@2M~s4ZSANZi}o&5kbT zCzs%gFtaS-zwbcn$zK7n_x}kG1*f$--a0b|^m83|DcFak|I#(`aqO@TreWE9JC-WQ zfBAxWal6dXphwWJwY9Z2JEyRA652OK`tEdOt^}=DP;0*C;XQNH^!HisVw#z)`UAhv z2XMn9AHA!}vA~@%3$rtn<#rU59#OV;=$(isnRnRlGhgB96|l~4oy*z}+@a_lR>Den zxS$|M64GA`YaenKri%kr7OAMy)Pg?7B>FR1hv1jbDf!Wdpc$EG z2}jyY0e)x@Fg3ljdDn03Ss8Qu>&lYFnzTpXXY5y*`(w8)ppexMrK9OoDk#7U9`VN= zcXB)0g{xtNi*21T%D!r>^v!;3tbT4^6z0|w;>QCH;IGol-Bzi*d4e-4Gv^nV+U)Ec z{Ro`ET?K`>XPv}V@f1Rf|Lu1F{tA6{G4h+B7!5etF>1msdO8T0?n!)9vlLX);{|1gZANv??$2SqLFXE_W+tR z-p(kq{GkgS+}#_cO#19l7BbwrHNyDuyghmPEO+P zMjOztZ3~6$9+fD+=0XT@w&<1ZB&<9p@`5_KV;9~GIwt?Hx;)z++*?gOx1$u0Ur^b1 z6~));@?tkmdH=ceX}Dc7@!8lp%Hj^kMHQH%^c``}9o5nd@kQQ6g`Ry%Ug+$Ue(CXX zd+;$TA1IUPC5^Y=M9E5ewwcK1SnOS7t1C|&dh)qC`h8TjejfsOe|k5vXa z&R9>!B>SPe?cDuldF7Q2D{hR8-cH%(=Vx+Ur}!`K*}qi^Z)|P{X6|ZI8Rmj|`?zi5 zan5H9#^z$-K0ng^$^W_uSe&X#0o9l$BZlS9v7i=favO2Ei-GE@8C?pR-4Jj|w%MIOABT zeAHct9{s4y2oQsdE~viBQRgRTzz&>NmbS!L;T>&`LDpM*c31Ws{mL|V_fN8*%VR91 zlcp(uu6)adQ!WNMJ=|+^QzPw1-+#Zod;e}0-#vZ$9DZ!LefL}M(=R5ngKeEYaCRY` zqei4va|U^(nzOhF$zAf+-(wpiKNaUgOK*p^`q)=A(rWQ*f%NCc8BbrFwV{_P3gcb* zfDJuOmeBV0N~>^Nm+LUyw~4$K)^X!HtvA0l&S7qT^YQvO=JoHIJKZ#Ie!opIbW@4< zdFIV@dK350_j;>&TUu{3Unl(A>i5@SJ`ZO9^q>6wp`ri9AO9noQlb}@*^q%z7zi99 zC<57jyQszyQ7UXgn82F>O$3wlyR?lKW7@o4ixLMtI#*wO=EaYQmkDz`$rr~yXbg7U zgl#27={o-^V*+%Zg~+L-zK%*gpdys%(k|~r(`52ezU5$;_#0PflR$$W(#i@j;>uv#i4Ehx&x^r|L01J$H^|oxqMCfymVX8-1{GIAIf3XW$TF_3 z$a?tM!?v}xl?g<(%U{4y{9s(7{{_={n<4F6)N6?W?7KhuLA&?vyX};ET{3C4juDEC z3&UEqq)^Dof&I{xKPNm{T|+wALJj;C9>{PiTu{(*1%oxjAe_}ke4jGN9fkpvX;#Qk zLd09NqwSHlo?mFAFd7PPZo@drygA`gspN#o^S{MInQkxEb|sdRA>ovjh2)i$?#3bQ zLD#0Bws#5KZf6CM7exn0Xn%!_3a?yQ8o?&ar8p!L~dRMW->jkz>P^%heEEFH0|_>-p#jk!}#Sicn|0) z4rIlfP`r(=aTQTg!%go2{V1ZD@>K?943lvoPF=kE@iXzOY=-o^a>`d1$1i`2Dd}9| zhrM$c)TB$sGNc%$FHP31OSJn+n7k~Xu3cH`|3L=l(P4lw1GSWQZ#pPfA~~N_Z^(Q&=cvmD!-b70&kJ!?sA+ z$|Fv(l`)4zDBr}ZKz^6|p#Hj0u|9TU;9d&63hQtA@Qa(tn0sGNlkWXBsbQCPhkj-H zAUJ64bA2s7i6-5fk@32Qw;u+GZQy5ljMIneJi5AJDWDAE1r(SL5||2CcHOlRDajP9 z{pnImnZpn9emy3p4`(@f+xC5mz3G*+@-D{qt3nelAAIo+Z82a{?0?HeIOtpCwS1C7 zB@}vOwZmo&-2J(3mC8Am$};W7#L_~KhBw4mS9KW;C1`RLo+H# z_u+?(W7=X@6kV7I7vupbqhnTtjEpxLd8jmic&EKH;h%WK^`doU%-cK+TeQzUBH!i8 za*_ca#`B~24ae8IpJ;dpxOzO##c6x`Hi%l6Bk{j^=|?|FGvo1UL5F} z)Z!@gqBw1mvUog>!V`*2yPdbXCx~(ndjxZh;|c{-sK_h20LCL|Y-izRo69rgq=K2L ztP)qSzq#?8vhOFpO3SSDy*-@HqHwBKAJblz(RTI`&I)5m(}|tC;pCTG6sA%@zSuh( z++pPkWp}G=tZ%dp@6F2U;yS6o(+L#dDx8dPi}Dp-Uf9UtgTiOYcZ`6S^8U0@zhh=? z)gud+sn?z6(R5KP(CDUNzgU@{YIBn=P?BFc3q7%IhrzpF{^FNyoieRGc&E+6=Y8_Y zXAx-F$0B6EJw{ru+9>_ZBlEmJ#RYRGStac8K<;c*KzzPTO1aWn z{@6a8RoK8zq2#MqDz)}(o^gLFtdpzX>d>3l+{~m#+wBu*m*L<0 z;5*Q%5@OHOH&)kHL(6~T4vNj4&k_ z8xB)fg{&ux5w%mX=2gLK+lD?O-FL3$E))gGqF?43;w|<%@k9lH$`aC$X5i;tUhb5T z7Fi}~zQSqSMY)3GLXA;{+nH}mWT8VUm=%uO@0{Z(gtlD$m|@@?f_e3O!sc3$B&=oKFG1LTkWH7z1QA*=Rsh-?H#B4wX0F3mXCet_{cj7YY|4T zWE3ZaiS)?!a`A)xS_PGNn0c4b55E7M#Bs64##Y@Scme*8kB_t^`l#|LcgHHf2p>lu zJZFrmyB<%3B6#T7tsLVjeb~B$FQ6Q@xySiVP0fUkxXX0MBQt5c@MiWqafWflG7DE1 z)|jxnbUo79qgp4#Bb7+NSzL2m5&hgTq|Cs!bvKwtMXFfyNI?5hFV`s}HVlQX559uC zx6*dr1vWZTIGP3EhNJ&dmC$E-6ln#$Cw);lh4Tz)i!i#swnSUKgPpN~vN&c;058*a zoD^68{Lg=$oog!TXMo9vAAPI6|K7KY0>&}>t;j6nN8~=> zj0#lYsq97?HZwKazW?2CWd|c6vw*|##ohPr;M7=$9r^j4gWUCX1aBq}I0QY2Y|4cl z@TJ1Qz9=svp1NZ{_tKqHHqx-K^+$0_--SE9k9^>NC*Vz}i;I2sJUQUvMH_)%jgpMI zI97U}=`nte8Oq$u({gw(WGzUC-nq!nV=ZY<$HpDyneea6OVjNK-}$h;3r&&_Q+Y10 zyf`-%{5UvqN2r~@croi?8prT(_DzpDJvcsZyZhA1`()z=ObL_43*cPp4lYY;qf7@L zBaq#x+b`P0ofpgzC|^foL-)$e%-0G3w)*{bn9qZmim%&$`w#x` zCspWrVudE;i=PtuX^I$LTXm<4;WP*#-gLq8)|iN46D|%FzcVEa!IUQkhd!`R_j#SR z3{buMa@VKturfO3$>dvm=a7(Qn9l_0UgamFlNIGR()A~4cXH zbK{+ue)sRr&2nlFBNIPA`2p4i&!Kk3TgAzVD zO#mJlbp<@;W&5c#t(8`VKmG}`dDWR6}02Ehs9Ub)K7dWvhID=AFAtwbi4 zRJNZ$8MgOVpys!A%&`K5Gkp_DJj!i7z~Kb?cf?s~)724Ye^{Jn7sHDoC$Nzf!?JGM$`p88{dAgVJH3Pf(6Q>J4 zFe#fp<(FC~3_tkArz>xs`00orc_xlw@$2o@(ei|Dc5dZfabveo221`JA}1aH4HL)u zu5#6rG_-g1)6YP8C%$R>uJ7L77hMy$#r^u}+oI2_H;G@C3ftR#5wI_Zu~J6UDu?T| za7&ave(K&Q;`_Rs{dd_bRpI$s{e1fJ_P=`h=O^j=s(3sUBB-gGcHKIEosHAed2IQQ zV{dL)HRWAt_g>~P0ELE(%*)UT-~aM5Zp@85`jqmnK=tZ;f`VEsIhI%xw)@ta&$5_D zg-MKGqE!abzxqzXCY|eW zhVX0Pm7j9eZW(2_jNijNX&EP9orym`T|xyD+l|j8Rr%Cd$AdBazx(q)`^N70dhc)j zhd*&~h(c3gkaO}GYb=dpWCWx9xme<3i2F-iq~+3ymZRlXBi6tdhU24j_3P3 z*;VN>KR4S}SL=8j?@Z|LPxA6?@6a-w<7>a0q7)uJv;m0*Kd={0nvV~Kv#nDOaE2%T z76M}!O}SM%PJ|VdRoa!VoSnNzESGmbc(=`?Pk-4S{pOeL`IFDG6XU&i-)VpA_y3^X zd*_`J1nlj#M-M-3&z?MP8_%Al&iCJa(B6ChgZ9z)f2V!;o$s~z<$G;(YPMaqJ51;= z+s@8j+u1GQw){ceGXZQCX0p>|frwdkeYGw`17GI3=#{K_3KP#@2@>H?pA zFML<9aITW>D!h*{k++Oc0+`Ot&$b1Rle<0AcDHugv!~CqD!Ps~bb*cv$%18$Vmd#K z&|=WXaL?Nx;3s~$LRx{T!XDif;>lmB_!`IW_~@Yh=GPwso9E$0J+|)x-dll{by3*l zQFqg%A#R7~qa776xZub1UFAIo&UiGO0=`A+FgrJ$9bYrk3R~{vE(v)%l__<+t9(NZy zo;ao=@f_GjhM#cYxB_B#hR7e2r$SwKKhDi9@XSZRdItWhZ1h+y!_MG7H8T(2J{AGj zKK;!jot~_N^BX&Dd-pK&A$O{}lV%hgv^=h&S6D0UaZ#8jO{h?_57~w}F#(z+@Ep^0 zpPcsCwu!*gol`2y>^JrSalP(Ma<|?k=?@2=Jt9;5KL&sHp&gr>>uvqnQ~EGC2`yH^ zEv_#u7kyNbV?6txLclEcJMNS|rc3+xY1;Oa%vo2KmfHOXciY{SrM3j^7#|*L=g0f) z^6Y>y@shr{Pgzgf!t7MLe|I&zR~2A;$MEpjOgm<3lq1`K>o&Ok=<(C`@X^z@w|79j zE})C{Gx{-Taf|W5`(<9hg}DK4?7We(|yleg2Mp zl{Ud}m(KH|9m}+biyjo#2ZpqV$B>mm<|Kk|aaX0m7UPGD8eH_@eR%Hr znr0sF^#Cp&aTk*CR?%ctouh`10e9a~T2NLM$ywkT{-)X}3JdF#LfcpIBMqsYN+9JW zCTbee&@1UE0j#h1AbpYsWdSH@L^eYFlB1}UdC^pyZ*A{1cYGPgog(%Hh45y!yXVnw z_A$mIXpr>11pc^*ci{aH%7*{djRbB`MR#lG2NNzquxIAD|=TF^Ln zEZfBPv$Y&Q9f#AV;I7BVt**?6x3Ud9dQbWvoTgs3wfN~+p_1LB+mvs(D@w(riZ}Cg zJTIE>E;x^^QyJyXG}<3nMD{>HVei{^a3QsAr4jo|0pM<4c}VDV;0!EP0x=${j8u7~ z;?8y#KUJ=|GfY0u-D$M|!7_Q87bS*5dGG5HZ4X`91#}WBa`^w?|PJ0EdyuaqI8wH)IMj;P3USJys|xW5Z;7PY!?4c^at9@#o zU_ZD0taB|4a98nI#?&l2q|ZCYDx~!#?Tr>RgVLD6P!|L;|iEx9z`b@|Qm!ICXGklwyzj{Rw;$zxc!Anz*-G`reJMiLe zC#u+G5~lm^E7`qn)S*I|YTUZ;y6NA4mr&84&X;%T$@oiJiBg7lCLM7goSyy*3+?HM z{_|(ubV?W=Kl)$39c&WD&;H>jaeIgQ$-6%JjbzBLgzW6ySMS$_>xEzWt6;ouxQ8HE zk1A)r6Rv{?|3E)+Dm`9$>)}6-b#{fe_aU9Y%pNijUdTv{$h0uvkmgGW+$Bu=?&fBD z{_s)Tdh)DY9F+p3H!3A$XdJ9v!4$>>21R8+F=igC=ipz$qh2v(*&LWHO4>Edi;uO| zv2&*!zO(WWf4>dmckqie93+k70OBzfefw%x>CrRrfdS!#hs?8#jk}m+WMq&OHspAe zZW3K9!@iyg%q>i!b_|g9uztSdPdf$YtOtXVZWt9&759yNaSvSZa||}U;qlQnzqr_@ z8N3v_%WPRs!$bhaV;!C7<+#Bh3+WQ(iosXKjf@r*%^>C^%8OWYd>;c{COaAAJnEtt zKmnI@OiBjN3o#j3d-f{rqrdr5FIOu@_{X;}w{UsITK%xM2R8zvTVc!sf6Gf;Ph{? zE6ZMK$~?WTlLic17bSb@kCfQ~CRw{**BOCqhD)R&V<9cduBA z+F<2%UFUMR&YP!z(&eWE=0@7xAX;Jc?!%f6W$xqnu3-LZ%BSGqC+~!>`1M_(>)Rjg zgHjCKDs6uGPW$#{&P$+HSYP5+!MSrtKD_zq%Wt>s-SijqTFt}$V}T0h+Hv*W8PU_%k`v^Rw!nv=iBgalyUMvkQ}${8I2LBZkVPYhd(GG8L?z z&hpy}W>Ukr#W_~e4Nxjn`Cs?7q^rIA9fa}Mbo`68FHpHtqAsM5zxCCn+`0DX)|ZP% z@0dPB@7#ZP`E~YdKJOY{ed-;wu;63ed-(VMMlgu!nU2mCpbYjb6zJUY)@nfg;!M7# zqXCY8`e)yq;_FBMqyOk9Do9+VsuIbu^OP}t=YWYm6MTifCl{~U_5r-j;R%ypSE0M$ zfN_;^!aBREaeZ^Aoxm44`5t2uoE_r6ol@{*GaKVzRcURYz+x@%C z?ZMh&ySp-izcw3#DYIg&}YWMJ-0NT61JRzv4s)Vv_6f}F(ol39e<+%s|S9s4%xpG+no&xNbq4(zPt^{$-3;*5u!hi78u-n^P z?dkK490hgx;?_W@=}|`tp`^VkUR6BKOsmisiV$9bj!NDfO$lGUcLc2AHN{U?I=ho@ z2EKJ+aiPu4&u5{Wa}LX+5zgNCDt~zUw!+!sEra{yDLlegcHtv<44^iwuz5CpidNMrX>=*@t9su7sM0$ zl;)*J$@5g0lrrwMqmqZPDyT-~{h&7^qZ734M4OqJ1=cgzy<=#SFcT5dxwvpmh8{R+ii1lE)^AkKhTo=y8c;-rQlO@a}N`sO>}hwzl>n$nz*c z@1F8L8~dVjBZb6SVUE35I=Ilx9V+flP|&PkSbzIqXb{g8?W$tu*|VqZ>9gli>X?@& zZMgHrU6|5hg^SM1R2u9k;Pco|`rr=p(8K**=*wREdEl%SoQx`RBkpQzmOuxyw zHoLgi7T4~#iK#jI1LMh=ihvi46Gss?3a8D@?e>&8@-}eu&L$OvDu#1k6nH+%<0^go zj|=h?AbM(qiV_uA&cUMigPw@M(viXom3Vcuy28x!Gunc=nu_vz_OnauG72zH?KrOI zjC9Z4B`9rDQKuqmEc8O03=IRf9gFI|H0ON^_uZLQ%E%~m^rP)O8KhT$MQPFXuV69n z*u{6s>@H>Vj1ZKuQ+%X*(hrL(DZBwM5}ta3C)E!fi|pIfo3f>ElWz4FSqb}pjkS(* z_MWgYykiJ=oldz*-xHtEksaV~7-LEIv-q(JM=)uLkA1vTz>t>VO(C)c@)M@Q=Ujnw z6jep9l4E{Uh|~_22&KUf1=a4Heg6D8?{#R9$NtqK2p2eJhYNM<7ilVfuvk@|Qi2Hz z;pLcIbkk!1#e3VNqiuOgzS1jka^xuO?veZ1Sx(bh4DyyX%p>M*3C-9(8WE|^g zuDfdX7z+=f7mgz;yuFLb$2iv0-60UN?1FSops?IJjxweT9OdR7M8)EE9u9Fmui&Z@Lmq3=m9*+ncT$N&KU^hrcPR4pYA znciR=QFf-1%eoc6mbMM->f8S2w>VifJLH<46&@FroZt}z~>~TDicc}Rq*?(Fha z?tn56>#0)9{JjdryT$I^dysqJRD`-X-upFAsf&EYn0W&`cVJ0_7ook23*ZgyIn3A} zoDU9LjOw2y`=CG29=WpixAUR%?OvIb)GW^13)mMP$*! zqAQNeF3>n*?02kJY3O(xT%laSHM)a%CvKRgira~a8f(Yh_7&x`3y^H&!rAUs@q>Gv z!%d?bPeOF|IOn%aAJ2EsxAot>d7EAH+ut=l^ybUMzy95ux4GXmUlb;_{*olVN*-@B zUpMYwCa*6tmF{n+9mUt*{sR?Xm`EnNK(x<5IH7Y)$d@z&(|PdH&2R!0uXug5rvSKocwaWcGhGzg#7>Eg>@mk&mN ztqBvCfe(IVOAyn`+k%z758vAo2LG;BiP*n24A(|2GkBN37YkCvJdm~AadCKY+KwT3 z%xyEUO9b8h<4UDnCcj(H*4yUO=j{Y0ztiOmjDxZSRmRC9RU~#Q!5lDZ@RF%=1&3He z`#OkcV6#XyiLKp0HyGOf!OgG{CV&{$-fCn;SRr@$JJ6eE7-XAt%1B+G4l8$U<9T*2(YK-7*eU`cUB3)|d5&-0!==AtGZcoJ8e zPwK`Kp&L)Rl19S1B1R?`=36(M98{gqCtdL9y6x-O0Vi;l$(49A9$_p6HYO_)bpy`X z`PIQYySHTE2xGdI&U}rpo490oGU@6j2f-`+OSx8fDNbs~xyox@`At6fIiZrdb%IfG zsxA(yrsZx%>kV_&E(sZM&*Z%H}U=Y4;I!$yO7G@~fg)zBs)e2K&IN z^S2FSw8vt7y0lCr|E7nfi>P1HzwwS^{glBPA$;!?`e6aep=gy1cVB>;N$@j>*hlHh zWZWu>L3HcgZ@jQnc*AK+8iO$Pr*GUVP@ay2l-+mdnY{W8`|!LIhDep3Cb476jbC3B z+B(;_DGcyvFh8;|*v@mr_VJbp%w;-~YkcV9ApyRh*S25~Nv^t+I; zSD{kAI6@cnC67!)6C@t5nM%3x_P65pU#VhDA0q#8tJ2vXg=IZZa32KKj>S60&3Bhu z09Uou=$)Dy*$=*|O2&ypoWIE(Uw`9&{P%t`&SZLqN!R?$1QRaL#y@K(=Z-7TZD{cE z`Kz|If0A?SDBhNyA470ex0zkoJa-Ilc&h z+Ymi>)(kPx>sMlDj8aGwWm4_xn)hfp1xJ+AJCH{16wFTC0Qe~uP`FR6t( z{e+&$Ib(WuH%Aaztx~&U9fv$-7+#G0GKPoGvOOGs<%@{Jmt&Ika$!jnTpstuF~8 z9v!}w$@$c{M^WC+j;;rH7uwzBxi$q~Gmd{9PkElZ#N4sq*i54~hWK`(V1&u~(a~Ak z*;b&xmEB&#u@{iIE5nuWj@t?dT&a4+_w)7V?fK&;39q6=66qN3m>j_u@OA7~NUqV{ z-6q-nGI&PY@YpagbSKt)@Iyh3yh)BCf@gLGyKVVQWx&o3ehS`-PgdBcA}~UhJMs!1 z(^djmd7sZ8pR#mO#5aBzGK9&kkb^qvh@@z#asw(0crcodi37cmZwcueKE zd=}5n?q1v2+@g-ubz~BJ^!TZ>@QK?y``Nvq09Az*O&z?I?;06)9xw$Qr{RCStH$iio7 zkN(A%83$k9Me7J7Um1Q*XgD9hkM{8C=~dAz9;5Q=h2-+8_WuZ#6W5$8PxB5B-<3gA z{2{nP8{L-2q&@XkkZgJEkLiYae~|ttdHFXvj;t0L*q$fua!l;loGmGy0voh=hwu^bztB_J>DDZ96*- z_S@dhUUovdJIY;=5#DveLyuka$SuR|?$*6pek)KGUfG#tn~=BtNdDcv;ha#OUD~3s z(OpXl{kOKZBSce(o@TXmnBOQ!Q;B6ho0}VLV`IH-Z*Eeqo!oKvB0G)52ZhG;>r?MB zIc%Gxr_#y$vE04ke892I{x}Z4W#{AkT$`L4OMg;fzq&NvR)DFyb6nGf*@7Zs1* zTkO4X=S+%^FNSiz+2+ncd-Qapef-J8_UO@ijz&|#=IVU~=I6wx>TR6%TU=Tp--R|$ zzCM%F(;0Vc7nM}f0Oy}Cs7K%5rI*fiL#M$D`*-F$;E8~WGK#*h!ld7^_@YxrML_9% z1A8e!YA1noOCxS(&P86%VT4i9E*A`{jl^{C7agQunx}Dj{7c;|qiFy~ z`)~TR)xb~<9`e?m{H%*g6uGEEWN-j`fzy9cRu{wQ%QzmnK;J%Bv=;gR%xh7$wAlsf z^2oR8r`ENO_PoV-baAHqxOh5#{7+l;Z(ZtLrmW@Ghl@)WChwc}FL-O-X6NJeZ%lo^ zB|PTKzI*dF_nYR6!o=@OlK3ilyv=;wxPO_vzQ~AApJ$@@`a3GVz?leiy8P?aAw}2e z^W}dRD8F&yPl^!-!qO@HG_h_E;7?H0K%f* zT5UeU&->Q0TM4E}p`4RRxUf96>&r=*E8%7AO7SDpaRpQAZZC`G)@w4x2BQe$=LFBm zrh}yTmY)z32j_0}An9ZUF7>VnR}I?Ykt?!l;y_yiBiq&qp*SJaQiHF|9_gp-GS@ZH z5YGJsLk82MJxVx48A(5koOx1TC+9UOEXL6KhvCIV6KIoGO3vFbPKJboI9H6S@TpZ< zLb)bB#Wef)?Y4B&6*mi~3;)w6#D}3;A*6y)W4qWNrp6T#O;+8-9X*MoMUa|bKJr`n zl^sJcErT$LR`$*%Ka~!TRqfn$i_jaF>p0yXpB1L;#aB8`+z2N!`ej(HH`3OjQnf(7 zb+15%(V94MyEgiD5Qs_IUAm!xT1+qPpw(0jWPm=L|Nc}z(<{;ZO8`GiE1?u^m7gCz zG2QpILu>;#|GTuVp;tcx#Q{&{tDBFua!Kj)&o}OsuBPJnj$6khRC;B!2}Ruu9b1>c zb*K&&7(*4xbmbxJ%{=-xHk_uyNbRd`8vP8DcyYRRk4M=GO=7R_-c(u@t5B(rSEet2 zOlOZTb%ywS*WIFJDs7KC{L^nt@%116&;G$r=Ev`}g^7_iH{lB1 zIu6Gbs#(;-7~s)^?goOOM{waWVNQCTG`jo69XgI53NIXM6x2RpQu^7W$60wQf8fFq zm0m7jafSbtV;M;*Dk`WmJ_$#RW4*N8385=rT@mRjdIhmgUXPAl_3YXHr#X7%=-7J* zYT~bODXTfp6hhYua*rKR3E@3ZrTD6GPXUJ@&yH{Ms@2+#ITa?4?F6lKOm#f7zVd9| zX)rhEYFv-Xn*~-c+Q#~mw*K^Cd-nLV_UzH8ZR5#jZS(nKc*DnS8@~#t2wW+zeHas?w^4cCz009d)l{Rww zRl7LeZ%;n^b=!UZs2%P+=UH#JUY@sinee}Rcd3n0w@cv>MTvs>qqcW+(oQa3w9|`M zdAx7r@W>V9Cv9_cH^;+xtdI3~%no*n9GN zdI7lzF2&v4hokU!Z?7GYuXhRCH($NylBOA6{|Lxz*A5?i>m|=--;md=wD6~oXB^Pq#PTCNtH+ly z3^*dMYJZ167QaHM@e6+!ycmbRjAI|;O*`{;C4Y`Oa^QU; zDuF$g?<_p5?PWQI2PhuFTI~|4{whqSI%Tex^(#x=v?-aDH z#7ki;{h0uMSulv3^Dl+`E_SegxU0w=S@Z(BhRUj%k3>EpTPn5^knn}lAIf%*E@ zST2I3KEf>t^4-_1ysAy?t9m^t*Cs8iE#2@)NEPGnJXnL? zEsR+(HuCFwtR|o*hLR2>RlAAlFHq~r?jUF$=snU?8Rr>!yUXwoibG3)%?i3 zoxu|vLNhnFciZDdQY<6Z)REr9&H=EaD3?MOIYFK0(bA|+N1Ao?jL0=bna#!u)Y)I>+#srQ=WF=BKkWy zy}~?Z>02Jpm@)hgxEA^*&dUcor?B5Z%bZ)NpdP-}F3xBt#1>`03*J@+?Pw?4afLn$fL`Z!PoN2k8rp=^3*4>1-YHT~EPN zr;3x-i=UsJz4MP7@q0yF<^Z1K6mc6Ho5;!S|jFoUT10DAdT@_;Qf$naeP@dZrV1_6~PrzhOGC z8)w`BXkj6OyPEt6Q{gTAOAr&roABA?1RP|ngzFGlWpV{9oQNria2xhZ>aB1gj5%Rl z=`jlIt-eoEe{jD!?Qts5Yi)Vm}uRZSZ z(>Xu&##Ed24-Nwul)b`N`D)D7gI^m?zXUU!&e9IU`zlQFqteJn?45OB%DW2}TNf@K zucu?(Ek|{&M2rbPLcl>-Lss+z2_K+Oimko-He>=BL;j=e`UDi(_)ZYv5&zyTzJ4T} z^^aRVe34lpoVHlY|Mj$E`m_mINmy_5xQ-LUJ9YFYZq@GPZMY=W)uVg&rkoPh^3+#i z$7cO2tNa8m3E>a6lvy|GnQGmP7h7+-uf*@`%3t^0hcw-?_rJb-{~O`D_e~=dst%n$ zKjCjM9mvb@wtRp34et2*pZ~}I=qF>0Ma;FBh`HlM;h!t&Yw>|XRt1c?3kD#lu(Hf5 z$6Sn4#qW8)5+*6UaNNmCP9}(sr?!trce#V%;>t7q>nNO@dGEL)t~2Ji3)^ut_Z{Hw zxZn{jDgeCK;(&?&4inwI19zY)Fc1$2NBWLg;b-_3j*de)f|#*eMS!iOzk*E#Mj3yp zqvMV38(|z{k_$}afpl|xbA0x=Bq!b8BQ`%j%Y=8lc}JNFug4ERX+Qh3KWU%*`WJ2e z$)mQnz0nSLw%X~@evT^itp1ns2v=vR&k)Zm#(7t`){%0TOqeIz{d;%Y@BNM6Yk%}V z{G;~6-}}9`eD7Wayz&MLsTH;Z@*D|s2c~3%cAI9xJjSp$HFi74=*>@!XE)q5^_$@B z{VKou)vw#rr%!1|kM^6*J#Du}C*Whp+VS~|w!K$^e%nVOgm4yLUB#MvsU|1FBY6am z3%0x;NCB99$=+`5OmUZq3sOSw*3Mge&8?3Mp|YyhY$G3k?s@!Ff~x!i1~% zN8mHvQF0aKl!7OD26;B)djY?Kew85J(=|Fe9{iF&Ea7AcQY(M*BW>%VfMa!arFrL> z$^jK#;@RxvXpWe1N0#L&WyKJDP2rzMrS0!-x6P+dniriY@t(A?Nf$QF0t@;B4JWVb?m(4W;+6{Hjm@3*@X@2TvAz!9R|2VH@A-0v408zu z`Chhu!1u|?ap2nvJxifbbue95Nvk|4#S6T<3Ow!b?h5dWr!B#(a4hP|FKKmPOFyzd z*)|Hj6av|XB81+d^YW2|Gkgj0ZNGwdDZl8`Idy^1Nl(GCvF(-i*K*4Pt|+KBtdu$B zFdy>BVlH4e>fL6*JiGbC4|(Q}XIB8{jy!h)-eI0J;SNmi3gKHp*2>yyTU)!Ebm|T> zl|SAaBTV;7I2n8|VW%tcJu1oFt=_Np4BYk@LzO^Fi%aPbQTl^lFJ7EyoV6S|77O~2 zhkiCeKlBLD#l^*T@9tWA@ZbUQ7ebrt$MPi3{cK13hh>WJlsTj;{8jYV9J25}ynELU zR3z5E>tDBD{Nh*O@Z+|*u^l{B0Vm#6|1(ePS#zA6c0!+a z)&I==T!hOzySwdhf1kG4YX`iYV>#av*K2<0+=6}yOnj`f^Y1Lu(+EGpJJ$%U2Mz*C z_|=@lFY0Dm;Z$=BDr|hAx@7j6qBI1kSh>LdY zyYAZC+1ZYw$P;tKC1qms(1oR?r7SKI#>&N1#<^omxkm6&B;h4aL}nFuyBJ#<0WPWd z5ACyEsysceYSKoug*Lm1G{N>M+O5pY@uTjE%pwFAAb=ayhbcqwr4(+~t&TY@8th3( zDww>B%yA<-f1#f)rcmiA_ISrv?j#4N#H*se@RN*hF66Lnat{`?6f%qZWZ*IB?l{^) z9?5U{Ea5GUt~=jU(!UD-y|ldC)>c=;ugM2XUqe?NBdj?;#utYJkl?aoOu@*pqrg@D zH1O={w_`AUTWohXp$os{J*H_}cR`5@rY&r3FUM8OsSL}pZ3oy0M63aSRUKLH^Y7}^sufGr2u{Zo+haa}R^-uvNkLMUCy&nb6 z*GCL?_odR_wrv*rJ8uA<@>sq-3UQk@dA_yRHg@*g`p!X)F?D_+n2hUOLIu6Yw2F83 zMU}`)i!P3%PiFCpCsxo`>GLZ~b5R=JU0q0j%2AdK7T#%i0bZ#L7si1<^+{XVB6(N4 z^ya2po^l?9$@`}L3*MTy+4*?=8<J36FX6yU^`*x8A(Xy*FRvAHOe-{-x=Ek@>oD z|1x=fk$GFX*E_!WNFe&K;I0TAQh-SjmJ~(}I{&o*rNU|wJz?`1B+Q5Zz1s~>ZIyQK zUQgV*?Bd)T-F4H-lktToZ~yuT$+!ab`RVV!W>8LFoxMU>rv9%yvD=M{uQQk?!L;U zOz&RM#MXIMjS3a=+ZD>ZRG50^vv+%CM1@iHc*8x2+=1JQU7dN%AP?bw0ii6D$o0lZ z#B+2B48};b{Y>l_AbdNJIH-L3`wOYk2gof^Jij(}LwpR3pF|aLof|E`vh%2D0y<#0O z55~Q+%!DOGmq$&Ma12w_x4YP5y@ZpKg<;BVc$sIzIQh?!l$OJX@R?i?F{{Lsq!mSvCgjbGo1&CArfK$=)14j6!8khx_}g56X9c@n1k z?%~m=UHQe@y}E$i%QglT%DpoMoz8Um`+Fm`m^ahvi<%V3egJp>cn5a*2CJ-#{&6Zx ziG~t7F2*-(zLGePxY=3zc-=?Y;#VL34pJQW7i{Y|wel;E?%}8M?cDvo@nxhwXyLV{ z>RX@X*87-Pj#1FyXdCM1Z(Mcb6}-&n&H9!-KKxXiyv&!g$ws=Q^-U+3>Dew}-tM{Ianvg)J0ap>b|?Gmw!{%HpIPh0y+ zO0iVR`S0STuCe>*?~@)7m;U$KTz?y?FKZ9m{F#={ZId+|MVy49>?n# z1MT&Q9qXu2arn*{B za?Htj{Y-LQ<@xCG)8>&rj#I+kv82Yk+ijRM;BGPrG_ArFS3WbIQr3RlP&wyHVpmG4 z4Ddc0-(K9-~HJaW(- zH5X?m?O<=aJ$v$5d-&($kH+u3;5c05|}(ZlweU;VoM=HuUF%$=GT2W?+Qz;!`BW7Bi+tasXp(rS5=QI8rL zr*pdM+WS0SGI>ABogq1f2{cFxDO(9ki{@&318o z9Q<``Rv7F3K-06c@U^b|y}=9c$XnTV=|{A)xG&EtA5zK#a4vr@<0k%;AR8V8zSEsF z?)DPzviOXirEo(5hyo3TN=vKD?e5xI^GL|t8#FtOeW}gPyOZn|@HuX0Cx?OQ()?7r zw>TYzp~vD(jNWOpz`)hI6X1mkVIKh8yz9b+LhjNTx;5O6FRr54bp^M4N*khmm?(I3 zl|oQ=BzZiNNAKNRTW&Mtu`uiEU-}kEtuWAgCmugpZ_hV(+VPn@w!%B=N?H@N`{bCE z^kw>rM>$C*6#V7^)(QqAbfV0o;JXds9Zo89qU?g_SD6zbp|}Ss^uj|GA@Wkv98DA} zwo97DcIj8fTQA}yTG2os-Ga|udxqzP2FSlD#Fo!fuqS`2sWgn6Pu_O!5*&y7?9#OW z10@AI6KV#~0e3v-As^3SRt(@Go)IH{I^uU1{&WbFY2-!}r>UJPN*g0etTKBc4hp$7u7702jPbfbQ{RQ_wG0 zysKcAx0Qz%)*h*TdVJVUkGf+nDWiQ~eqMk1auN;PlP>N)eye2c{d#3%1i1usH^T1j zL0jM0YCF{Rz#WH2?nWqqs>(C_wSCMZS>5sY>8HPGPaZvr@KV8MDb_lLmpDL~eXDSv z^;or)<+i-C+Lo4Az}d-mNIo9X=*|Tf^?7I58TInMEtSnGBRsCkIx1j1KX>7!JKT5! z2a(yfqvF9ih1KGp7(`PA7FAajKa4~8yO1MB;B>Fho22FL1ZlMjw3_#d7t%TvcjBg9 zM1=MJIp4v5XhYh-Z^tMe{XFK%;3*H`G7rKHFEPCG<)f}tC}q3oZ+*pw_!BSmE$N$A zh*G zn5!&yUL6<|NK!BBZ+%}eo|?a&!3Q4O&9Ybr7ihSMrH54%9F$4rhWx0zQoW0Fae*-w zdLk@xbo1eHcEP9!*`vR>dq$Z~?ebDqq%vs)`p>uv{hwhB_4v7W?kz{)?gAz2Ck|Uz z`5R>r)}vRRSymSSoZ;@m#D0g)6ts3$ML+%5zT$bI-*e~FQWj6ly4c6DpSF{SRmtmk;;yJg;(K44e3N|1{$4FAFkclZ0!_J)I3#@z zJaMy3c0cPRfP{^1^5gauk6^5m4pgd6r+uVRE&`YKy4x_PD=@~oTU|QjVlm^JsC^*a zJ1}*(^0o4?WQw#6V@t|JSo^m-Blk&jA0AcQKRAT{h6adBo&vDEI2XQ0xf)4U-aMu) zPJ0JD1+hZFhcRe+vg)M+^%jrizoM9Qhc|f~cGtPMLqB(&(dN!wRLZ$?Z|{IUNgnQ6 zlTW*X(bzvcZ94~)%~KPwyHoFz&mLhv$b880etKpibpGj+NA2TZ{*p5DBukgKn@V;s9%-6N^@%lHWzTXla z^X9ka^W7}}^*Hf)=56i+L*ssFn9ng^CC=AP_b*b8uVUVou8OarfBeV)WqPtJm?X>o zi}0WafVDGpKn59IfvroD^M@zC64#1aauCzgy@D73OQn;v%5@+!$%~&#BR>_Q^XvWl z73rqn+jJ9-QaAxjz+|JV&!Dt11&8ah#qg25`5WZjrQNx-mjuw3oa;iQJdmJ-uOG`) zFN>L70R9;?VQ#z)PzB9rZ~BJ18AUS)mGp(RZJ|3q#7X(_3w&Y<9)1e;C?*p5b$DpH zEUQSGE}aVRQy%@7Wt1dV_zIQKCd5C(MmvGY-h=TzdwB)%J*_j<8RXBR^g4xj?zeLY zW+ftM<58BrJsCNL|jYcRx2ULn>F8l_j1u`+-tzjC8G=`4pM$=dM4Poy|T+krH%?NnQ56LkF@iciG2vT zgOr5c!8BX7nGinrJ~Lq8wqlhse_wZC zShispwM-;nrcxRH>r8Mj6Qv%(X%$n1rJco@81aPix>?=TR-CAgn%ZIn39U*W#ywCRb4PWtG7a*KKc)5_Of6U4L!)UVHc6yD*AO%!i08 zEu)VVE$Q$?0ALDQq^R3X!*}muegSm%D);&bJ#9Z0jH#oZ_}+Bzh> z^b1F+#7&bR7=@Ujr#1?XeO>ZSsCr-92wg!cUrdVWw?Ca*0`TEyPdS|sSssnv+5*O| z0{QFR`RVItMS_ER#Lcoor#tvq&x9j@X~d1E&$rx!pEfe=f0HIQ-hsJ>w56x7I(Q^; z-j$wt=w`Tjr+8RnDrg5vLtE~0FCR^n(PZ^Y7+m`@CRF$1t45>B!QaHeQlZPpYgC!F zSIZfq#xC)p@=IB}_!{9+4bVY~0EW*`8d-PaK*tH=XHq1wK{|f&ddW}s8Q69y#@#-W zw2eoIsx$ADwOsOV8vGQVBd+ zu0E_B6iZDidwS3@5u6l*b+Hj_+k?L&8L`XnWWQj7ctZQ6RLrUKi|NU7lwZ z?K=b|n#T|~8O z$vZndqQ<&d78k}$PQXv#_Q`KPj<8~4ay(_7o|tTBjOE@Pa=~~$2kho%r^A;VF)kic zwOb>!mAoHy)?LA$`~}I;Ccu+&2}dtvSFq=OY{Jbxq0&UYwTGqSy+SC3+Fl6mF-j^h zUHqj`QK6GyQ_$^hFX1S!qyS9VL>NW64O4=b;#E}ODByCX@VG09fvbF+ZJ)(kq$BTT zuTl`9(#s>%glR8;QaR#XsVYB~mKWPNFtR_Hw*nXyXqIcp9bWJ$-dohb0gsgGd8Vd9H&m8*?~0YZ zO8MZe+>JEc+K+$dqxSBDmF(!ru~xgs?bn|?ZBN%XNNXrUC0Bzh#JacUaZ-13OwyyL zTWw==Hw&h`S596{p^E7^TM*}59CUHzYVl*r;IT%OADDaekNu)}RRzT2dC@&-WrRdR ztnUNyx7-Q=nSX$f#iQxQclgl~I_J`S@XK&29mEm+1cYfA$MzSNDk+Rpc_^GLnrptf z_&wBX&I<5dIM54ceKL~rpE83lnL~8&vfSPqld|(C?UTNNiU?i=`2UHA0)3R8W zG)j4Q7C33_!!ES#`=$QoX&Fo}N^#x*IC=JqBqJZ798t*HCn%-$5iWhdR{^0htPN#3 z3m2U8ImWmZEuxdD!nI|*NrlkMG*>p^U4Qz?Y{rs zdr=@buF->l?NIun_m0!iBj|RVcD&kl2Nh%1G5u3G$ZITlXBhQy91|b+=vUTbW_m7) z2*-|#3(}^V?ktVs7kDZsQR!@(T37p3T@g_y+qnZ) zxOoqvZR1XJX|{`5gpD$Q!jD_<2BYv@i=qAAKl=39dKC2Di*$u+IXs?V_CRTTXMOi{0u)GwsYdgb>$KWDvS&Sl`nVZj8Fg!9wJjXJX zfhAuvtTLp;>B?h2vR=~sY4FGeS@It4n7g~W65jekzE(LJWpL-Rec8V2ZZ9Vsy@KeH z{G9W-<6NAFY{gi9cZ#XBalB9oWm~u#EqAX$*WI1w4!}x_a*>X2FHgbCP;78fc@bmD zF?`(qaoc2m;UWtaN^)P`-8qsSTgoyin=piiIN!?HLfhHS&L`Z_cyDb9cv3I=caHCd zPxCYY`Fh7rm8tG@bm9L4@ceha{UN;fc-tkM#}=NPUP2T0v-s=u#6?G!?Toa83v^$h z;DWbl=0sVvPFmr2Xb16Y8n~=1%t2=+;LDWpT{4d?MW;gEsj-oEw7=6Hd*m`SLq2_J zWvzYhyWayoW7*ZVva-@X`u0bmU7PkF%XUa#+}@1x3oK1uX_2(cb^G++8e!v8_6pzI z2k)Eq&b-au({0U7chh+78&mndB|PTM@7~nYi)ee-h+Jx50M-qG(Iy8Y}LGDPwtb`kb_7(n!b<5i;pkUdgJ@ zuaDhXuhZ5ZpY9Wnz=L-$gww8@cw^YtjUjLocCYzYUazN(EAT7E(r}3oV|mJz-wqxX z)8BII%WOUdcr9(73SFiIS@m@@?X(#mpNp(rls?~tFnHi#!~0>ocj@4E0Wmy0KW+Qx z$L+uYgbBz2%>OwP0gnJY+&gHe`wU!!Gl{IgO3I}1veKJ|`MC$9AVVd?NUeGok^;Rm?&q@QB$NPOdaSIrVN^wFowGVXI!myo{0g>8s!qF zWX>Ykh@y`&2bS2oev$q`I4AbP%(9AuNglWvUS*sjOJQL?68cOqXdvTj(c*&Ni3p_dSKG!jjNr%&=~&X-kAYB zaI{^_A^(Iaq56$)gK5Dbf4Cb%Ge z`d1&f`^~GMTW}`u=tWIQrId64gX^ieLfRxrx6F6l!3+a-kBG4wLR$~yYayJb8Y$P3=(q3qSxX=!Pp zEiW%K7LH{#sQk-*b~2nspkuqZN?ie|6MF@}8iljo5p=-hba!W)iReyy_nrG$UAup< z2fw%9wzoE$_geM44pclSXp_J4=pa|@x_b9J-}zp9_k;H$oF!0%c?weA*W=t=-7hclx@Mz>KtdFQ@`4pgM(FuC~V3CJSgLL#qBX4FL zVQF8GceDT5o)j>Anq_g$62UdmEO+=Z-gQK}ydKy@{_=G8-AWyF&v*i^*YDCp>eCFHw;rqPCkJv=^YCr5|vlKDXt>iDUgk$zbh+vCrwg#Cgfu|UGx@(O5&T63UkU#`vjK> zmm>LuFgSC{f3X6fpS?n^YGDbIALeCGlqdnDWCJ? zt`Cfjj<*Hc)_R!Z%zs@27ll|6Y_u9{Kld{dwEO-|^I=4#((2&Vy~=v-6X{dWJE^WB9C>NBp|5 zLfkQ5`=Is6Zbfj}MWND6jZjm0zqq{8zWw2c8NX{BbJsF_lrRIgJo4;E-}|6_@Xp=D zdj9Mg<=SqWjO9Q7&GQ_yCam3cy|%L4Cg`&VjK%x#AmYFGAuTP;wz=tvD8@WOQGU#( zb{uf`jJt|=;eWQa58#I`vgrE$ns+Eo(Jx)(v)Rt*=R>zgpf}!|N4wFk`|eD}FS|Qw z6P0c5hW`*ccb9xm8H08h!>p5cnW-SpT-{|Ew6SA)lseQ?-pEBk$|dZ(Q8*};3oX;|rAYv^{&i**3Peq9{<2?Lu^MtZ=FDN>jX@im$>+|3dp2 zqoQQRO}?ZSOQ`Um-%!pdTBNP?sZu`Ex01GtrQMwl?O~h{H>DFr3uwXYU1#e1~#~TQ0Dc z)+xV}ul4#7`7;-o2}Ai%7t%<-w!rZnaPO3MdgZwa;;;RcKNXag**fc7-@ayaJ z7w^e4EwAHvKRd7=F#f)Z^4CRlDiU3!RAc*DJAhxakGN>U^gxmD&>ppEI<|8yJQpwN zi|`ch++T$@Fh_ZH)sFY~;k_vHIddxNI}Ok2E=+g7WidQstBXqBfB!w)Xg~NT$51z( zoH8GgCpcv8@#wQp+y2fLBbPG1!lz#0Auj4t?=t$`^zVK8FnQm!cjj&On@XFT?xykD zH>UD^OL)wi-@Un+ho;h@?P>qME^nH*rFGN%|Fz=lfB9ehW9DGhfrHsqkHhT}Kk z{q4e4LgibL>s9dOm+#cObFYy8@-cX8J|7;&iCgEViFeXY%Jt^kFOeku0FMgYm)S<@ z;>(}Jk)OCZfwTc3emFUBoiP|4z|`!Y9k(5rcPG}~<8aO(e-5!dg0Z@SP-jUdNvMoT z>JZlCMS5;^UuKX~$m03aUJki1KM(UU#l&MI1B{Of3kN+1AQ_rWU{V3IYAkGPL^KgP9Ju2Y{j8+td4&<=IPOhvkgT3`IdE;4LcXowY zB;PP%^re2)afCNEvfYZZxI%4idbX`C-D|7MYi-mE?r9fSMP|ngVWnNBT?TuQgbZ!C zcwF1_$!}3WY@Ju^{_qic%kzphGMs;vCQrggji$Bx_T7iUq)d7hjjDtbsM0n9uX64~ zkzSWZCDVoTze_8hdP>^5Sl$1?R9STEJOq5~^)9MvTrGr3S{Mmo2&JY=dtfT>YD50C zk<$5P& zJh~(>S`5rTWv(63om(DL?gDoONay3vhg0d*oY_vgS=+(!qLbEAKKS+(*sZ zAMpJqe(;I4BAHH&{q>!CTK@XPU>U?Ezqsp`|KyQa_?vD_DpqM$naiX9y{<<-N&aTI zt}J?5waTEJk{-^TTOY?y$L-`-ud>J8c!bLbp_8-$3eK8qH|#tKnlDWk$8_^eu2{_1 zzl1gb#vIdzF%_=|T@vkHeP})Vy7xF%b;hoD!fARN;YoCmMsMi?|5x9j;_Dy$@Bg2a z-rZVE-l5~0&z`j>Jjd_^qa#dEp`!|h+$|-X!Q6 zarcm8fr7hC+8Hl0elnI_!D}eMQ7}C+?BWgzLcP8JBFZT8^f)aif9`T{Cy&Rx+`D@> zt5?TJ-<9cC#8D{Y1o`Zw%BVm$f_NCQ?3kvUjx{QUJU+!swOw`Uq~D3A_c7TLL`zxa zscbxj0PYZCuxmg6>7TcM_iz6VrC49 z8@{6=(bcQ2WFKw&$LCDEPuk9be9LK+BMZ|L?e22zXmRDY0s)U}DNwtT)}7jpt#xFz zkGzQEe{d5cZE<&uN-xKLl_3hQT=1fBN!STT%M>9oapXzmUDM})RmO7a=*}MRlXKOs z_Y--n&pY?;CY<+Xox>-n%u#XbDroNm+1uTX5=s8S4r#jXc2F>rT`KPWpiEw9zPY*4 zT#>I}LgC0-jy_z5*H%yk9|Y`j(LDHLIuoO}+w}Nwb}Rw}(l~6p@Vu8WX|pqP5tu(; z-);v-rR;KbzXB8EF3!(I_%c8B|0VBFf+S6{JU>i*Uu<`C^CdhYa?h%)s;sV_#&lQr z02qM`L?8gj14$7ccpBabViw{;2m}d%;LbZlNC2Fn2rs2Gng5mr@AUDt8$5q z$k;r5-^|T?U-19^pQ@QfR7Pc1u_iB2_s>54bl0a(^*w!0ms#;YW9e9Pfpzi32w7Rp z&Z^#%yl@KT*!%C?SDbpPHyc(oRN&c!a~wCyxC`F`uapFr`uudN&QEFXahbOEjx7KM zcToT>G^#E$N;2+XIu`zeyC{gnjrvXsguy7kQ1*rrIs{g<6~Y1IIzZRki;ZLlr)gj2 z3e270FX=z@PudpYB=|=@;4~v8d|BMB61Y=@mLB7jCVhl@DG9rwc%hHN=W@gy#(Aj> zv+S(kZZzRL{f6FocfgZv_J@kx@FU++GQ>rrNL@`C@J5|5!9`)U(7K*En zLC<_qJwj~tV-_?v+ilJF>J~7v3+2*v)&u`4*ibkY7xpbASBV8DV8>jNxd%KveM8M; zdwgrX0Wm%1_UJUZIl}WbIfN*n{uEi1B6}(Ab0vm2+&1!^Mhfm!fu6BIJusbg}J5UDSbRW_M!9^ z-jHty!Xlp2pgd})XkU%*jsvYmL4y(v8G!s`CoJ@Xc^GxakRSLo*jc8BzK=YBzUwrV zW$YrQOks%bg^nsW;lW+n7&tKgA!nc-%taZqi;@eO1mnfrtmvk2u_zxIgAm|T#%6QD zy9U8|9%v=U7Lcts`!!bzmvZA&Kqg5 z)eu;2Mf2I6dYMi*;<$V6-NqfgcFT)O|kmoc`fDM3ur0mkq-(O?#fv$%-5(EiXBa1;eRa0f34 zL!S`>n3rQ$?%g}f9_KlNbysEK4zylBjz@)OfS!OmFm&`wLtglb0gtS>&&Dzc;UWzO z9^2n|7jYQ(DT`07ao?m5g4>J_D5OK~=Kdgf;6`JTE8qzrMf;nF)>uqkpf4PkJTCjW z;7zD`@h=ODi*m16XaLIgx{8%KiqW2cO+WQ zNfz(EwU*Xa+a4=Ws6jtbBzjy_`yPpBVy7It@fokcB^ExxyMco&ssTp?I>QQpHyf4I zS*%;p$3l+N^K133t~U(KsJsj6f0cR4CEk*Sa%xvLIxq$@Cc_t?V5Tiq5aGjEI^5qE zkFz0qD;^-20KuDa9<<_nNINjlfS?26Uwld!zenxayv{zVv?=M@$aypz4lnu3yzKv* z-^IMD7%FrO{ChRcVqTZlsQF*B;%nlkfBI)1DFn?TWZKhIxUR9@x!ld$e zKvz8>GPqNJ6MHeBlm+GlMwD<6g)UpFHECfI@tqq$S~`#FSOn(S?T6uA9)WUJgrAjT zOk&4awI@T_y^4@}!#Kg9i?QpAA@TXsazhZ|NsS0oFaWH`5gau@!-V)a7{Ql5;>il| zH7o-s><-+m00Q#3Yw|cV;gx3`2Lild=pn3B0vrJ^NQe8x$j>Wp#c-5Wdf3UpWrJ~Z zMIjt0o-WO-dlgkK8=^$Jhr9Z}+M<$|#*qtZ8 z{6zBc@KSiAj=qccpe_6t#>tj&B@exUQz*)cTlpb4fdjt7l){v2+oVz=Eyv_DcwPt>^C&H*o(0FH&U@rcF>Qa z8IF9qy>Jfy(R%Vr4kav(0h{o{M*nx3Ja&)ActAQOJ;OTeOa|=+ZsoAV%3pZJ7h&v& zW4Q5e{N;~;c=?s>`ZLdz+Z<=7gN1DMS70B#DIiQXj#0u6eldy>7MV!9^fTNYQb1yn zQi*|~&P=)@4D}C4QvQ!W`Q>+Z$Jf1|{BJ($_s)Fe$BWIKw6VP_UPqHXO};tW$2*ZN z0M!44#%PV-#zVzLSiqu;!)`aNzt~C-zj~e?K3-27TjC2&MayoPOpd3s%iGjHzf6ZG z=bBjR>0hMY#dVs}m|btSEC@xR1WZ`riLjZY@3f-i?p%9>SK=XJvH4#K+8&EAHO6}nwF@nurkne9{Lyet{@2C-r7pfpFA=DM!a#+ zJLv4?<*DzPxjgHqUiUCPdibSxeoal>re;+WRW&5XtFYplV;X<>gAdYA{^VavKl<^9 z>794q(FC}yi7t0Fw8Udf3zo`Xw400VncQ-x2RnRNaf;vqT!9X=`-vSx2p~9q5SX&l zhsp8m%)HV_X}{a|YVDq22|PpS7(B+!*n|~E*Md1KYKh0aLzS7CRGFRh(K_sS;+P%Z z`5K64z785pzQBgn^6*FSmk0w029JOMx!3Dj=?AR`Us=!sFXE)YdliJoJSl=x@t5#W z+*`n;AM9qed!s&=7F)G+b9rWkR^ZsUh4cuISmbhccA1U@BZLzOWZ-Y;8nit`alKb6nsr-pbf^6huBk6Ee{dVXYY7igRJc7=ev}5&GjqO&tyXWQ>b&?S!4}>P zz6qR|LfPZ8vw%)GMLHg%^e8`gE-MYI+?7}L4mK1I2rkK&u^Aqb`38b3BZ;6z8sNng zX{-MO6L!_1-1WVH7SN&i;yw;eDG;wM9+3J}RNw8bjr8o~UbR-Sm759HIQcoE-@po7?HDhmX@2556?)Y2(9V;kj@RMI<-~ zyg51w<<0&+I~_Tl0E8F*gY&>dbpvJyw^5j&#|nY2`jlWnJ=i(6w;RWUva1he6L;tV zH+Wa(ZO}gVC8c@8pZX+o1>nZG=6M}(XWl0maQ?)o!aT^7PI z-vcgzcccYu2^;w+4ULnG4~1s}A2HO)Y39fB1($_(16M++?Rluc7od;Hz^}yCvB@bLnBoZ(XYD3evV?E@VLwPhSG+6mQdcoUV@gM zqw5d&GVbu*6K{cnm|apF?<{YRVelkH5d*Kl!V1#ongSHabF<^=-reQ&_FHebPF`># zIH442FR~MjW1^=LJ4U#xk9#AZJlpg_7k00rpg20*OFNtE;xjmEkDZdqN)wJ?J=VB) zadzQd>`U!NYKYgFo6-2LF_(D-Fk}oyG1+XY59hn2So|_R#_mheBBjYfrb!;baSECu zcr&Nxo=5tBr848YnUdZBgz=Qyzj`4bC=7+Zl8 z_!e@jP~!VONx_Xb?Z~*w0$byi((n#-rAdER%lHpFVX2?{wAvh)F{aI#w#5!wf2;n$ zl7%abpU`s_tuvlN=TUT1XCE1=2YiSzS2*Q*fD6fED|C;Yh17$EDu*nz5G_OLA}7ZI zSNDV;o8l2r$XK~6Tms*&gh%Wk0`K90Oh>)2Ba~zG8;;|Jr{<_V#!OBufWA^k;J~6M zdAP6BZ|SeV$x1vK(k?PD#)o0wXKWLXq4wvb1b9twkwpOTe%chhK)HHw1YPL+gd&cCEPV+&-Vv_1o9csg(NGjf!c*oC z+>OcItP72b%Aj|v;iExYDhJ19s#gk5lWAErZ*^IGy7*A;TZQk2w^$UvcxSogo%ZaO zmiUML~Yyg)yAIX zgU^AlqAu(lzf_+?rUhEi2jG>#arkT&OE4zl8RKTqgD`4?fn8s=hFi2zm=ebCQF}I{ z{`4gbJkzL&FvBNO&yV~@)5CnzcQK>xri(Uz-RpT4OyvF=4@xCeS?^}j% zGOtUQJH94<`lmnr2xLUifvm_z;nmdzm>f~B0g7P9$`225vX|evEeLPq!!07XAhz0M zi#lSY6`v6_K6trYcFT{-co#dL3P*lna2xtGCc7_K|r6`yYtKPCXUEAzY8i`-(>~sj3{cv{>?073L|Ak{N8y@)`|M6Wu z>>dwgbGn8HPms3=7f;{=AKA%i`%@n!P*|DR0IN$4Kx~I*BEi=BT`>s#?s2;8Uy7-Y z)nn#%^dc@o1hc3RS?uy+wE`>hVnPwSx|mczSRtTRZi(@M_(P;j$VE9|!aU(IfmWJw zCmh5NqFoqy7(T#p<~(x!eRPHD8Aln4p`zX*P^=imUKC|k3c;1gSXiKT0Ow+|z-rb|4kDbg;Oz{> znkHS!$7NGkjz;20K_>Cw$)wr_<}g~0c8CcNlNxZ4dQujYu;4iDK>CyioK|Rk$BIKA zdUXg`=!GlRL^OZowtm?Yun35m*zVhtt?n89=f)5{9? zj5jI|eG&Yj&XnH@Ud83e1AIuIdefxjL9G?cZ}0X}nOy+E3SZpa=9GNjUUp^77SJ;h?B<)>~_jy!RUjrJwC#j-x5hbP5{@yC#UIeARUpS zNdAg%!sQRs1KB)IW3xxLM>D)^2&X4f&taT~(sKBmcIgxVuekBUcX``{pR*^i;y#Fw z&4@M1pnt;VtzoXCew>cnfd{`i=P-oBNAD3=nU}+qc>WvtE-)I6>$c4f0q1aYsL}9- zhrV1k{P>W~WiC&Y*$@B4U4NAOYmJ>9c#syR)KSpMhKxxmn-X4sE;lyf<}f^Vx5d5z zZ#(JF^--xJayIrcZe(mEYIgU_Hpf&xE+b{&ttW6XKKM3{VR6(_{u~B3ha-#wguDKo zZZ2DnE{7-=pYe`Ad%2YHm8Vu1Yl;Xy_J3}d{EpHKHGCJ8~cT4JjEz(gvTCl zO35!}8kUNQVXel>CDEstOP^1D-f-TleG{}H=E zIHCptJ3>>0_6Utwxz7ZZRrMC;YtqKiRZUHwR_sJxpV zKUq)D);D~X|LMhzcqs8I<1=Y&axPt`$#gTJNukE@;ALh!;d}CIJsoS}k5G$Mq9~9W zD#y9X$Pq0FJkC$g)7I8@diwN9`t>KDq@VrEpQT3+9;By_pQKMe{dM~M)6deQM_;8U zkDsQ8Uq00HWjf?8);{-jo-6)Y`s&f6^oyVW+`GAc{mYNjr@#88FP=W_9g43zu%NR{ z;D7wX@29``>7S+#zW1Jm9j#V7H5c0H&9~l6Z@v3=T3lMPU>UlHVuy)1f+BWzp}Z=` z8d_AV_MM*8w`eW9(NK61hYQ@PGsiYkPmZjCM`0B!#FUlUTpmyTQ9^O#*;)TM&8Yvg z@*SEVtDjHIH?X2K1bX$v@o*?fW~at{0X|13a>NctxDXEI&$N&Fn-R=8Hn3`cj??2| zrR?UEqK}!h#qu+a1pUTD_40!B@+GwS- zknXK@ROah+cD$dORp3z-{Kv$D&<5;g5-%b?=2mTukeoX&D)pw1ier}!yS$z}d7k$6 zyH+yL#t6PBGrQNhGeUhu965NSJBO?#1%3_^V71kPV|gy(~I^c@-q z#MHj6!pGOi9{gkM#-R)dugnVy?mkvja3MVScXV)&*4Nh)M+2I7R@s3QV+%Nk zQ0?ma!gHX-&XUIql%jFmn(#p3P>`bhWCsx|-MQGGlQ~d;QC{Fd8&Mv{yu*Vd@7nMR zZ;dJ3LxVC)jja&uAe-}XYV7dfI8yI&RX>2_vb&4BS?DVW?>siPo2k=Tw7`v>4eTxi z*VrM^=a@ov{;ADSv@#FlVg3idN}*^QV8|VA?7~0^$N~WFk0UR3(b8tL7fJyOS5ee3 zf2?s_dev^;K_h%aDd2n2+T1VH@tsB$jS19)bP*tO6fE`G7u-=oQ-*~m_2>wHcRx#EUwO0pMg_ zFeuz4PlVq-K2c*0`0P8ptT59Uq25K-j70_C3L{eHV8JO+T;(Avcy6UJ^`O`oy{Q{; zcD=H*BREa@6UILgmi8%W+vwYKCs{2RRXo4VpG4X`lrfSdq-T^4%N#A-B2CYi$WI11 z;2K|HkU3cKU0f9acmq2g6n#-2k{`m?Ip~{mP+sH{F=x+Z(_b8C3LI%0#vt`)Cq*1+ zBm(+4y@b92t+Db_`I9E&0`1Q3R(5GqOUgrgkP2f53xpXf*wsZso~NqKeK(Zw1H~ls zS9Y-SRG>4$SC>~~6N-I!9q_Tt{aMuDyR((I-BceGHcKnZR*aEP;D|~ANMwMA7Yb=y zI@I{j!s8_t;;PU1?m1|;La`u#evMLR~FM^Q)7i_eW62JJA3KH=Cwx{_s4MgRz=%gq>U{zjj5JP?Dlts#NR3hu9fJoxu~}#&NQg zzbsgRH^h&{6}|3}6~Mq7Wia>!oT06x30x^Fw1RlZx|pyqRw1XcqFTH;VT8#_pK&P0 zGhl+k({fAo3t$Cr#qP_7=zx!lR(;_g*m3#mPk)vE$v^!c)3*2}j{F4H%p-ssJT`rv z9g>utai0Fey;|ILiLwY<7*~F%94ZTV#jd%QaAwA=WVH_&-5BEW+9LDcadp0lmXA|<3p}~*76=6ohXFKn( z4$NqJqxP4~D`7ld;`U1TS7X06y%FIhjUoo4rr5o2T!D< zLFVN^dU6t516`6Iea`}cR0S47s4X=3I;@C4}&@d|CQ1Y zj05D{;@^(oM&?!QhLvL$XqQV3Smhohj#J^RTrL+!=@q%;2w3!pRdhTCIfy3Zg>iz2 z&uKE?)zq5Mcygn`A3|)HK=dIj8uY!xi^P;JD_DYw&MQ_50TO|N$n#A+6G0el#euP> zI4B#eu;8J1Dh$t+7znRoQl+h6k)3-cm>6Snt^CboniUE_jY%;plpv<8sEd`ye|QsZ zOkHxL6hlMV$bHag*aL@#Cfo56jH<1A>cE(?Dn`VONst8zB33@mLd=L)T8Kb-G9`C} z3rt+C^a5T?v@{WNo_Yj1mlI|_&~>=F2&SKj1WKIiOFSc-E%?ENOvU{i?An8|BOdwk z_HhfUA2_Fk)Q^IZ41q$Dzb4OWf7+dIw>R-%5`+WF(S{XS0D(URu=18RgvrDmyz>M_ z*+A%np%x>iFfeQo-+_Qcc3=bU5GRC|!abNxwH5gT2PVp9?nqPRF(a$A<*g^mk1;sp zZsyhS1gwIp@&Uwz18Z?3uJgcIKPZ%eg`gt5pA}=$2>jO{0X$CoPigAMxKTbZe9B%v z`KCNEbm(W`Awz}~h&NB97LUH;kMc);n4wFKM)dF^I;9LF&*APE{&Of^*=kqv(KluE zxK0tnE7H~v?(8m!s3kH1@YkcrB`^Q!?J^S-=UnIbj&a>C;q36ZN1g4E-NGJe^Pj`m zFGB_UAP)6ccsPhYEdZehGqjg7^8H;ZzE(f{cRmUMR?r+Kk?z&u;u(tF1{p142ah@*$(_hMr& z?H_UZv#?@nHZ|MJX+|^=afXlKS!||v-g+~={l@+D=G`?5W?3=(!F%t>ubpOR zIxDHENi}qb-5g(h{vd6=SdVk}x3|;dhmX?3FTO~hefn8?^5mI!)*y`G7)FTSy*o?k zFaGpT(qH@IKT1p7p)o(}2{THn-R-UP>F1xPM_)Zj-P5boXm`?^Z@-;Z?yQP_BOnQm z&qP#h%nogik78vu6Ye?qH2Gbf_tWgeO{&h0r^+-JWKXAx;D|7}d%`_9@E)S8;sp?B z-Jm!U?>Q#=c(}Why1U!yU}rO(9qpy{M-S4tCe(M9mjwH9m6Hp#L*WIT6wBZ~YQd!@ z;WymJ$tu#TGfn=v|0{NYq157{e3UKRmoPUw>7y6t_2$^5MpbQ6*Q9@;;fXo|KaRR{ z8I_*}LwX~8V8t`aFw$eyZQaMfw9@kOf`x9E=e@MIvyr%`q+AkTuhzt8T&MLH+k)>? z-=}qQa%LU|Api?oz$=6@@KZdjc1P%k;G?RCJHl9D%pG29!i_sCEx}b`(v^>(S!}Vh zP`E6<;)G+>dWUJ2_$n(ak7+tC&gYmKE?;NGF}qdR<%3cY{u!R6&rYHB&9ouBIu>4m zJD1{(Svk)tZFW~3_fO=%>0L*xfJbS9u#a};m_m3R1hL=;!cW>M?p_tonFTc{EKw%# z&An2-uPAYRr~0UH4FTBp?m^nw%R2)te5#25iS$uqdv(0Z#j!ywT0!CJ4UG3mrSyys4e7Ydb7IL)fe2tH9_Aw-*#8^C7VUT)XZ$`UKZ7i4dGwKzKrR~H+pp}ylI5D}aS&+1AaC3Ho&%8`gH zyaUMQb>XY^jH@r!)sE~MrLQr*-CbR>aE)Uc8F!fzp>Qg@xPTYRFZzf@!1{+TN1)36 zc5V6^_nWCstbA{`YH3O3TWE%W9>pI!**G?Bsk5lQx?}~FcjG8AXah$ALbKUjhG2eX zz9#t1c`Rrxa132dVYw6S*veblo<*L9tICOh)3~WQkCk5CBOi%%gD{x>OqV-_KI(jZ>k z8N}T(oOTjNqQ)4+e4BY#2-Y!H8Vg30(==XbFg|&wi5?8|7xJc___^Hr1HP0$p3Ezd zA^v(i=jS_;bqxI3f#eK$zCF-xR!3h!F z{+^fVA&ru!$6@ky`cYOAb=fJ44E1zyl?kCed1DAmeDdOmT6U@c7t)Ibmc#T>VwCpw zk;2Q%!nLZ~2xSV#lyUSOC852D!`Py1qZrDIHUox?ZR`w=p+GD90)@!rjC@U9t1cS63*#ogL`Op^uvb=2m<)s^$|ozIjGv zp#7mK>|Ez~Wsa6*F$*$)E5--`-KW(k{uKQ~fEmyWJ&ehW<=%CsvO~j>A8`a@?BZha zF30>KdkHuC9*bGH8YFh^3f@ZBautQAjltdMD|##cGEP7bScHMH%knmjiS-)1M>{Po zuZYiEwi2tYaTdkAcWDc5#v$V`G$wX2u?UNWE6_6JBHerxF8950Y~zW>J!mPkh9~Y| zWd{##EV_!FQ{Vy%G?1N6m|DvxdKl)}drpw}kSbT-zx1v6UY$?W0WnAA8KC&$5u^pZ|-0k^b>N{io^a)8|%lfg6mE z>`3!sA>lz)JU6skAE)y z{z!Ek^Ma9?nF%lcYKq5&2ZI-f_xVCR{r1+TARwIc2}xHT{d{b((qjw*KYd)H`d(L$ zK&|vx5GHtuhLaYHD^PGX#Lu_Y9~u?G3;t64HN0s{`Ev5YkW`n(a+iu%1yx*htY+mxu#(9mH@cYgDin0CW zC@=X_H#yioYJS5#+ZoG&G2g{|H1=rPuQT5!%-5OUCEhoM{e8>uP3Cp!TJiN4fA;4e z@j;Nnj5v6H16bnQpMhi45GFg>pQpsfU?EAjoQyq+e|Yj+;*h@w8^SwN+zC_si_v%f zu=~Ix!WF}S^_!KqW3~tK@>QN8tE0!|@aMq47^m&7FEjAKaaaayWHtOARxQF|p}Q7G z-Y~btFFU&tup2`5D@C)nf8(RTI$RYaB-bQM3R`abW<+4CXEvebRsd3 zI?RY4O{`;;CyJi1MKp?mV=O_SwFXPq-s|@v~?1Of8 z<3(E)c&b4B;39*M?878vh?CMJD>jxoY30rx3ly0Az+iaQtm^9(!wQEW!>fPQ&Rj6c z<<1-}<2x!0AA}P*Pa`EOP=9x+OuUPyKMqCVM%O%ixckFR&^Z z@UO=!-m()W${v2nZSXnOsL%9H!VAv-RyCeB$N2%7!#ae1GW7GWz7>w7@hK&>62=xVOcwqfro8PraC5HuD0zo7Z7N$1 zgD>TaZ+=RsVhcl%fJeAucYn!&oQGgt&@bv3<+dR##ladb@y_YlWY2=LK&3FFIkG%6+592lWS#YNkyAwEOtgNhMBJUOSd0fX0K7er?dc(2J z2%s73xojUk1X_gPo8!L5H2x#}LXbha2yPI#a!EPIB!2beX?py0J#FuD%*nAP!hH*1 z$e$wt+1bI4-d20j0t}AiLlCmEw3t>`SKVy8J3BtIEA`r?ZRD&KSOrmEJO>HQymnBIQ> z`>Eb+r*YMdRnSGy5@+_u(O*6WW-1mdK{u%{NAy7JV#V)8;!Yio$D{CEOwNMrMKRABegrr>I00w zV`+DHKRtc6o}NA1@CtMUG{MJCSpbS)2!VOv9(P%B+$2ZY)cv$tRSQO32IbYP&!*a( z@T0;`bn(%-x4}!C2*x|xTS|K}EibRCo>ePnxd(<_icg+zq_4hus_SctnIy z2f_h_6DX}%Acg{ig==(lgq}CT1%zzyOdNxbU~6V-%y)=c0VddzFa6((uDpYb9s2Pu z3&`Nf;j@4N0!&~Hj!bBtF}>mGWM~9(L(XeGjnVq{4Z|66+tKpAhM=BD1ld2IzGOYmF~1_9AT#Zl*`Rb zb3%B6pu5#-Sa{yjn8mK!j>^UEQ|=&RM_Aku5Y{DXMB?TPH@DuusIejS@0&Bz7B;7In8$ zRsQ5v=3$KQ0dwV}KI_GU#y7H64S1`J^f|^a2ct}~xORk*e}o(1C~%O0R|dcMCJp)c z0k;h&`mNG)lI{lz$A=!nhi|+xEd3pU`H*Y)4;H#cp*;6;8407ub2a1wic1{Qj=5^| zGnb0UkwC=L+hOd+BNzY&#vkA$C*&6h&^b1i1rQ#W=+lY=jEz5fTfU*N&`ow9t*$Pq zEvxot97CZCFF?PekH-QXcI~iJiSZc0c+%K8?=m9GV0>k6P8?(zz#o6=)AiUCM-QUJ zFV`9{M$ji~^-4l#jRK1?#`kIKxl!8m0VQE23F8+EQpTE)vE=c{@Czj{bfw$v(s~-# zXGIIHn()Oz?3l;WeRB$jzu6WeyD4VVAm;%9L5HYUxk-~ zzW@#@jrhA`kJaE2$_kENrCnLvOqrOQbBr$h0XXW#Euw8GfKX&#DPQjUWWfWAT$-Z8 zvnm5Hp`4XZaWJD*fon{v2Gev)%ZnN`hQu7L7#?q4aFGrGn8Z%;SX_H z1i(Ud#sQQxTN|4`#&u(3!^gv-IN>f&Xc`K>=r`axG9;9&L92j0^hy9#eIZHg&=!vi zk0CzI{YrU|4-et4)V9zY7MYtzWMM)7L~rpiyL;kO#5X;C<`WPOM040}+Y{eG-p~YoQHFAIWL(87aK_p7hIN`Lv6f0;i1`OjT1FPvzgRE*uz^TLna z?Tz#=|MGuIpMLr)!jcQYPLGG06 z3iqL3YEp&(_oXw{dr}U-lLaoo8s53a;w)(OEV~Y4{6moo9LLlb;psU&34DN_)8|N= zg*u)O7@w3d|GaIoTQ-9*#cta$yx*htY+mxuCS){26Mny$Uop179OWf{%&XtUgzN{) zE02CkoPkp|uS;vxe48*|XMUG>-xT)uEyFjN*QFafzW(&5ADN@W=pC{UMbH!En?Z=T zzU3Kd71uBksyqx?qyCC#sS!+Cn4!Q$E_NIVKMeGeKo3I*7=f3BWctV{*%Vu(6$}d# zz_0b^9TjrA!!iJVK!Lw!<9IoS?8TQTxY{K={S_h0JHlcHX_v5i6DCS0`v4w<30Hm% zu~CL867siAwuHZa6tToEVIrUKj~uWws1)BYPG3*F9K&`qiN=fgCIYXFD7M3(@P*pJ z6FW^3dSZz7_xF8{{G|p|QETOy8C&9L5M>}H9<(MDPKV#-IvA#$bv-gig<@LKF?b zjEk}MuAai!is67U7t@U)PACyrbw)lAZ6=q&jKaiwWt-yCS^&d#y~_jxH(;b`y4)yN ztmyNR5ej1lTfwLg1ev2!u;XWejTjP`Ktf#D+>V_Hl==k98{cmJLzY&f!_h}9zG0rSKJ6h_jQFyG*p;gM4U4z#1| z3f|~Nd!gK9s8I=BHVYEe@TA4covX{hjT^nWXG_?kzzR#dX`;&tX&5k8mLaq#0yFAL zp7a+c|H@p9aWL%o5stQnNrk~i@C6Qef}vaxzOfSu+(5}!&V%OLU{rcAmgj8o)*ra( zRhcR~6A*T2kuDV`K6l%}a4^}V-<*l@IAc|c>M}28F^-UkGFm~Vc$C{a4hD`pMK>J5He;E;SeeqW?d~!&=WBhaf^jMQ$IVj-< zWp!O6EsTZ#D;#CF61e>@`^WiT8uekmRNave*pv!{P!)W*j>(r&oe zrbv`2(#C{OEOaQTg|ENt5OGG~QCbDJaEdU+xPG=73Xzu!jO$3ioSxw-cYHE5{51&e zaz{MB^aDORNqrWWkK!}%CBNcNx{+SEMdV1=)>0T5zDEt8xMj?CNb@VM4}Nl|jq#_? zIh=k0iozI9cH%qovx!2+V@G{sHG<~v3|Rk;=Hr0by_oVr9z&~A;U||h{|xI=(sORM z4@yNkBmk_-cdj201*dT%=}0eN%M)RS_V|rIl88J?PM8S&i(h{HohiQV|K#8Oh;iQI zwkCBbxV*?EufS!}N|`u*dB6{OMJ~!KE^$9|T!b?0&|vp66XjVR(UW-us;!15f!vFs z2{o&cHR)qwZ{fejc`vB2og)*k5_flTJmSXIUfSO8ri<%|)IYyXhdq_=^43SCEH5pl zx+bX5Oqxf)*HAg;RmlsQAm3SCN-N7ul&h53D`b1U6Vd*9dgrbC>Bm3*e)_==-%sEB zK+g}ppYGhd@1wfluh^}|CG7|jL`Bp6x8FxN6*i(<-TrCX5}&kn&`Uc<{nXdwe{!~xW~&Xul*#m2zn3mF!S8n! zZsSE-Uw>gC2k=7Zu)2CD{m~!)B)$K=cP)g`bU*c#m+!{1(lQp=#9|#3D7W6VRiB?q zwOO7S!@@g>1Otwof&K$J_(qhKEXbiv;89F}l?K9*IX#tWwg2@+I@;e(`|LRDcl|vh zQp<5KOYNqG6TTx%6MWyBru47R`o1r1XM4v&nnt6Y>Us{3dg;ZB?ez5dhA#r|YvPZf z&$~m!t8ok?yUC!_;2#S;#Qs@$u*e+?i_NsqtXgr1vTs^^0z23AQr{9TaoN4{y%K+N zAbuUe1jPFQMZ>)j!%q}@L;4X?!$a9P=)tK zNQO`l#g}<@!B5PH{>6jIjRn^9A%x-8IRs3y3KsC<+%aZ>F?R7j@Jbx9$B7O_=}1^s z{-bCEKTs^xt4de(BM)|!U1@wgSO4^)G2GBqD5o(!cd^9Y1rC^q2# z7_b<}5VRriMbKw~q52Q~mavqUF@W-dGdw7bQL=D~g^!IAzeU=FrJcZcVCB&eoPuSO z9|CCN$x&E!>pbf0(4VOY?@-dIr>QL)t)}`nJHGU<_A0x@7-NqP_I;%3<42Fu0Y}Yq ze4yGHWheqicu@qptmL-hLX08tO8LwygOiLoDyQ#sq7LF+xpNFbDEzKTmS99%Gv4{G z5zY0+CT4^Hv*}jx)b-LHO2^|<_5TZvSBGi$@YrL)-l6dQpzkAJclP$IjAxF4vX-O6 z5Mq}dp_h!a=I2rNqR3Idp8G{oOyYVy9i%V z)Nw}%f?(nzfTf?HJVP0Fr973X_~j|}qY%)|ss0G=QQC0?A@f6&2<+-WiNH<(?qoyh zP_I|g(lQFmmQvRkcN{ytnDbBsb_M$+6U}dF?~`8FJ5{^;I~vyx)lNOt{oFi1co@p1 ztN_gP9>b1D=9^RuKhFdBlM`(N`vHF1C>`1m<+FF13CDc*9761B)yh=v@2jH3t%GNE zKg_*J!@F@9KUMFTYeXL81&xb&uJFcXLFpqL5nj=DUJ$AHF_%$X$JDRl;a=v?mK9_i zEOTwwS;lWYWxmdLnJ@A9JG;?u!D*uK6Dfc)0SlMIHU}7_;l3~9vMUV>*yZlsrpl9i zhjqwhlD~!b^7H8^q$796FsCOwc{x7$&_=vTLl0q`j!d|-(?jKy8+ZsF-?_7DAw6wv zzC*C0F3=_xGjcZ$_>Hm!n%5EiXDl-96aDmkd1`O-E+`)q7sV5N2XjdH6=24$Eyh{K z1Ptv)|6>sk=~p?{&;8)UIL-LV0y=hKGuC$&7t#`U47KX+$K<8VTqp33`7V8j-Cf{6 zinEw&<~C5Cl#RJE;~_0q78o&JB1>Rr6pI-SIC@lZ5Sr6Zq0MLKF&;B!qXY(iN5?($ zDlFD^>bO%Hg&QPD@ep62iu&X*(m4h2h&gRRa@r?zP6%2Lw;d-@LLL~+5< zuf(Bz&_k42j6Kw!oz}E5{1S9)xg#Dxw3|gZDBj(tA;?ON^bB8iripe!hfrW3`(W&1 zArfPi}TZqr|4d{WxTOY{!98OrCN#e#$IhGP}sb6J$ZJyXET3Pi!d3PJJ~P9moPcWHZe z;GujvIXm@ELf;9dzJ#I--k#n3EJB)|P&u#8gsWF-&v7pjg18QQaX)y_ltzRq2?aFBV`f5gjX)F1Qe zcQLPXC&A*!?`Wvk#~GS$6Xxs8?-K8u!v4Nx_$KqZbWwbb{k{Lo-x0lX6EY6@Wpt1m zL<)m9JeHH;hYttVrxMS>!e3w6$G;`fh#T(+QT$&uxHHiV|6$r;E2$NCOw{ky@FncX zhfPjlP?ndyU$qZ`hmgFKDvZPC9}7{j;-R0CE~cbcj8n;;gD}~t#K(;0UE-L}%FYCf z>CrG;lqG-4I4QmzFVZRShgq;ugm8)Qe(T3*F=9f08HtmIQ&S)fr;djR|3nk1BQZid z`@8A!3DF#0WJwTez;l z7;QfWrBjPOkFqX?3&0G=2Ydp zzD4nHZo&-#Wu>>z>}OzB7znJHND)kgQ)U$UtmuUBUU_o#^x5g>EJc|{*qQ2dYArAL9+SElk2x{kBuxAI0$bIUiLbZL>j4%_7MX9rDB0+P z2_{M_3hSdglm<8f4&RtT3Ty^;FyP=V!aHymMv4-lgk^OutH)rV2?sIu9cO0nZoK^) z9J>;pAatNTdgXEVikv4YR+!t&H zA#DA+Y(_$aaky|D48Nr;qozb0BrvditpWE2#nRhZWK*o<5<9ZgrX}rHXh4kU^efWK z3Hk%KT+Wv=d&S@`fBWWo2_pvZD8{+CEZISZsG$rC`-qq056bLx!V;y$7C07e#gqs` zTMiPgL{P#d?Li(kN+;KI;6xtzi(jWfxRNrCe(49C;ZyM)O9`{{)Ub8j$zy3%4OQ{^rwlF2^tM);8u)0qAa)LRGJ<2B^@ojhrFhQGLlPI?Q{3_v{R&mrr z9(wH0w_!;b|2Pdt$=^d0bql|tuggptb|J0&=G$$^JA5%gjY036mX&(cp@iU#Te$x> z|DS*8VBdxL_x^+b=WX0Uz|m+NA95PJjLS&LRVvj-?1zlXuX+zB@(ALY;Kdz}7P!Nk zKnFC&b0iKENWwu=5G+`D2JH|pfg-A`f{w*EA$&89W4wos2};C8se&+@Q6R zFToK(Q!{g()RtqK=rX~F#j#A@jdl{plCVQguAb~7SVMReD@Lo{^~N1b2>79G&`c|o zW~W3OMdQ>NCzbJOuWw;RU%Vp|*8h z&p-Y}`s(R()f6|5K&qw>fBd1!T2I|$rF(vv`r;Q5RI$+K@`{z~a|&~lm+K31X3Gttj^r5;3)h;ImXVC z{rx>zuEby0(}n7S;$mF&6zI}nx0m*hSZUvP8=`RK?hxOHr8w-kgFm93>7~B2gSMZ6 zXBQqKC`TYKJ_lY*sA2q_nVn2a3r!zqv$eTx!T#OVw(wv^`Cq8rLRke4pw#n;2`URm zS8*iP;zBENmkapB{bKN<6~+DjdvB*7eD57APA&v9ghmvi!M!mbRupA#6N9?WgYHzHs8oE5$3U5LbtCpHh9O3%jB?GL@Zr@2!(9jQO{j!%pSv!4E!2ch~Nwot^#ke0@{2q^tIc{={xD zj-x}lva`D>+&pz(>~xll?<^3Z9Z)pw?Cfgn-0~RIRNr1*Uh&S9f^+6qn5(KR;Q7w( zuK0p|FY1JTAoyNhS@w9vacqp8>_Dd6$Y(eT^zPb<6;Wqr;wg4^l&<=P`Z0VH_yS#k zj-ZgCAA@U0hwN_Oh~w$h$9<)M#uxk;Ls@jfxG|?b31`cgetL4Oapy91nzi))JNMHY zZ`@ayPyoU|0Q+;*lZ7^ny|fX>9a1*>G<}BSNY5{Bd@Sz9_Kxauo>mv@>AvU^$G%-% z#9{%IH|@nG6@Oa1$E}b1WggF1&s|B#fuJv(RK)InWCz!xXGh{gQ1HWZb=t90h(5)g zjpj4*Vjva=oQW=5;iZ0~42>OSM-lW76i1QBj<;Qvm1BnceU2Z#6o0~4F=3eq3r^aC zEp5?WWM^H&bgZ0AzAEhCKE6*?sxhqnV2t)x?%M}L5xUz`51xEn=e zjF~FKut({aYN#Gc2VC{y@f^nC)W*YK3xI!IeHrqjO}3oaB7oP@t%`~ufd zBypE1i->NOHai0uPboh#IZ8pFq_3K1#)Xb)A2p@yzWnkFhhs-MyUXs~SxbNX;rr>Y|H+Tj4?g^freCw_3y0zX`>q4@ z3cQ@0xJ`3nnBmK3Rc|k>1~)kNP!F)sh%FqYd{yHIlT&GE)8(n7)b z{ORNL+2@}-{FN8^Tqo|gYt>^{SsV#}m7cuVHjlW_Y8sCiPrSfF<)B4rPfWCNjHAVb za-DGDUwj7mzUb@!uXB`@8?a-wD|SAY&xsEeKLrI+n)WC^&A>GWwA_ z04JKiWb%i@$cR1-{G&yA!X?6xhQIvFE7I39lE%Pfx14?UQyC~T_MA3l9#mIuq?w~e zxbmR}j~Ft=O%5>FIVnB@F>)H=oQLvU(NbUMrI$Z}n?4*qM;rtT*Z3VNGdBD@C=*%^ z!xSSNuTtIOTGHjiq3l5ZId)Flzx>PJal_N@SZ#`hFcExU344S_Ed%W0Q3}fI)gy6wSQkWVF!y6`t$remtnZ(czD5od{`9Y{4;*`aV6O+hOR)4GP zf)lGe&5RL3|5NkRY4J`cE!|!9R(upa2u@*)c~G`pcqLD)2r&buNjSnSZ~0cEO$SKt-e)W_dAt|<0HUv zPsn)mN4sN3@#VB(L@ut=^u%1cv$B@%bXHPjwj#KxedyyfzTiQ+;wd5x@=&H_geVG* zVki%Nq}T_Z*^Tcqp3?J3bKq4h3WOD*F~+~HTO=3Xvf}OY%gF^9L;_!C3TsQqj$YIPd!>>V&N7BNFVwaj0 zL-HIKg1>X%+aBRZdGISr2g3{(y&WKj!vLo65APf(9I@F-1is`}yi1H6ZqP=y6GSER zcL|5pi45b&6q`c{&uz<5imzdZvpzFa^zhcV-3b@pVW@NDPaiDs2$&UkL>S%?qZnXq zXxVL$>L7snNA`D^To=2P)e|b-jq)Cb!J;1rm5cs~H~3U|=PJ9~n@I8q#Zg3a9sN%P zIq2K3YswaM`rIh;3sxY!=>pkNVdXu>BVI7|*7E|~ZoWaJ<* z4m%$IvU|iTg_a3W@f~ePILyGBVfkNwhl;Pi{h$B;ZsRTm=$&`~gai6UAb?=pf@IMh z@8H$AOBqqHpsaxYgpy}E6f2q>GXBRz^~yX00vUwpO!nACZThWzgAWfuBEkmf7?VBk zC|5qvR)bCxegsKCGvKbVA3CFfm({okg4^sU)0;bVD%`^}Ga5-yooX-+)d+e={#47;!WZJ5Asv z5D-DzTzc7~!~J2v0jBew92qHp#*o(RhwhWTBT= zW2eb9Uu|)Fh@DBvHU8Pn%rj6#`dm-ezX@%KC9yi z!%lp7plR{mD56+Y2ERE85{rjKab?^WOvX`^L*iaXO}$BG>^Dc`B7l9OJ^o=%pw9lc*DDEOKEwrE}pUPJMp%6cN2FZ zu{!#PAH1JF{NTORXjH|!UZwsy_oAT0R38=Z%8oCNKeQZA#Ye%!T{zqyam*2o2+Vq2 z!3*Vb;O>p^khZDRT2`jQTbA*PHwq*c@FCCx{}IS}_on79D18w8vdf1U@MI{lif|D( z<|FW&z>mJo4uwXe>3Xx{AAv993_BRCkW=5GeBb~p-x+bOT<)EueOB9Vy+~&WX~8u0 zQI1BO7w-CaE5fS`R^F@3%vng2J_Vk66~Ee;yy%>aCS&6W`$8c{n;_U?F2w_m!RH_B zZhNO0N)dL4Ep$5R-rc)trPE3rqe&Oz7|*NoUV8fIq1tjcz4PAt>CJb(XB;1c$GyHt z6SuyFJ15M(L{%vw|t;f3UB7_I7<-*g{+L!&Xc692fp74~;`Cj;z%i7EFRO z>l>TKJ&tPPxxN{LW(&rylboZGc9AZbB{RhoSG|5LhUqu+)KL;HJhWgA90d(ELN?XRM4}8KF$2?YL_a zB?t=#m=l3hDDv2a!W@IVfDJfK*+OX*JBJwC$((V(a}C*<|De=_*GF&-Z2~_$-m31< z4$`o~Re<#z3j&pEL4RW&R_2T(isBJkf{CgNC*_Wnv?G7QD!%$fDKB(0=pX41P2g?7 zu+UQSh!mlv2AskuE-;oMEp}`|&k1SzPJX6e(77lxajApnXw-vm(o@p39mX`tB~z!{XJ^f%zdt{m=~qkhO*R+i()QsBW|R@8~(%s4WXabkOSFYTcG>K&^daiks! zU3T6uk32uS6nzuEDsAL1E6Yow=kva=bANZ!<>#)b8PS{RsX6D%*iTtlsKV|l+z!?M zUTktC-LY{B-ehcSQvFGEM12NqV8H-<0x&*5XE%uE{i3siuy>oiac?c%UG1dR<)-=) zN7`x}5nsS!6Bcej1KD-W*vIk8*P?ga$poHyF#|^&tG}ZJvC@Ox*`{Z=R<^_ffpN8s z#s~N=wJVB6j@5&IqHi(wv#W)LG9uuDOB}}s-vPhUs?S2{>D)(C_i>{ajYc# zRVb}Q0}Ko3p?DI(0fmyXHGKnb@uR#PE9t%oha{Z!0x*qhEQn@2fbM};&_)dM7%Scd zFL)kcMSo}PqyLxPhQw2X?vs=W869IJ{n`t6MRz?G3f}B&H~*_Vpnvpv6zblcCS0Sx zaD*Sb{!qSf{9U&z{-)2O9TwBjhv1u`{i+M~VSHD)pucevgUU*Il{I|@xg)!_Xe$De}z%B3rI$06SlX#Y%(?F>XE&R9t&A&+h_TT!~)Bg6R@HVBj zyYKjjW6dPIu#L819GQV16*iz$o)%39)+}H`xyL+!-GuaKl&>sWd8RV0i!OrG@Mz3G z*vLS?VlHqlUIg0t@yDN}Pd@!DZR{Q;wXheXy(zx%{kPY|?=5J&SxDF8GwGlI%U`Np zdup3S?`i~ZM#p;N4sVc|TKgRaJShqh+>1{M~EiZTzvjM(KDE_(aJws>WOdqGAzRfOe7WsWcV`QaNUyZLwUP5B+(;p`OYV9jwY zz|i;bXs`$y44I?Y04s-!lG%;mw#f;&k|uWC3OsBN=Ll=N^5Ct$f?d*BWGbOkne*n4}=|td>Gx)Yqi6FuH$8VdKMB!{<{8Qf5OVM2%}#(+42k8w#+(aDtw29KhqSuuR=r6n;3n%IiD zVfCZW=2ti_PKTNDL_-O9WuENd3qlxRQG|(1mSAjvmnT}zkO|FgltmLjCOL7J2MkwC zu1JGP1Nkx;gMnj0==#eKA&<*!SnE-lRb#aY6TrYVPmq9-;&W65%ownN@dA%{z)R{( z9-crcMM_IL3=gEwe<^pYY>de#^)pWM5KnK?gE0W69G5pYBj#C?U6gt%sKfb(vKb!& z|NY26GNn$=4qM>9e(dIO;Z9JxbEFXVu*sCXY{etSjBwC@PTOHfoBHx6j}Y8Dio9^c zj;{=G#sMoY08hHvEmD6-Jn+Ro-h8_~^Y^&hlk{+t zqaOd+U#|S?W4Jq(Qc>=(I~Z>w7#_J?`YY{2B3LPd{qj399eLX$Jnfw0lNLd2!;dmM z1STRI9{A-rC9PN_li`7r{UTN|1(y8eRUQ&G5qN?xf9B%WiP+TBP{MOKmQJoI{ff& z{vSS~4y?>%#U(=I5E@oAo=%IVpri>NL1^G{H|ngq2rf*p%|qx7eT44ejvGP>1PK;G zFcCZtL5C;m;y0Kad#o?W;72qCIwm++0H<^q;}HgsulX&JqKoTWO-Q*T<0S1JbgjhN z7H_txi7Lu0c0_Re7^^H#E;I?h8B3b0r}OKvbaZl_w)fb*-_-OSa9UbhZ<0HXFxP^dXQ?T9K-b)8Z zr^1P&^kQo}?Fx4I`F=UI9Rd?pd$V{5MIlNr>gY?|h4{#;?$eFLf@JcKXe zo)>nW!Mh+ZN2t_kH+>Y)?9{m7i%^Q)SMc$@{zW?Wkx`+DL0L?n1IO7p1uo5Vj1)%^ zsg2xjDldJ8olz{H5{MiZq8#`s*ojx2oS=;P$Ugds+6kc(cVn<4VRQXO+I;aM?W(=^ z_IAC)1>qU}a$%w4quN-z2$cnseKf5;Ah`W<~1-jjOqc;&cY!Ongw4)8nedxi7l z7@|a#{gh+jca`V1m4pa9xnGwR)JnkZjdGUo+(XA@_}~?|@0|t+M+F;p5A5&lDIbph zQ5@9~rE;}a_o6`rd+Z`WP)$2psVbObXfri~+Y{jx%23)Ffj{j6TWf(nfmBcCQlw9P z5jZn1@QzlLp5BpB^^vHHi;HQlGUxcjMS1z;=`#!5n=SPLl?6T;r3m=VVyhQwgO5M? z#N(1MT>XARI5OtN1_yil=J|j4!3XKxci&c=TOT72z9Q6{Wru(s@?uveib0Ny1%{_; zgA2j_=K4a+^+jq4HxZU{HxP<9AEhdP5D3^pM-j|jsUM-#<`_A~1uK5kezZA#97Q|F zZEkGs_(36oQjsxxeqQjHt9U%*^bd9^9%w$ep*lW$@+7T4dzOwg=8-0iz#PImQYSS= zO+_0q&btBvebADi2h0t?ITT(j{N&y@lpN4T+R8YpF$EU4ke!z)9w`2t_?_r|nIvlsCPAJXKD{1@Oc9@OW%ztfFku4?{`M;!5U*q=)Jv z%I-OhG0-ly^8g2@Q{1R$_T)twTyN#gF4%AsY}D?mnae@=vf#(N;xhgcm-1i?N8I$r zl=&8^M0#0v0sT^6w7W7xaZ0E`nN?q!NZH!ozj_e@IAbF{9@iuLyIzrk%V3+_ik;sm zA8FipR}H*^=X}Bo_#_pN)SVZ*nC`4Bn--$LbovU**uzdnmE1fBvI*KDcCkaJ^I{a` z%Yv3mg*gx&LytMdhW15f!k7tcL$(q4%pHtWhQ$%cU}z80BR)su!OMVWz3!pfl?9-a z>E7B>;)pnQr%+d9M(oT+sl-kWc1&6ECqL5l&P0ugUht~A@&gV7L-GT+SyYO$0eX*u z0;MwLpzMrkjCt&;H~uLeeHz{k__7;|u^xEKrvq>wT7ff1&$8Q^wAr1^9ib?v7)xmb7U&=coKzaL1xiK6 zkE5ewjV%YhFCMuAJHVEf+Ns@c`RGJo2EX9Ds#LF#fz4@LL%f#2XY3 zzC)_U{i_wbqbNfzNIviuz@1|$;k)1~Q4m6t;JM%%z!lmhXy9$?D^C_%Q4SP;G&~Eh zSa4LCXSZ?N@=6x&KnK`ud@R0%y3>C->7Y74ojM$u*>0rHLL)6L)Y4+BCVNfxdRkDw zn3)iKL}O6oEp<9+d3nWm)!x0ck{0#NE>2EA>MSj#d-v`q?i-_Q@Fc4%E9uQQ-$-xX zzwaH&$m`S;ak7GF7RTK6xsd#ZjXBUVsyFs%R(h zA=>CxeELrMQo%vnjePdYp|9++T?dEm)#!-j=*S{NdL}4t8kUhdP zv_Wv?j(<4mKN5>yLWC`R_zpkZ%QwbpIN=<^qh6%uRPd8ii7!snla`3W4+C|C85n&k zShhQ0*!6PC1XlnAkzRdHdf^#{{BgED{KGTCglwh+4l{%kVTi93$%6UH$PuK`zn}dy{E%$H^Fk#_G0W1X0aaL>z4R)f?5j*mj1Usy z8u4r!DGc>-BH^v+nXa461BM4e#$=WvlJ2w!6>b)|>cNk# zz7R5$Q(oaAVhfQCrhv;&JA{09?N7RYNCVW0#y*l3Y}L_#f!oGUz?(nd;((5VT`xK&Fajs^zWc$u z>BB$%qtxbzBQc4mng~)q2sanCax5WR{=K?fY55o%aVQqHin^M)5mRghkNyxOkv9SY z7)GyVg9?iQXR_-fA_YeaSrm`9VIqHV9>+*pdZ(gJ&QGSrwdHjGoww8CQb#z#qvbl}@Z; zLYSgFRHq9~w9CY^Fmq;-gf~n+5l8|r@QTTj1*XDBm^UUN;FXn93TH@Z@_fyGX(}d+ zFE|EXGRYuK7*)QlfXojQ8rmD!Qx+zslm`aIN?rPz>IYm%=kgp8^9j>yE|=VR3`F#$5k+y8kEL?Ca z;p2-m!UjBwPic`bd=W14^oK%^rh|!4m{-z}v*VYz{)m@NG{7J=;?ZV|zWh>u=jCt_ zCQK=_tpiKsDhC4yH@*184JSo%J#2E?wuJ${ESp0%1<^p;xH_*vWfhQyJJUUE{_eL3c}H9E?0K=um9oydzjF_ zV)K9cPyWB^LQzr|hF`;v9RVTSX4e-hr4eo*#9>7%lYXibf=2ZObp_}O!fh)w7?%~_ zbV0Nb`sJ})G{(k_5JEuc7D7zu6BBU@u9O!-e}FW@YEFdZf*b;Luc{SIu#m%fiw-Lt zdZU4=v=K0J7YN7VAiO|Gjt~g}5W8dGd5CYiLR{XIL3U`oSG&W@seTshaI7!1Nq?jP zO}et6C1@ltP$Cvs+OBYgFH+L_kzEhlv4AC|S;3K2-w65G;l@g9s7$~*ggOYlq1U*L zjgd#(BZP2>opLvtz+0fMyl)hSOV$z6QzeAvT<+aFJV@*7&%HALkN(=fmO88V(y4fy zeeuTJMS?&HK81QBe4<|PCQxfujI&dlRm0{lgcsaN)|lgX#R=uZ5mtv*+#Kxfq?6uZ zx;Q&#NHw{&kd)QnOPvJ^KrCoGJx_hXjbnKj z8N6e0nw9gk>$rt1zy+QTL6WL&UWen{s3$N-DR5_bA>F^*akHZAfNyHoE9uTsJ0Csm#<{qS@ zBh^QEw$N&%wYy6`b`WJq+zEpcGB6*$iCzUhqHH}l-1kl|g#N5PhBpHjS;4IYgoo2< zv9pq9D;%+ok~a&@6`wR1+c{zoK^$>e$&HYlK7(MFU4TXSP5~mJX{i3mSOIUz_~1Lt=3`d_?QMah;$y}#-^>_6 z*bDV{<^(KmM0r``NJPPjlQ=?vNebeb&qMf)5ECWO+${Ia(FfVJ#vMMIv#GsV4Sue2 z9(Ioe|JhWjH-rmG3-llF3g}Zouc3No6K%hM{qYMOh z>VDkqT8PScH9a?{F>EX?ciQex(`sKiSU`Dna1^jmKklEP^g6c?7)3P-IPTa(0motl zlt_$IzSm~&Q0}qYg|_z{SOsQkV`zbo7o*>xR03C2F-~l-!d>Nz@lZt(&QS+;Vxe55 z%q)mwZUTOJj-rO-kG{=OZ4*;7-W4YYjr|;@cy8Jf^Bn|(tj>?Q5JGnrC!o}FzDmE$ z8LYTfotanC{vqt=3V})Y?~6-~=L!Qpd-15^(FcIBDYM?OP!d5eN|dtWi&HZ+mWeL; zK4;az^ixlat?G~Rhh7*4N*4o6yt`RMhO!ctbf6hlzEMB-N4Y6Ya5d;GX+m3~-_f4n zcgYjl%RACi`SlPFSWu4WuaGJbST)nPAx?ayP5<#iM>m;%^iTPUQ4$^>BHf|;ZyM4J z83c*&3OcR6BbW=JT^{h~7MRLTyKp>VquEwi?zCc82jk8~YF1{`AOHA=@~@=L?X7g& zW05L~uXCS1LwT6n(jMRl3K<0W-~#yUJ4RbA_dSkSrr)Sk8WTigy$CcGAuzu_65U~O zfX8Z$87xShuY{5v0W*Dp(_Fv}?m$`<{hgb-_2P^l{@{I$jkBgpyBhBwKHc<@YS5YG zrM49o(2&^qb!wRqav<_XP|i4ltOa^Z`rsk3q&HT-#QaLof z2o@ZZ%&t+6j}&_ONVo0%L*q%ghige?sLg3SVJr(YFphJ75`Btz>>@i=9iV$#8h_WH zeU+|G4^n-8R{1V@r|_l5=st_Qxn&933A|P2rKQDmcWFT|Vb|D2da?dOwCLEhfL%5d zUUb0yWH*X);vHQa*~>V?;^y{3BmMAuZ+o{iyHSA&N9i5#h)$k~Z@5){@Qah;86bMd zBw&r`lip1&+62!*{gA!+iU!63RSr51ty2|!Wc1j()K``ekU|FzOo33#RvUf zU-%Tq=$@+me3F6qQ)Fl;^XT97UGR{$ibYWBPZ~?;%PdY}XA=fqn1xh~7xWGK9Ag;D zRpK#ro41v*a$gU->9~Vy)kj}X3di6fILdV@otz<`JkvYwLIdaBH`V6E$6Ce*AFn95 zLA%Hs#USP9#3Sl%MVZnMgC8g> z5#Rs|@PTr80gdwOsbB5y@2E^1wOA89sHm?UrUzeqnjSrVsW-G`Q;=s8E{C%ueLploe7^UlN}xWZUIVQ1LUsl^x^2w#yNy+xzMH zi=A|=dJ0sA6MYh!$8v0LKT5_pJ#-5be&y3)^Sc<^aevh_l~c>!HzHGgYZ#4`d4un8EGTEU4~o^ed(KUZX*9h9G+L*V9BuasUKOGcSJt? z^AmCMmjIz}EcO#aWV@|;h)KHPUhH@>dB{O!GGbFlyr~O@7vXTre*ZrO2`FK-`?Fe5kEfaIt`4O zIfaI}wU;_EVG;9>z%5pHM?eT5t4x@%!HB_hmz6{&GGc%rjxdIV^{P{dh0-5ogmLo< zCA~Sugq0`|KbTf(O>V4YH4%n*sv;137$4GxD4N;Sx8b1}FkQYwiTKzRo^97Y{=wm6 zVuHI@){5}6>WK@>5pMlqO`b4N8`Z&Ogc<}zuz!3D_Ob>JWkY*{XvNq{yzw;OsHR4H zL6fLC!;~FgFp`mzn0Ud;t0Pq(6jyKyq%Uw-;pL-{M8uuEl4Qby)omkqv-*gmTwq|V z0Hch+Rxq=WP<08$s4zA7bJXEvs<*h9wUMe~qAOyqnY^Bev4**JFr`(>O95b9$O1o4 z?7$0^1EnWQP~R&eA{ZR;D7+{e?TPV<62+w=o)l3mB^v#QNl7UB$iu5O^`=^O zhlLeWfuC1Qs%%9;W!#35BaS9BFz<|4Ox|L`7Gs?omq&?)5)6ixz5>%oxl|6p?ivZC zJdER->^K@F#ZBn~SCXApUbXpH&8rj?hES0OunOfwxbo|Fd}Mbl;fEQN5i@uT@D3AC z`B8KaAyGEv?ePSA4jCRpm;4jX*-syV(>yLPtwE%L8GPmNYMrnXQBm9<^!ShZV#m$j z4kBw#8-K$I-<(c1#CHS(Axxx$A(dRg2$^joKm0p0OoSl1AAt38fH2vavhhdh9Nuq# zxeW0{SlmicoNjjaL-Kg%z%S7#|B@yUjBn_RvBsZ~Pk=>#PCFjE+nU|naTF7)-fqK4 z!s$hIb3WOP|9D7S@6kwuUxPwsG*3SH9&Otko^QQ~Q~CyOQL1zC9iha?ZuZxc>xMl$ z=%o^t^6^Un9UxxjUtDNl7mg#LU&Y;y z#LU5pJ89|9?yl2q`o(v+GQeXT9yoy)biiW^%gs?Hj zcjy&kGyM!9V-XwzFUE7ywXhK$Mi22#AK+bbnh2#)G!PHkLTN}ZXbA%8SYY8@$|{qE zc_gk(2K)l`7(C*21kX#64tCifh~jPf4oxOLu@Oedg3uHGhBRG91O$QsE5}(R13gAq z!GabqWI?biI*5=W%0ZcU1uqCM=L^cKqQ|^N+r7}KQA_nYLbzsXFElO8;K(Hkf$*3k zm3;ruEUS={C)fzko^S1^&7FM>!Jm4u+==6X&Q4Jl>McKn zZqRg&azv0%8?YPh_>^6F99uZ)om`FToOfrjL&r*knb}mUaI_r9-7Tb*mDSYJo8#B! zs|q8U%khG}e&0JS5X^Bu7)MUF8}sR`caSbmdlm@H!zU5o`ci;DPdAsRY4Y|eRj0;N zt1^@7igVUKN}vDwm+9kQ{5);0KTBP9b{!s>=U}xr!nWIS!Dv#nex{Z#ZYR=VpVj~3 z=~VZ6y=EZ^N6EbV)*I>W>XOPor+Oevhrj0T7}cfGun-&=A(TKtKs$4413WLvR|H-N z_u;>IIQEX?bgnPBLk^*i%0yq#;DF)-g#yAMR{MgJ90!E3jysqvoRLAH*%E9~a&d(C znc6OPc_4h8R6ET0&6tL=(-cN|z`MeednciA0VM_s3b(D&pnVbK2QL*oCwOiA7JtSr zG|I)UA^He{GIoY>3?=n64rV-IXNA){k8j+|&PR^F;{FpW#grEOGdv)7-H|^^xf$Wh z!qRfO_trb<-n}=iJfi=i9B0AQ(cxbD^w*!Hjg57|=_V~LbDY_m7Br*8qr5(eLG`6C z_;^+Ex7AAQI;1Zm7~}Xe@@0n>^+1{E@_SArei9y6I1Jvivjl-S{s@!fyUT3A@>+>P*@^FrF{?KZ+;OzA5j!K<0lKAe zW^;4bJ10q(qfJptq8ws~qr50i5W0X5%!hm3t`)`zG&u?i#Sli|l3}clFTZ5U_-nzi z%EFk5klA){pIxu)@{;@5cqmvyF-E%3D+J9UY_@=zHdcbb1URzr4mv}h!q0**{WE^V z?nq8ti5-CRjBC8rzB34@l_z0IpHecnDoUtO_9!FB8}2H9D5K;`ouZ=t4tMCH0?Xh> z|CX2R@m<{YYdd@g!fL<4Ejy0*IZeANUd-qZ9E-Fao>t?tq{UBsM{MdVx(Gc} zy^9~m*`qWxUmz1{1Pmh9>x|0odJ_Ya^Hup>2S4gJ`Xf&;gFH~q4#qNe_M%Yqc-vQd zO{c|nQ{@ZA5QedYJW$#iuhn)e&?J58PMXZQ8Ot&F({8vkCKAVOq;}zGIp4P~S`EJe zTp9m;pP~9Xc|aqL58_osd{kC;4_^Ct($$qED_btlPc*(yqy^D;cJH!yAa;?(5r^zJ zirt&=9NeRYl3aWcxK973-Ia&$vSa*KSt$!N3uOR!%b0|ctE)6o#Bo$$WxlGk1XqQH zmqL~RT|zm-&LXZ$;DjE=e(sH*p^quexUNIAd+OrNT0VZWuDU_r;q|~x+J>>pIILKV3*Pw&e=K;i1CO1sDEB!s zlQAsDH}Sh_XLe1YobwJa_jAV47;E(J_6|F8IPt221#K@hHLcy<-Azxv`YLU1Y`CAY zpo^n!!6z^Bn&&RBX|>a|>(>^4xu{3fDV_GjKaIr#Bk+@lwnuRVEN^cv(*EvF+I;am z?eA@;gWavP{`^V$^wVFZUw-mQdj9O0`5^i%R7-?K4<`eV_F?KD?WVEoGv6J@QQNG~ zm=R2;H9sKSg>aAs7sP|7WD(Nt&Yl-I(JsL7NN)Rm;bEFd*JCr{E2~~m)m~cD;63X* zWXDB2n~SSywzeSNuaa7wwX}HWewwQ_)6&X4eXpj@y|>fS+FNO1`EFXd`$l^6o%hr9 zTs`$J$I@JLCAAffW4JlxVQgaBCqq2j+)K}12)^q(X?<(YeD|Da^}V;=7ay~h&aTGO zLH|PeHq&BfDYZMD^x=;_Oh5VKzm`_--u02|%Zohh%4=Ft&OL2veD^o{G)nnf(Q*{# z%q_lr^f-O>__=rq6!`*!;84bQzXx{4{h%XdT#azWpQqS^Zj^6KN$WSlN0Q!+)FfFt2kbz2e93XsFl68Jf{Bzm-mXi?jmjVZKe?#k?BwcZvH=W|-Cx zU)b?A@fSb+i;ozvaT;Vt0FZ_kKVnoJ31Wk{fAyAI*a(vC*?}*ZU#A5~MKBSD*vKi8 zi##F>FU2CSp_9`Y{)QQ(ZF~Gs14>tfb}p%zrwC}9%g;AM67S;cDtb3kIA?dg-Ix@H zf4@pTc!V+Z27dBY5wH`4((sUutM7;iD`b^}g-jW)1LF_5(Jn;Fo}?ZhFNOA()0VNX zz4gO?whzjzAE$y{77q>%Q%qshq6Q)4a>OVzcKthz9JaWj1nTy>R`l#_Zl-gHul!)9 zQ8Ez*=7r-gU{+ae3DbBZcM>A4=~<5A;CP5wacDu17<^X1AyhCi6mf>tW<@aHg~^2( z@LBI7uw3x#iLt^kIVKL1hY&nPc!(zxUo(_^!@($J(zy~bg%LC@k{jVXNru6apLaIN zKUU(&kJ8JZOO9bSeFun`y~BgUbZ~H>Fu@T2L5<-C_5okYDF-)FY105IZ492dwcsA~ z?=aYlkv|6E9V=T|EsBtcmD&&<-}gk_VfJtn!vzCq%u-sw5Mp&BMv!oxWSHQS6)O)z z`Qu573QM~ps33iU!RP_EQ0(Z@A1z2(UdLl8T9wcCe^|9(&LGg$_R7s zyw&dbbMdV4NReZb!u={R&LN25*c%H76vivcVFJN#R%|LhX#;B%snJLQN8>hikqhxr zEaKZqBS9s?z zdR!*^$YejeXD3_)JqI3?*`e%YlV5{yp(rCAewET7T)4U1{th=MMA#h9dFQx<@s6Qk zFo(h2CR_Xp&ur%>>cJD367dG*GVJw~czoN>pHUCH;o#cY-)ZR|!8uX+@Cy@OgC~A- zI_d+S2!w~>g@UN$i3u7UFmT$Xj3oq)a`Tsd945yvZhnyl{>331(hXD6Alxwi00z-z z>>6)5*e$+?>0rWjP*fnKG%)dt8K#4m%V&5ft(+MCPAC6He+eJbCamMziA08B__PPk z{>vs?{3>s#=M zkOj|%JK=KLHnM4aBWuG;KLr29$KRde>)k*3_di0IfUx=s-oU&7!XQe|gqty2Wrn}d z_=-Ri{sX}ZlX!#)^O|rYz~|C)3pMh?f*!(qmy>7>N-b8DB2;2UCl3lR=n_H-Xa^tx zR?vkhO~|3I92dh*XcQGb@&BCX_Gm1Ok=AqWCyO z$lg0kd)f>4@ru?va$5qE>^cTdxi@`fgJZxM>8X?LU$ zx*@c>LZ}Vjpn4*#M>$ui*3-h`Qfe-C(zxI(3M{%m;rq7gN{1ut1hmww&Zhp+Ub+>J zg+Qu%xS#fSx6<+cZt5NEq{HovbaJ?xsx#wh!FQ*eriTx{NS}TFnd)$x-g@ip^rIhr znBIH;`|0kzchY=gIo(dxld7pYizmHQ?Wot(j0IWsDwl=}|0c)t{a;xH=hO%1pd>;2qocl;e{*+M1dqX1UP3W$B8>k5JrJ3D7(@%N86oR zu#TVuVU;X`8Td8k^m)K-b^%dVaM`uf<1LO4 zjQ)cG?_w;C$M=PaFJu&(nwd|PW;?YycT!VNt-0umEIibw9r{j zZ@m3py7%VW;$bUR{xF9^k-}m$3w*`b)#`N%6zSjKKlk&Vi%;fs2GEt_L|H;%VY;lo z>Eps&SCthWm%fXi+eZD@W0d@E;w~soe&9{Jq9o<0J?2`p3;Z!{gy3p1A34PecTVnL zd}3Vmt}(%wHswC9p4y3HF8gO!>d&Es=RPd%g{Cbll^Kl(HKkdz;FQ($7uPHxn6RL^ zF{g4~sSlo?sGc1E7&|e2_l?rpKR)x(r|gPg4B-NO%DdQX2*+kDB>n7*hiT`amy~Tf z7cNdr&#C`U`k2_~>)Tdxaa`=-VF>8Cv(NJY9_7W3CKdpogkUEeyFodc^5nSdotW$b zrSGt4O<)QZ~z> z@_YBNaJSUSxDSt_vKxQghlG2%EEv-QyQ@@sNC)G%GJF~~{N*=(^h@Xxb%Cz9US!9g z{V7MJE2l`yKaqaPhd1SMU&wBlVvqPafow*@S#c!ed7*8C>>O?w@^yytMjBzFetrNj zbx=KBhKwJK3A8hF#ZY=_4y^u-BI)9iBQ~$o0ywQPlle92b3zUULs<-sro8Y4%)`Ub zud|GUaw{LofW6T2@+LjTUHUN#KA1PdI{*uICwhEU9^Cm==C6z!Cvs!w35!%v)Ui>c<^u2m43f8OE`{z2l>Fe8A#_ zBaO+NuES!CeYMT86?5>Wv?q7c6aSpW9!eAX%Pw;6F}=~)M!mTw6m;hb2o!PN9WKm) z#zKQw=*@A&EJ}hVAZuZKVcZ(X^1N6{_~P*ig&T{w;4M8fR2iX<9774;#A2wRWgJf& zi+MHV?-KW$%rLFYkH}=j*H69UYnZzRciCfj3Fo3r;^EhVJN})J zSrOTDkijeB;2!=a<3!5-`qe*fxR7QrOcB%8l-I>{P>7e955<1@E?>JYko%;4TDpZMUUUulvlXeR?-F@Bgu`J z60d}fdK6R2?0SWR(o)zGMvPOyny7@0Txdx%JjCL^1eXP7!alh`gu@Vq2Qmcne}v+T zV^>6MEx>oU0%H+3G25J1%xXX;$)p-dQpSl`sVGKeFbNg08eQ+%p6BLz<600 zB;x56Z)Pqg&5*Nt4Lg$>uap)eLpr6-5J`6BFtGq8OjLQpJj1+DIm5w~730SQM9dtM z5Ew?75$XUV=v_Jt#Bv|gfbLZ|^5ZOY{5j+Lh&v|G?qrz#p^PUrxlWYd*q}FmL*$b? zb;FGU6zRR=jTFeise@oQFSv<#Pl_?~ib)Yb{00p*}>FnRPJgg%tP0vV+nX(|s9a`I)eLBgz}qf43LQ`rzqAUvc#o`jLP zOtfp1gNZ7NMc@^a6Ur9&>U-T3(u^T#64`Fb!*bG(=qVSDt@r!&)nBq>J z&@DBNTx z8fNGmVPZ@yZv5oH`o|sXpv=m5kXC+-OBmA86HUxtxX~wVu=8Ku5#nWdghw{G$2)%o zJp6?zDNv_jyyEt9zB#Q(&|y4W_)CT$@e`l#-#YlWs)^of;Q4Ojmj&- z%yx&5P!6fjfCpbBLF`w`Eh{eJA12a~vH#e2s`y%Z_h0{ryIELG+tY*^n*KX{wNmx&=sJQ?1PlmWL^or{JS+KwH}Z}F^G4(5eL?`J2N>%c z;W<0+p=I8krSh8xQ<{Vix+Fe;vM7Hqa3Brfa)WX}qY-Web!bI!L+ShYDusiNLi@av zM!XaBoW_UtBm9RxBINI~BSdd2UZ8>37intz+5!v&z23bbI?d{41X#?g$HzsVMaz+? zaq|~~7!i0)+_{VPO#BQ--&}e^jzWq{=&74`H3&w&6GZKZFb^2Bg1X8bVW1+5br3j; zFQkIdc0{j@2%-{e;SX<>QJF zE+QA?`Z$BC@d7g7!)UJVdDtxLcc(<#a(Rkvy*DilMr1ApN(g<5pYmg zAN`{T;U)?R_;Yv`F{k!N$jPo3@F)cL2<;J|3H~ZKc6Re4RD<8Ku=gSaYLu_=gYG|S zQ^s#AmFG3@Kq%*ahf;<)Mkr@c($TM|9*fxErAUjiFjw);ITQr-s{5Y%7xNFjQ7o{V zu_b?mm%wsLeHlKJK8`ZG;=5iDn6V06b>Z%>vl9z0uhc#@rOz=%wR%e>7*8B)#VYWw z+KV}d;o|%d5_9Cc#w6jUm9a(HqCNl|-6qPL{LL4@1M2bkBRAewz~QHdKPpZd9HYqm z2E1XH%OpD@W>r7ct+}w^dw75cb!;|O=N4m-#thYyBeY^C26aWTEgsZ&b+E`0#hGBN z@}txNc4W$~BzC5;`;0jl{Rkl_bHHhZL$S=gdMdVf2F3-HlDCQDOX=6=YAavvukn(H zJ8T$t$)BU2R#xu_UbAUyXE#0k>Zujtw-dAJM&kfVSn5x^doh4A0k;@y_;xvDXFh4= zFJoB0r@o};1cetzXL8hASs)l=JG73!!sj!-nU|N{NF_u60p4-)2#X2nYk|YGA@H)I zRX9!*@&I2LBWNRKqjJ-4qU}hP{zAJm4v`n}C=+SXF5J(?*v_1qy77(RnX!YpAmJF3 zDHq2jvgnYb=BYQhz%DlCf@)@^8*>oXQ4cgw&dN6ERMa=}FAoOy;uob3gB!FCFE|g^ zgLdKGA>%V#lwj-pnZIRWdX7ViKwcTy-TC1m6YUUTc*tj9a@i~cDc|`$FeQBU3*Igs z@-KD!dP6uvCYuOP9f_tdxkXx05$Y53I=hKb6gnG0LTQ1$S!>34rtturHGNTk@@_xI zzJh-)Kk0;>u@@y6{)}_%Dx$wLH)ZD*?M>S=2PPlJH*kdG5q4APSrpyUX z4P%wl3rzKGoRFPwFF2}HG|q_5YD`7}6$^IQ=_Ohwn0TJgj7fcqy0VM1UTuQYP;jePs$U5nDkJ_y`@VXq;cWyXL<7^vRR-;PWri*4Bn%I<|QkXgBu~QU?VLxtn*- zqA0mk9)h`k;B8{}7yXkX8Lu3U`_w28^+Q1ejDRagX0kB$RAu9VWF7x>7GHSBmD-`a!O`Fc7+=_-#~6hSEO0G&1{NoUEDipOg){I{$OX%o z0j*#MJ;yR)XZ(Q|rkxr4ptC6Af-kLj_Yiy=<8zD;9EE$84psKO{X@4UeB`;@g3l4I z3SX&TxsPjd8X8m;Y^PFRG^E=*^F63vJzG!fn>#)hn`5J=#b=F+c1%o(*0opCoqKPk zpZxfb(og^F&(gc^zGHku5y_$?ONGS0m_HHTEsB=2Qx3%!i@Cbsmtf9f5ALvnZgo#C z)8@X)eR!Js=i+1M>s}}`Hd9UA(`(Txjs!k+x!FDK1s*7BFK@jNjKvxo+~>QypSr?< zQ`%GQcZpJ0W#U-DWATP4*-Rq^b7W$>!kN9Jp5|~c%xS(0KY2JJL=sHI^tJ?jdZ}=&O@fwgO`ot?e9~q$led8}_MKsrH6T)JLwfaen&&SKF-ht1Z?@O=G&z;G~XtCF|UUFUE+R|874J^ zlNDco{^x)GQO2l20gO_7$ejrogxrRg?6C?sJ~4zRc6dWpY{N^2ukdqRUiq8HOak^n z88pN@FrWHze)u?m#!Y$ppFdl}WVgueWs|$eAdG*p=e!3}Hs`083jph35JU_-h^OCh z$?o|tDnR`FUF^2vKm0E6!{pcC9pU)KC4Na8+whNI86M?(@XkgSSivDY0)oRZ0T0*E zFjY8zW6$~F=5PP{@sEiYCSZgc3=>4_=(y|S{W!*jT|q$vBfMd#2&@D$ag$qk!C2mE zunXk?t6`YW;oQu$Lu6eA0Mu-y=02nSN*`x>K1>y5fFA+*-of#*d zs7qmJ^%mpoNr?)Ck|*GjC&!ryWTJ1TQG^M??7}M!?u6rb6a-@2iG^~4Rjyq0$dMW- zbN>RCWd}d-FcyRxXARqrc@IuJqefn^!YJ_A6~$zTi#wruz=YL|KBhzU zMFGR)hY4RWF@gu25Csy`0~75}B@1j(47u^iLl5B*C>3TqRtob315O;6(ut{w)LPU8 z_0CG_EO&hO8>>sp>Pic4H0dHyL2uL72C zHu-ralk$XVEt4Ixi82J-C_^#yFDvbwm)sTBec0v9@o-blFuW+fsK1qSaw};N5dkJ? zM0mN$-NPa#yZM{+{f#~R;$!IMp-OKLvtf;&91jJVcly{_ZzHuo{2gTqCw>N5Ke92h@XpTV zEfcUF!UMa5=5!1q-1UtW=ZLJI;@|?vu83;wD02yqGXNt|8?~VxN8@dmcmQl9#g85r zWE38eHdqM^q2mrRlD5O~=*O@8=4e0?cX&J4E7A$;;HRX`H))eXfk!y%U*CNC(GPWT z*|8G`JHchFq#`^I;pB#2eDRkZ26p`tC?jw1217&nFr*YQ@^6l2J7oY`12_H2?vQrS zn5UNw?#`;zeVB)HkYC}Mh)WyfFV~fX4IkV6AO6|N;}rgOf4S8oZMivYeB(nr9BKQK z7M@|pJ;N~&CSdQvfPn-a8sgwW?Hnh6`JasaR;)4;0VkSka@H>U10S)<2{QwLI{dI+{Ek1KgMv;CXqssFi!xh6;14`vtD&9_DA#w z0rqsJf3YZmgN{Pb!BI2_br4Dm1}X@`1Lzd=^cH%hKk$XPOsais-7Gu3#!|I5Z((#z z@3{)RRS3gK3!yOd9C{i;E*4lsc}-(%r+gteMR?9)9%vkG&C!2WKEPWkJ(>!kt@)<% zP*w|Y)vkI&>muLSHSeQ?lpY454hjL%LfOT|^T3kt8I?iVrP+z=)SRD8cREc?q&Yrl zGPSC6X|aiN0lJ1#BUzz?scU&!A`&+`+?1 z=X;x`lInEUkJZ1syXo=cC+XRk8VsgW|4iu|o%q-|j=N#EU}v$N?yYgJr}(IL!$f zVj;xMnE0ZpS@Ta;e2Q=4h^2*QMQ}yfruJ2t5a`7nal#2T2)KmM2|*OcRifZUXvNW6 z@SgBID84whk{xmgguIJLd>$9#`<^cZ`Q~BR;X}T4^ImEq;UNl|SUpZYUesoR;jH=* z$`W?Yhd`X&mFyHm0E*%WfgQ$aD1G-?(P9hJ;az3OgT^lccIKMQDJC_CU@n3{2Ocu` zL3ZE7t{M~t2oKrS#8Fqi|3l?tp&rVpxvFrJvZ}ohUS40F3Fo=D{z2*q|5-@Lkw8}$*TNHac%TSk+)$gq^JQL^9U#oVPJ3}= z7=4nt6+0Y&YY3(lUTGB`n05wsRvH*aq)U0DpA;b_E7Iws2%dm{rPfHTb~`ODEv1FU zMYlWc$O9b6j~$TQ6|}vzsd{kqVc$E&;Ncl_0+$6(!HTyR#vue%{oun(z6j-*W8J## z)NfTT#^iH79M{M$IqHUxu6M3@*Wl@tm2aKJhH$^>oh3`1mimx*Uxnq^(dQdGzGG;8 zb3YyS&eR9kxfpZ43k3a|&oQUrh|Z}g?uTLwWJlQ-Hdis$a=YyihbU z7YRDS7|5~kq>qE~4iD9-n1LJq8fSqKdBqqRr)yj&eRh^{)a3CII1=N`sq$uSgaQnO z6lpMS7Ud1JfH9jnPnma+x97_vbLkK&a*W-%#$S%L-1W1+w=4YI^{xfllHHrk3%T2i za?-b$Q&2z3iebkO^B$*&J7X{Plc8*wppQY@i(fH7Y1GM!WM}8x$3po>yr9eF4osK_ z=%Q)0;**PEke^o#F2%KkE2hLLZl!!KtKQVv{^6+pB^apxxKJbM{HDRLJP~w|j(%P0 z5?^VJD&>Ov4jVyYE;nIC$eHk(GO=h_5%r$-PCZ~npCSkTe4ibP*_;RU@d6fS%lH__ zDzbZ*e#o(|;2jHKd%dn@8z?S}LrM?6g?O}o6cq&scpG8J6TIO5DDKAMVSz=bvykqr zv@P#}H)zaHr?us#Xy8SrmB3VmQkw7#v!WR_(M0YZ1D{AU7Epw;gE5-&1Z*_lR$O=& z@R~X@zOndVW(IzSySI|*Wl!{&F_f`-c1Gi(>Vr&zg)u0GSkT3BuH46Xm6QiCW^s+i z?}e6VK!fWOQaToYz;S!*iuFC8$0rJba$qc-AiEIEdI$UIK>dhaWAsJ9MIT`?M5nWq z78ly?R~((Ux$z>cKYuP>;wWuxZls-^Ey3bi^(gH=Y2K7E5~a?$;ELi3B?!x*tn6SX z*RAS|;;I@7FHRglj>Z^IoAgkY9rx1C?m^nxKhpSkVWmV@Z|+{&KkTV)CszJ-k9t;Q zGCt7W?2@-EO!(xT(W1Gu4edgk`7TM}0Xy%Jk#Q`xcRDeC8n=Q^_NhM_H^5WcmGKJY zXGOdnW#%qPWK-Y@@;#Jr@Ve04iOeIj8x6T3yPvJR7as!dqo6@4czlKu@GR}K^Ivu1 zZqZ}a^XgV@I$04eD9q_~IywsLlTD$jVy2mc4x8F_o?%kJv-LQZUW2e)(6;YQi6L)wW zUyP;R<+zVCoUOJ~rL~l<#-`JYox}9i`cB&3*;iX|r`n177ITw;muaHf#0wI#e2xwc zjrYz-;g=W5h+py}cXqs0#iwy^8FY@m!Vbhc%k9(5IMe^!c{h8v>;|%;|C^M`8p+=l@oNy&=hcNI;Y9*Fz`ti|f zINJfs(2P2j*Z^w~o|iuOc31={*yK=vYCoLp7H?dgjy`ykhIcLGZ^~8D#WY~t4M1Kt_-k%+CoXy&*xn$8u$odr61IyB=k}``WV0?+)J=gn@wbz zqeqSbCp*Z!*PNdlvJ@`3- zlj$pYz4D21iqI<3CVn{DL|Jgp;p{pB4|)7o|L`A#^LJqWkN?p>xMi&87!t-+3o10W zLNAzTL;v7`7-OLgA$WwoAuvH0h@t?&GPHn&Amd)eTH{zhO#Pmy%JQqG* zj3Z(Cy|@R7o!m^s5uDMUtmL#}Lgg`^C-_qjXcBH=;>aWf4+x&&rx0XxMW4Cf2!S<1 z4B8Ps!tJcM2&Sws5e-Hu5R-C*QTj$`fg)>ePH?;wKNY)LSP{+fC|Bn_A1}kMuD9R3 zmsVGo6@Nx>M@Y|Zk6T~Jy}7gJBhA>s)oxY=3wGO8(uLaNu*(YBzA?*>+LGf3*^R_X zbMGRX4w`-~SaWO{cRaB|8~CIAqkf-#{&{-x_>ucdXK^vT@x~jeR%`l5r)T1YX)hL- zz_+g5yK8|ABzb&t#zLsw!;>^IJukN_@s8VRR$y&Z=2E9wPxI507Am8tgLmbwC=_#~ zfqh;7fq?y@R2~XGElmEj! zc%Gh$*FLmA!b9$Z0rz%ykJ8Rw*FqL{dNF3fC$ZWatX2~XdSEi+TnJ{b#JhQSfbv1v z1P^HCn$krP?Vb7VBM48~C5EsKA>6F***Q|*JUr-nX8?I{1k{P}2W1ojWN^H-*tYNs z9v&qfi@La@iunR}uyNNJ`OyCvSD5E;&n>4GjEQH1heT0Do3f0Mev7cniXy=x<`xKj zRbutavNOc|w<3Xu3`mUMh1O7a_j7%-+tGqF6jaQO)b<$iWcMdWQ88chTYMzr0EY3J zyvP&$;Rv?v_4Ty3v#s_}J=A7J0S8Xd_u1{m*vDAOLNEmPjI+K6OMTwEkd!AvPj<}# zXY>5Z1Ns5%xm$;Oy4VSaVi3hJJ1*Ge*jZdq8-rUKn=~fussHcn9J+mQ12-5`f!Xb? z+Fs)hyIRi9G)BmcJ8`BcGYTAyU*H8eX$75Wg32O%frm%Y=UuRZHT=0xgit+!D|I4_ zX{E{y?14K_Gj7s8v<)tV;a_jY5uvHa-HC}vi+>B>G_Ja|E62qC-d=iv!gMlqTVzbsS?$cm-DC;0g0z`lMi`aD>5xFjaFs z^)2Ri;0)#FI7;SQZezKz!-L9!cklq@<9f;!{KS}Vlfm8a&F_e(^3JlWklj2LE8tN0 z(O-ZWbtN8fq1?d59@!KdIOMk;aw~Zj6ZyUD?(*a^V(_CKM$2oZvA%&(32%4YM&gny zb&1?@4?pn2aM7d0B5l%edeD025Yg5St9FH6gH2X!slFUhd3Wtz&*xFx|bgs$_+emuDW=sq5a}ZaO%IPRS-7*ir+S>H zDfk}MT@{E$9ZDC)4ei9PaCTaw7=*{Fh$mcKz2lvzDA@M*4%34N57WaZPt)^t(QB25 zvAEmawc=;7vm9e^rIA{##Z(o&Ck%HK?u$12h(FP37Gr@ijJfQ3Wsy)*{Lpfzz{Jx;LN`DyPR>#!e-5<$kVq5P8Q4YR*rkib!27AW>$5iN`_mmp$H@ zevY_%PANmZ{RRfvA5-jhANj`Ej{B=_*^Jsvd$SpJ9~im)X51)KF{A#}<7?BAv7Gm7 z%`gw9XrrNCm)6%BrEfUC#=M#q_<;>jv0~Fz{JacIZVNCKIQD6XrK6`{1&=7Y=)O3Mf>ncdW0t|L9yfR z2SYgA^*yMM>l|J<@JAkAeH{gMdKjl}?;tj%Q$j4c0C;`lg#{ll#G)LIUj}^?8_wG? zl(sV@zCvj*ML!^Vu|h5w-YYQ}p>$vpaBW7BxYWx^8-?-8JAIo#susQw9)c=@ z#BQ&BO~es^MLmb6Tqax?>)*@J{_qhuT6!2gWlPeoX+ytgs@LJg75Fu(!1fR`kv* zF%GOChi`!?fpAVtkEi;=LTYsu6Dylhev%Kw7ABnI4Np1VgR(l!z%9c?FAHMyXFO3Z zfO<^0!3rU8Nd;o+U?u>Di=$YaPA1^2=4Isy6Mgz8$MLYTnQ!tW@9W!3F-M(oZ2`{OnNL#rEK^p zJ=&h|2iY;}?b) zvWJ&n{P3n<78CCJ9Yza#1RSL853DxiBsbMpSQSq0?=sXe=NIJ(TlR{q^q83XUw=-5 zu#uLW?GBFQkLWg-Y`4GCz&l%w`{5RCA7KoIfqnQ=ISH!|jy`nq+0X9&3pYH&uHOO= z+1-5|1PkrM%aF0b&y|yfK2>1hKj)(_yHWNC=d?!P;TYq&Z8cG}18yz{7VNyDJ`pv- z5rXucj)N-<+4v*!^ApwaPdE+XSJE4l-$0Hc2K;Pu*is~i#nsf;&rb0~jGUc|Zkp+|F(cuDfkJu{E+l~Tz-hY=>*lcj zbC6svJ+c_K{wC7PX`4sDUyhEaZ{EPe;q0jV^(GGK62SKO$bT{_mw6=OF@`EF2azE} z;YXryjuA1PUjCzQ{5cWcyrKe*P8@gS+<)vyJM%@-geW%r#?sHf!=nyA{5SshA94RE zyQH{B%exC`I~m3nFSOC*l3hyd%nFC>#wrAD0{GBasbbcKiVBDjZcu`--Dya_ZM=tHZZ)zC4oBvo1A ze@x@mhJ;1=XW@OTVIc^xfM$883_^18atN)N0CO+M0+*sMwo^y6eRX9ett{)k+>w1D zEiJWD4W)~510ja$$Ih7B^VC1sOwS*EmX3Be(!Dz?>Fu}Pvf>ALBDC7sJxT|MJ+GR* z63%j0jd!LXG)Hlvbhy8vf4G+}&w9R8eDd}xO{I%8H+hp<6~RxiJLw*ztrzQQWBpm$ z-P!g68w428QeXtXa3*-1pg=sk@UAg-(6C$NQamn44js$BxV)0?zxkGrsq=9#DraYD zHI2{Ar>%oyD`c*(HQtR+n(v{!WhWjuhOht_QEnE=Ab6yGIKB$S4M<45ak-}}@nxqy zJ;&*Wx=mcC>a@}vX9t=3oZ1QDAom>Y9`&psM5#3=xNw@n5^bS2U`G~0M}&XeSAmcW zJRE~J7B0Znup2H3Zv8%dzUqI;s_$Fl=0bhmZMe9gbcBoC8O9~5N;2cz$^V=R=zC>P*0Z+*nv&enR`-QG~!_Jz0S zD({8IFO()TdQbu|&xkof^k;Uanb#v9!QDH_^hRNdkgMFyhZ2PyO|=G!Oy(lO1C^bf zaV!igccP(u>UEFO`tzr0XM4--h9Zo91OLVyGOf;1>a5&J^VNpRRZG=oD>WC|D#N_m zl^r)#3&Id$USFxcSIjj~aI@ord5I8C_)U5&++x-D$w|*U2@qamd{m?Ai((T#k6nYc zTEn{oYxRcj1Dn&s5m6|X2J}{Ga+d~tJwi)h5-?+&5Z_p%rI&tNwWqw4UlgIeKD2SqS%;XT^Mj_8wC?IEG9g zF^(z?6jcmR>^5b`Ao#p@&`W#!!b#=B(XbvDS(u={hah-kTl3TH1IVeut zc~WQP!&ryHE0mOKGw+^?BmGdov-7FjMX7(3dh+KuL*_#$gi(0WKdpQ+9Si(K;g8_c z^&yP>gC2$jiwFNx7o{4eVA{Ic90<@53BQADm5$W<|@+41aPgcgE zkaYSe>TqMOL0@7{g)sI){fHy&kJXl4*B|(JXP&}<9?&Q+T(xpD&yjhYzw%bbUZAHs z;}!;d)tB_v3pIkV47N?eo%8+L6DUpWitx{R<=P zMo1^9vC*euAfziZO^n$k3-b>Y09xa)cuhjZ@$ae2vnF#zp&pCmQSLV%G~QN&$AjpzxlX;a=?NROjBI zIq^vX*_CK4N2|_PG=^4dt`iG74*OTBd#bu$ql}m~PJ{DGMs(@O_jE#ImseL)rQS^Q z8k0E^m$7Bz#YWoL*zi61D2Pz>be323+(~n_R=T)lR}*(@Y1~&?_jb3_m!E%<9zOV0 znoO7Jd+*#&@4R_ed>C_k=o&N)o^-~$$iWxxwuDz=+@;&Ww{Wx^cm!s-FKE1Eu@!tA z^wB%2puym@+Md20cT#0uP_P7dkk0|%X^x*agrT-N}HY{xN-NS z0Ro;Y53x@vc648hr%)uhkap4D^mYl|N`*jLXOy zDI@hj*<5yU!B0W2%?r64u?P-Wf(I;?@!h!<7L;)k#BAy`D`~A$PxqD@X|-MV!mzsd zHF&m`>Nu?q($(CAJ1@O}O?lGR(D%L`;KbN%r6%Ky=<%h>#^S)f_)PGFv8JZJfl`>` zxo6d9p$*(6XF7Q;eg$6byq`FtoL%$qywErwFRC{7I0W9Qeaa~4ac|`93i}l}SM23I z2q*KB`^Y!OcHCce%jVnI2S#qc8Rq41ug3e@bYx!VPI|?U-_cO7kMlL=8^V5@a{az} zzZ&v)D)+ZEqiN=&4*$kS>Y;W34H)?HN4D{sKP>zRX2m{4bAociPk(y(JN}7>AHho6 z#3u{}|9FKVef>sp9LL`!!00!2obq4fJ2a(iu5c8<;q2#M8G8*Q4ty!I|H941$!@m# zr+mqf2QOS?C&@wV_#c?;>L^9wW}%eJp>I5#9)6ioa`pV(@3R2KDvI z5D}*`d10j>!VQ#NySw{7zJ~aKjYcr+vw;A+UH|_uhOH7co=`VEPLYg22Ah&cG)8=7 zKN?jIw1wMT4{+nyB$QZ_3J=VHOIhVdeSnWX%rqLtMIa$!=v9-#59((Etu$B(#kdix zB7p}PlXc`tdB7DjCVqs=Q(|^SFxyL=w9sBq`%asYKEDj28?Y9GEm#ADVEQB7k`~6t z=*fLd=~;jRGY_0Z*v&YIxuYBxSD`>Nqa)@3MV`wmH}C@@PPr`n6SGAcbBY_vJrsah zSteX`jhL9J-UzTf5uz_CAn`0r;9G5i8!L{$S(q`710XIiBF*TRR52K6+8`9NR4eN1 zrq#<6YVx8HaVCuFA8CtO7w%FA>I{QHe;V`;z~op4XW)k324BVxoXbd#i8tdC8R_4F z?dVqs{&V>3ZsYKBh-hKwRetoi*5v8<@fY@N266P~eEdl$+sT6B*ez#=yX%I@acCL- z!)_1z**k{?lU#2n5++LJ&=G|R-EcJPbuNIo3&cnHGI z%ip=qgRnrAy4xD*V&v)iWySr$0095=Nkl0}SPk#uN;k*@z;I6~Msn4QQV+y}l`$OB8Z8$bA@d?hKz zBR+2ArB7T4XP>BxgW4wyVX^NpD&JwSM|IPp1M=W}n z*Mt$lePvFQe0^(pwxFJ4K5(nevzivAkH%EdjVmVP8n2}k zpGAm|00hBSJTszYzW2(zaoL52fIH|Oi;CD?1y6;N1$eXj1G~e)i?LF)!tQ&7E7T+6 zBg}%XOihUoQ~F%yj^YF*-a@;PmRH(o6`|Y8Qd(MSTT#X_dbK(ina_ISJu@L1h|u}u z7)g=d-E_3O>1TguGxbk;zA*cp_rISiji!ZVhuxF3v9+7Fw)ZS3;bLqAUaO1EwAh&U z5r2*9Y?_{AJQoJzR<5Mi6v(bm+2M&~wQh4#Agjj}gbva5oRQ#G<1R z=mxK1K3Sg}aRcs>@5=IWT4*)Zeh7IK-^w2N6a*CFjfBf6D|)ADlS`FDWkR`eDjY@d z16&qbE#n1BBj3%U_$U`EvM;vkK5~-F&Ed07PcM9@25GVLg!uuBsptdnR0v<;^HDCb zBL4VrUpS?F=yzbH#sK;bEA=_<4#jNua8GTvk__~`pc{ywKcmGCnhzPR1x;nTyF%%z#x*aJ{&?ol;GfZ z9NCCJ;~6_fIqtDuNAbl@FOC{x_4rsQOi;|aPlbXK1=f|yKsgvUh&Ml1Q5<%MGDadG z1iM&ts6ME+XJ-(*Q%IXQp@`r_4}^tkXTgGnhtP@`b7wua5YPT92mOh%Gfpw?vh$In zxfmZd^&A`?3x4dBWp2lgC603AUPf@`#P#qUJt_}08KIl`cV!AMz?%hY@Z%WIZwSL2 zL*KYEcd&^d4r>LBzKKuWQAB&pmm7RKmIy*iDKF->N{1bX?B-z{m;i46R$Hk(V)p^} zE1?Kyo{{GoCX=KQ<#NVkBsb=4UKpo8&$Hy_IfFvcFPU3`Kb}7kML(p2z?OQJ#da8y zEO21HLVF?ng?8DUwEaZdD9d;=&%r1;8!J?J6b_z-Ka6=_MK+IxD=>0?F}GxnTIMg| zCm-eQys$eOKT(D#OFWn;V%T|6PwI$Elwjy@LtNf2!_WjDpYcTSiE!jY1xMZr!)`e5 z)&yR9kCunmAZ6RB1lD+mi(p4^M~Ql4{MO?y64FCEM87!KIB}fz_kupM2xVnuIW4xE zRur)l14R%5^w`A{r|3i-l%CRIEHX}D1k>Q-!L`WC#mQy>9*xm%Yx#pWlqXKfIk((| zd9-mw{wF8r-T}3HaF}{07wJl)JPRCXN0j!Ak>Eb}HZn%*M|oarPH|-#Q-lA~_};3| zrgmd4wd-?U__L_*R+ak`HQt-H!3PNbDxMe1s^BaVVC*>Nh**u+&~WG(bPI(lr?arY zSy{WR?DnLr>;&f?zf+CDEWF^z;NJPQXrpNHna1oZXcWgIa-?-tu((bq3d?vkFFL?o zk~10;E48M^)OKn%7rcn!$Kfkv!V5>ZI)-C2IYj`)GUJOE z@+d5M(ogAdF&?Td1rOXPufxq2KAm~TwD`K|)K*_u5?|92Pu!?+#~Z!(*8Ly8<3MG7 zy0M#{Z0x0-uJ{`9IxG^|-sN6V;kw{x7%Dv!oh%w>H?(m^@ShVLn5!%{E9uTsGu`co zzid@fV;(=|LgVJ4_EaZMPGIp!U1eDozup!Pijs^z&H@_lw2LuD^`e+E!|`(9kY9{R zFZ+$UVP0|{`Nr6e`>Sr*{B}D}CTQ6CFJas)@*9bR8BGK8>US}(b0^i}$M0yU*T?x9 z^9^CYO}T#Gyk8CZyToPW`X=KrN|QIwKjNsvzxQ|kZ}i*Zi@&ULGGU8C@j!g=gdN8v z$SdLFZ6mAWMk2Q3`%3D6f3@?a&*h;$bi@{xXf67&#u89Njqe04^!}JU{ z1$4NP=pM{?yUg|_vGByA^oC_5%uR&J#`!o6*~o(^;pP0u%S>z{aNt`bC{VC*k%%hnSmLA*Y%j3L{Mkfh8+i&bc^LZmi&$5+S_*&fDqj_ufs*%S&!QR_~mjGil`_Y3>W)?gLGB zRo}qT5UL<7Kv0089@8TJC{H=QU{Z|541zmN;t?n^A*I}u2LjH-A4b56P`8Z}Hhf4s zCWagxAirE^UOz{p3jAYrFz5Eu4qo9Y zW`cS%@|L_gR>*=M&zm+)u@{V}^#o2%1W_J@$ zxy5I=73-+UWzLDps__gbS3bwjrdWxRfBYS>2(CN^b(eA4PBel#%?xDHCJeu>Q{+|B zE^X^5x#Wx!&{IB3J2*aJM3-?aeIk4U{*jdI_&KnBoTuX($fV6n-#KsGZ*OEDxP|$D z{e$oBsKdYa|M+hO3iydh(Fl#RDie2=a#1!DTULfL*_$_i!fv1tw(cJu`Dh+aJ@Beq zg@adNdEXkNY5m2P=t@7`zjx2O zrVv`sX_C(BVPNK+Gn$BMjww*HT2p+FKnN}2jto{ibJ;XU*ZKYj@hKdEhOmZXZV*Iq zR3Hi#$|8a!UXB&A2s03nA;3n6N4rElnDBGN%h=78cUIk81zmsk?78wf_p!wbt+seQ z6gsoUA9gH(Pm|+n`0Mj@(LE6VxbMk2e9D(!ewmIB57V8sJE_rHNK=(sYPCZN<=r-C z9NVZ#^xmN-&F4lupttgC|;+<;MiuvKH_>P5o z#TSY{e72c3ce{c&LYQf_Z#6Bno30ZAK}K-|F>`YW`>xV~V89(*2;IhnAJ^x7!RyRI zBvwtMAYiqzcQL6Ah=ag_V=h_wkJ1I9CYRiA?Hq_-XJ^c%>)2lGD4%)d2rn5s#Oerx zls~(@*tK#dJm3hzKF4ZKa$m-n1yTskSfGPoJXRi~$eT*_>Wuruq;L@&;hr?1qv~~& zj{6sB=diE(AE)Cp0SjJ7xHGHp+(C!(M9n3fKzTZqwl`m-CyySAA7uwz$9xYfqp!!N zQdc}9_{z~evq`-8MK?{e%T47$frKJz8=;ZlhC*^|Qt+uYQ)g)<;HHegQFiw2?(C{P z5zJor;rPm>tLiv5dgYrVyMxQ5L-|5pk9^6&M zjt`7^1Rm3!7^A~oZK&}B*mzMVgvx#~$0_v6?JRtUC#T$`VP0I{jPa%+nkRUdfnpek zz>oYWVum;KDy7XB>s?;z6T)e5p8yE75vC(>hFjyYE$2Ji?Jaad9Va=2Ns)7~F*d zDi3zj0_c?PEiFipMu;2_Gmw zv>+De#ypWcXq%$=veJbzy|e=jRexhlizDmUNg78Wv*3hXtv=RP{+69kRx#{Wt}1bO3-AiSCa|agI_vTZZulV+U~EL`y|Az#zGf}mU0qC->9I6Fb!)*m;{wp2Ozfg%XW}va zSM-{4F&8hpq}j0*v^tJ_<6f>w6z_9&;gxs`^;dWS@Q!hiva_Jz@UUlA^G>Ip?)u)b zDf2-4UDe+Vl-h*x5#^is6?RzPa&IFzH!gbJTryo^H#oGKwyB67F0qq(PV@eg!^BaJ zC?c+IC&Vjg%o6QpM=Qrt_mB6}&gOHa34eKHctK-DK~rmK&AWmayW;e$8-+hej~@Ig zZ9IGA1x>zZ>dw8iqNmnqr^(rBx>8>{I==8dO}!pFr=aC53^~>Kd>P6LjitaB1sOb^ zkwv+pOhWF)QIGUNOKg-kJCckW8aL^y9FN>UnbN5Elmf;?cq4E}NN+_`+}ldux)pw% z`;NsPM=PGNsOCat>zk)#Hx*+wV+&VXgpx~mrgXSx6FSB?WT_rKPEfg zz;P-8{e@S9pJVX^X_YaUI%<@OdZ>OZ{)j~rf|1+hb#Y|L^`sj!SuS`CSsSj_l+2HoFl3Mm4+Ykw6Nm2DAakdEKBKxBpu_cfLbD?*j{*=7$ygc-5s z5W|%1Cu@$GU4=Zj$-!>nIPeem97C^Cy(mwFDW=51Fle|Veqm$_KMbMx@3n1k#1M3+08FAs7_p10ja+ z!L)JlFXbi=GjU?nQOaEBT|Z3DI2wW@4zJ`EJG{i?hyeST6%iSfVXXWxQ>nTkfPpxp z*xB0JNe>=8@RoH59t7J=qWu4`24R`f)dTZE6TzA=)3h=}-?Sce0@SS91aDEoV1Q-8 zAts%K;h~gP0*Q!KM2uLO7qz-*4POinwVcMGcgKH5d$5vBkG7~UXs(H@>i z(S;NycDF?tFq93jyKm`XqFN>x7*Ce{AP_(xbD{Ka#hg`r&lk$CxfwA$`g4j(+xWmo zvDmJc-p&tKzKcix1-2MmoepD;t#+|(XcT)8CZ|)p$;j_vT27ntIB0m-swcvP-=OTg zD67(PKK8&dVmX+d^i4e5vU^T|IK$A{$Z9&JH^Pm98zCJn+@fx_7AL==KgI{%)GH^K zKa|o)_$YvWc!x_k*)77BaDzPc_KP2lJrPUB2^YA_>TnU!KH+V9fO8lZKgO>dEy6j> zh#CFBPnq0=#xsL`5ZkXCB{~|#<>IYp7&K!?_QaiZadUi!!9;}8&JJgrOb!!iMmjn8 zFi>`;e-qALgK!a;-oZm=18{F(abRYC9Ifjx<#_b~P83NG%w!Vaq z8gn#e;U4$ik)D32G%q;>|2GmJqi_8FtN-R77MFkJ=D+wa|2u}w#KqVMO5i;h*N?i~ zpK#$ZmdSEC9*#+@h3=Zj_cYEUlx32NV9<2%Mrnxl5SHU)sGtRUdcZMg13NpIuri5d z5?!s%Dql^OMFUSy&P2CDaL2A=1i&0+$S#iQ*--W{8Ah;S;T=Xa0Mg422qvMdW=6pP zd^sk}$07-^=b|$gmt2${#|_2#{VE%@T=hoT1)cN}yrQKX^UK|p(9E&hE4LZP6W-ov z@~#Q{&dy%?tH1hL+S=Sqt%ZfO*zQq!X@|@c9_7I zu}G;X2jEA}&rVe56AMKUzOf1!s?Sc75Q3bh{r!DU#=YWJ>3R3c6tF>n!J?LF!T8!c za8CL??iUdoPmmrjGEywBLc?x3hngxN{?fpwq^iZcn_2@}MnS3(eGOG~AZP z74dkoTEO8W4}~Yks>^4ee(L)u=I5(v#HPY%*N4$l2 zAhp-bw0I;jD$2n;&+gt~>U(8;N(a63bO!#ZT;eLd(z+vlb5>>ZA}7_Ag>)y!`(8oJ zrR%QWrTU3*d}|kl;DzvNA+0ShrB-dm0>()imA)juox`q=x#Nh(Gv!;WH`ATFchl@# z#r+KB7|E0vn@faBZ|j)Dg$iohM}?%_%K!A}>#IgFW)^QJ9P z%z$S?5>|EBS^eHw5-e+OXO7O>-`h=xD#O|7x$zby5;%*{k8y+5+w@iQp1?|W@*>^X zwS=>lv0uX@b_G_PhC9;4Vj7d#lBpcC|M1m_%+KMN}V|_4gQv6nB(Zi*~BIKJ~m2yo5gPz^k?-kgr`SpZv?z3K@jM& zld-O`(fpUvL6FUEMZ$KEk2H30e_vjNra+J-&yg7KGH>tsvkc`xQNz50H^vGal@q_9 ziF))#K?1!no=^`x@bmOzD~UBn^NwG}SK=#wM|W0mV48=iA8@A|un2yh5mqqN`03-f zn8&DW>{j!UVEwM)!I(;sp&u>_^^u{S84DOMF4UIL5Da0h=%l`iLlI&=p*B$Yryu2d+rA;^iXc^NF%)5sk31zcPp*PpUFx#z|-?}`)llVABlAAr!n4e*PrL|@}Nx2 z)eTR@!63*+7|!k)@EiO`f%{V1&^$^TL)yp%@ORtj9qktLC+IZr1oqJ$vXQsaG3;fJ zIKV_{5>OeCH*H0`7Qrm$N;nYhA88G60Z+f99+b;@$?y&sFsDbLAMuHsJG70_WW)^O z>ETUV)0Y_If=`M0IJArL`R?jcx_@^iy>WldxV5Pv^+UOMh;e(Iew zC>Eic$VSxm;01NkpK><-*k=9!g-R$Y7d{%I3DrN-FvC2agBulSLbJG;R6T2uYr zeEVJRB5N(Jrdn%Jyx&CH)%d%++ZA8XPY1LqW1!j_8JEz)@(PqCvFne;LeZWqWT8C3 z7B+(&|_yE@R!G;5#8fcA5R^3&8aL3 z3m!8r8LMRXqAleilonl>GA;D6h|~0Yj%lQ?DvW3?xK3X1I;IuSF4@6-`UHQZ%NWUV zeC>8=h}o;n^uiKc>%JiRtH9zit-=>#^y+7eBclG8U=XRPPyf?kNv;Iy3IFvlU(k z{AQ5{umX-&)aeO1riz{81834j;m4h9AzR`!2#xE)^Vs42zfkw5J+dZOo*!tj?-A}1 z9(&v^Z)TFrBw5{6UF>32v073C4M~6m=&dj>=Jf!AfL3o31Pyzn?;v2%)#z@00gdKu zOEdjKYN>XTnau6xU1MK7JiRMSZ`^xXNur9-Sj6LxJ+>Y@cFgS9IkvFK zTRfZMy3Z4wD61GlfuBANL@@7)aUO+NEVLU|-7$6#58R0U^6|fvQ0ZR^SEJ(TScril z>cz&c#%tk4`LjUGe5J}kUr9q{m)v}zGcPN*6yL{jWLt@p#CUh>0d3M z!(w;7spIhbKcC`D_U@-muRrDJ{q8mY|DgEdUB<7DANKsdYf651{d@8Hml-G?Q)1jr z)8G0iG=V|!HSl{s{QV#EL0*3HpWXC?lB-)70+B>FM7$zy{>%Y7>14l>cCS5*Yy^@i zY5QB*M%bPL@a{D^08+ z{3Dlam%pr$R+v)O*Ng-44n`2W1zuRncYfQ6H`e?v?*8s^v$ZEsfvaQ}7P+e6uffa{ z0kSLMZ0Wd^xO~C@wKU1!+Sy6FJKO3cW0j4K2Z@XwH85nMq~VUqVIoB?^W><*#l=NW zsJumYoTD*fAc~cSaTdLI*W}3q4--WOUM4AY5)ir>UNsHElRg838>T*Das$%^BdWnz z@H1HXND(n9Fm{CH3EEHsdJ~=c@L;Y%0cH{}GkbYZ=aTq(qmdeVIE%P2yromXco25V zUAJG>0F%Koe3Uh?>?w=Bi&BAK8^QnsWpZSEb0UHfqT-Lv1ZLcm9SwF@!U=q#J6|Wo zz@v~#-vbay@*~4!g}R__5zs)i;Mc2Blpc6TL1zJS#s^83Fy5sl=Rpn3bMp&n?f!i$ zKVb@(*qxin~ri59TD}Q~4UB5y(#ohbiUZ zvxKqTt{7;LFEEzF5XWKlFT3gALHNNT@^du*gg3uYyIm9BxH+)nIUFz3cRZkvw1F3| zUSn{0N}T*%0+KdiB4juNv+-Ec(+_UF-#K{rIbHk2OOMO$O!?N^amfqMu;UmYm9MVB z1$;!{45PzlgR|e^82%YXIhC|}qu^N3hEL>*HRpu~$W@^D4kwr0@2KfWyAwMc_@Hg{ z{5gCM6fay!Q*Xj%U>rS%v%$ZUXvt4d7zljAucU1wJ1w<1QYXbb(&neQbkpW#{|rF* zbmQ9HaAJ)&ZrLf^WCBKvZ1`hUW%Q&Z)BOrO#&;)O#_DX3^!1I!Z>%|f1aVMIj!eQ4)V|qjKP(tr=*x1x#C9UT-aEej;NSa?f6RR+@CHmO`!(4_ zAO+OwQZ;rVbPYk!&Fz&YmaU%tCPMm8+U;d-2RgTV-Tt4FWTjO^Nhrtl=GZ z${Z`6cnggW8YNU-gly{n)vvR{l?gArQQXhN(R(P}nBexOK_QR31yJ}LA8{00%Y4d! zU`8o|5(}jV{Wf{g_iH#Z2(Ii8FQrEfI$Ab?@V#88?T9q|OWGBfErFh)lP z(wGW5F*2CAe`97+eh57#hSRjZ`;=DeNIa1ELU#L9rzX>ccs5pn(oPUmSn-F_NVw44 zJdFuyjJYUKS_lD7SfHe|E3;O#Fh;ZbnAM~LOE?8)L{~SSXfIVKJ?Xv@&w|njArZm~ z?qWFD-?Lz0M?C7w=P!JG47;FFSdPFKi1r!38I#y`hazWtXE(jtSWoL4n?7oWBkd5H zbAdlflhmhiA1cuJ&h9dVGQOWeWw;RzQ2rZY9k0} zR7CGUWOa3e75ry{O*{ZR^!V7MS1EJ<39w$YTj{KY;QY*Y{P@^qC9v`8W%`pp{-gBb z+1DcWi&Rtnb0-9}b1D3?LvQ`Xv-I@I7b@SY)UUdoMd2qN1O5V<9P-Wp_`Ivcv2rZ< zf!ARX61+V;604w5N^-9X0v7l+1d(FvywmI6+Ol_jp^WAJtfx=D)bpA0yGqLo>|Usu zM(EFcq$fL*grm{XiNsx6)jN?3C!3BP>z4 zH4ZtZ@Kp41F5JgLI~JLtT!Bv|EJrR)O-;p7g?fBno{t@@q?u{uBYz)J2LG+U(pUO; zE767fEx{Rr$5>U)BCQbq1%Ga(o#N0x)0c28824@<vx^TMy^bb=Wr3c_mY zkYlJOr^ZaH(2IFK7flVDaq z$}f1~O_^Ju1OPC2d9RokEFlo)xG^5_{J_YuVbnhipqW7MM^x|*-;Kad;{g4;++v)K zu{o4Xr7xo#%w@qRb1VWynIe2=&P6(E zqbOBrkHE)+q0H1l%wyvCFv8O>hhj?e2#3_K(j#34Y!+IA57(a_xBE+=;1=0^`74jNy@? z%(ycT>-cB96?@F9VxGa+KwQVikFYj`k2v9nclbxy;TY}cI$~}}e({d5ow(UVJ}SHF zx-2S+a1j>M4IL)xS*49cO+OkeL2by zg&edV^-Sq*thh$00B;pX$HtL_jOFai=E%82^)HO``}+s>Q)IDcYLB85c3$lr9Hi~- zUH7r0E);g)9NuT(`pkS_jh(6D(->38i#*u9<#A0kNHg}n#=u#PJ9FvVAAXoVc>l4+qN){R z-X$fThF#FmJbec3BV--$E_nx({6#>*dpszCX;+j9#R&L_`~Qk1J+O zL74{qLHi@Z13Xtb9+7rHn={`aoS-a%7CEL6r5Ouv*!_=!jh+)6v#5(>A36S+(*S6n zEa0lwkIZKt2~RA7W(RNNjXW}`E*K+XL4fN@2IZ^ARnadG$CR_%kz+lBUlgw>{&MhE z^>uNYW<}d51p9}_AX?*(Hg}|Y*xXS)v{1T<#8n5Oo%9NVd)Q~VDn7EUb-C!um z_70EI*U#6}#`eA!LzR9I6a8cEe>>l{iy>6J-+e*aY`8fgs&aq=}n7(hFMPx@Hpu$I5duS;mP6svUh|r?lN*1yheFiG}fb|AY6_!-o&W7*%}?3Bnz3*;R)g%rp}K4c0Kkz$f6%EI2J5 zXQnV>(A-&4=E&QOtDazFgPFDB%L67%H^LYOP3#Ps;f^4Pl8_JIOcq!v%<&^$X^5aG zGZMU69kR2#n~v0h^9@ks^@e$i)30KzJfK2UT5+aKS`IpZ4~awmX~2*h1^ zB5;Cf@Rojs8PVWfou5zh3kyzzZQf@bTOhh3Ju;*oLogs(6Z1m)*9ae#R+J}b+yX;+ zGjU>NE9vtG!v{S=8>ESX$rC=gyUbRE#=r}cMTt$Nn`YUZkKaqZbWn=gJj>jJzcS717n|`q6uLzsn zY5T=Q_y`mKQGVPZMNGWxn*GXmyd%x9Q^4?l9eAhbx4()-w%$NEXSG~frEk%9(-Q6^B;EVg>rQ2n-5zY+?EI#4!!uv z-W~t=)k9*o$So4F-A^`Q)sFxud4p?e#qs#IYk2bOB=iR6VyH)ZC=rMBx4mRKmTdSY z94Uky(}7W@q)iyyyVRyXSty%}r+|ef_zP+(u`&AAr@N5sZb6FU>f34iv-2DGB9eao zCdEiV&Y4~nx0|m&d*im(6R zKl#7>7*58MarNn}42Ks%iDPAl#}Z)Xj!?Z+KN=Z4{w*^Pj303kr* zu$2xDkA2Kgz0vehBfQy_<6~f$I4eGaD+IU*N-U5X3SP>KAriZ3gfCSBt7$n3hg~pd z8VeB+vLkFtll2+J5`bp~!OQ~&iv8XN9Y+8R&fX!oS_*p;nudsuuxWqLX-*5=Yet(umX z7Sr0=YFf~HYKmPLw@Ujc9qsR>?alSHx3g{fw zCi%l7R+0>>JhjSnT9BWQ6%>6~(4g@Vo@7X6Bj%{N z`o7A{?w`i7SGyw+;L>{E+ci3wW@cu+a{TJ1KOL(sPsGcxYX%(qzK=Hi;I(moCK$#v z#&VAb3KmukHx3U~|1I+_2$c{#vgVwl+o)UaJm84zz5PS+nP(!YEAP5O;WerE#4tx# z_NP&mi*kseGS7n|$%17)u~2Np3N2P%bMy}PRdEat$J4MPo6G-aE8|{)esOw~HeNhQ zPd@)Nt-pMh4)%6LpG}2}OXuM!P`1u5Ec$MdTCL`^eN;4*M_(k`V+Yx^>U3UpU9DCu zbcN?sMVRlPeZ#Ydz%+!}2vj)6iX-k&bifxP?4c1s=cRoy4?t-`ezcX%t?krk94f7m z^ytxh>HhtD7AV29q0E8LL?Gl{972EpbMSr3%)hhzMP~uIwEHk2&{#%5dZS%*~xmodyecsi0 zsJ@}0valFnN^Rp-<>a_jdI2kpgh!4G<8HRvY&9(|)GWC4d`fc%_EOz~FhRaS}=y+GxUFLXX?>4SXique6zsGrEC#1{@^N*cY!bq9`ssFP<8JiV~V zlr;D)KGdVfJ*7ikTOp_rD4wgcbFPbq#yMcGRA$sZhD=wqyIav7b7qw7j7{7XRd#UE z_n?gTdu%-V9FCGz9O{XF1t6dsw{eY$&?No!jPhY8En@`A8O9TiPMg*E&F)O@9-FDe zy-(00JWQX`zY*LV4|k@tIGWjX1bwLPksp!fJ@FRb{rJ1-H-6)9ruW|emUnhlDho<) zKCP}jO7A`XP<%xt9f;3*`s`);{L8P>tMykJyHC_mRcBWm=g2+VYE$q<8cR6kXGn|< zeFwWUS%^y+!3jz#>KNQo-^};9Uvngfr;O86Q&5T8Y4r2-bLZ{zw6%SZ*0<_uzi}eo zQ0@3eZCv<^<6UFS6w*{*H$L9=;lq305xupwkv{$OXK8bD)4PQ)&rSue_(YYV;iK_d z!rP!1g3O4=AsrTXu$aTtp}K}v7}sLqNgSKX0u=B~5EK!<*H(TgdQkK+?s44q)THWP zVz1ZTdM)7% zC0v6e%GD-NV0jURV4+WA!G;%`%uJil0WV$vBRT{ZDC(??6AtOWJq8P2`v2H5#m>XH z#}a;rcvNaigy_w8A#I; zLw-0Slm$l@r^l&vxR;hRmanZXnU|rRa?E(_5NG%Ox$Hs&?rI0PLnrhH?8I7{ucrGe zH9w29)6R>&g*Ff;1F!&`1=^}#;T*dPmf9yx%^`Nh*K_ykNtzlNOmoxX+xxE4iRKu4 z+ncG~YPxNF{p3md`Ild(-FnkXGTOTUHI5+4PXE^P?tK{N2v_{dyVx^H_q&*Pxszb=M;NPA&YUxAcLLWbS_z4Y0aU!>1I z`NXR?B7}Ykpa;g3T{>Jw4TGUkOtBf*xEoEn++_R0<}frg2Vi3q{7 zB1P3~94l=GMAD_cU?{;Ce`c5&aMTH3XA{9D zVs2n?xHrOst_Fnj3mC$4Z=Yw7XF%ohOs|R%9BfJ6-Q7*=>svnN5ayAx!w~&-7-|H@ zfC`No(jWLPbx4!Q*76o_Wq$`T;ek*FJmTS&+meYSA~ARmj}67KhZ^{qP~vxa6)RK0 zEsOyGF~Hw)43FUQgiayBGoCOQthND%)C2LTKPJ8i0x#Oax0uMu%4Ax7^e{bo{DJZs zOl>hl7wjTbDgwnc%8K}FnIi0_AU_g?o3Lh?h-xIjG^YpJEhu{eV})r7!xT z2omKXnB(T|2Uo|B=x^X7dv}XgGEyMha#+%alI>_-fd~;P#}G^Ja=5jb1U9<2JG)-@cKjH9_n~RgfXAkGipW*~RmR%Gs zz${@)?u5o#Qjp1((gT!`5jv;SlQ!_No11_o9KTN4Vf|zOfT83?TC(FPLy9H5W8*CU zoJ{BEpZ}|0-yL87?SKFOzJ(9qe1C?r!2wq3hETpG9>6;$6iz*?`)maDOn&jF4Cm+9 z>Bz#`Gp~STMK$~ie24`?2s+%?he9nLlxzt52E0o0_V(O6o!IHa#CJqv8bTm;n&Hom zFUBDhEF3e2Ab`3XQhz@pvY8Yt)6*LBMnQ!nsPb`#LRCvZ*##eUt zBfQ!Yue7nbkzPE1mJav#J^6ib|3UirH~vPNtj=m;j-X3$sU-7r6-~MqHD1k#&QvnS zH^GeZfH4$Gc~R=wsN$V6!gw>CRh zwSeRFxRox>PBs3^o&HVrjez&b^B3kL-h24KUxo_NSTkL}B~YI<~kCC%4nE%-o~ zOnU+!jN_CafekzlxEl~&5Jp_6(VPiJFKQ7y@M0VTXQ5N(!8mFP0bl)KFMayyCssJl z*XGTKbBDyl_=M}CTC17qf}dcuJ*)21&1E`o)vd@I8J`hfRkd(cJ)xkxHXnr|2Hpi> z3OM6}Q9GiC_ zxY= zgW|h&lFn5gDx0XG9eIf5Jh4fqg7SqY*1i(rj!a6Y6yf!$dl5RA6x zBTCzG{|a-n7*OdhRXemDCCPjSz7hc`w8gQMD2UkQg|KsCVpwkCn;};5B2}t$;&-Q1KR2n>)SO6g04vHg_*!;3A{?KtR0UIVItcn`yFgYJ zh!sAY{^4A8#wu{1Y9QP|2M7o$6FUPCm?2n$Pvy8NAMd2Tvrl~|yE18C>=@zB8IG4I-uJ97c}aK1e@ zI!qYo6(zUdf}8Px_JjhF@xe#*4TwL_#*5h$gkDcSvXdA6a>PT(O5e?{Ot*Ojwt|s# zgx_oR>2d5OcfO$vCt98(f+x`^?ScM|T?OFLW4F?V_lB<6J&0n2K7fS;_#s?wdA@>x zo;r#71qRr>z))_qdEzohWS5#3mI|-LV+T+%rA$1O8JaIRig`ct5coFXMDCi_n11lX zT!|JqKFd3DR6djmC}f}`VDZ>W|1LXWqAuxY0{4`ec|Q4)zUz{PA!CJHHo!qx40s?u z2A7Z-P#Zla!%h81yzGmEOi8P}!y|j%G0+(O4ls~TfwLH=(Mcyv2XAu64$jy$L*K?u zN5%_q%p!q@4jCO&B5=jE~W=-%c7mLw7pvwA91ce3SMWz{RDz?cEEBEVemYr zX14+8sRiF5KEXTgL~r!jEDYx46UH3s3EJSe!rI)NkJ&|$z>XvqrbK#bdnzM40GS|= z7Q044JIW;bUfMg9F)mtWk;1k543zNuJ6q}Uteut?7gVlQ@5JT^z5V^ew6}X;x~{UEKse34$hdaiNo$ct%E%yXp!JKxtI4Dj+k1kRHo9x z!fcwInNk``TipU>q|EfqBYNP!KKc2l>5u>TkJEGU4%`7nAIEXU=VvErdwa)i|AWWx zr@!@^znRuFhL6ou(%{IXhLJJBorIIN_|di(N5NmYUxLO26G|m3kwg6{cai`HH>P>wQ3pZ#>^!*%*%g!hi zOy*ey3u6dx0i?8mPxRzBeWUssjSHpkDeZ`MDU!3i1$u(sdllRS3)!sF1P%obg%s^x z)TDZ0(S(&g^i{HZ$Fa&!zk*_rHiNQ@aXY8%zAa!7?b5HvhlOhJWR?@co2f5iQ4)(( zX2jEg7viA^q8x)LjMX+6>)^XlT(Ya(a|v~P9-C1vp?I4Dj&Uy}(J<$<-M^^~KpX4| zgeSkcLfP0{N3Ium6Yu)g zykWjNmF8wRT9?J+jNhT8<4AXS5O^>5(LBP!0MkG$zxa^KD;nlBhfR*_eDXXAqv9!7 z(!Y;QyZ&Jm({u^t=Plt&es_I(@%opUG7^>;chmH@K4|mB_^89*{o(Kb*b_o$1|h^? zNfem7c!v*ucEKM0UlLsbSW)9^?9x&DnY;@KdLk%AcKS$vl9v;PZXHAA-_7vQC z{Z$%Zz!<00k-zn;S6K}g6XsaG2Q4wkX5x zl+_9%)|kOa_=hvQi2~m9mr_W($QOILi}irCsVW z*NpQ8Cy-$G5|l0AY-GV31Ql7QW!4gG+fD zhpwlLO-CsCDx9n$Ifr#n|LL9cHC~FF9^x1H{Ebn-TLD_agnPhGvIVtv4^JDT*MAWp zxR$P)VUp=Up#M@HD_=@EaEhRva`PE)reO+~!r-xz1`!#TU@FUkyD5!`809^3W!gbKi(MQ{=uo<_%W9M(yELvL zj7Jd5v4IGzIqnc)EGwxIZcI;%d56WUCYh|>yt&i_wy~GK`s@=upQVi#&(qP~UOG8y zq)S%#*7s85U@sjV9Hh-x8>zmp_xgHz`t@@k>$ktR?;S*kM@L@B!?=q;oK>yta9V%) zO3!*~YZ8uNe{OExE5V_2ga@oJWpyfj&`GPAcDA>a=3Y9`v%kBWHaFI-JVAlRQ9~#J zxX>6Vt&E%OQ z5jirkUZ;GUX?KTJq;Y%^O_qswTj3G>Y;0^O-RCM}!()393N)0@q1+Js?AIIKHN+&J z<80WZ(ywuFWMVwc&ezf$a8&2gC@Y~Sr_;E2QiOJpI0Eu>1V*CBSlDvrdtKY-n%a*{ zq<(}x!day((;P(oKjgv)mGIzTJa)2PI@NcvM=0em-iydad z+oj-wA490drTFa9f=1X`Qv`ze!_Tpk0l|0KL4(rT%1@QcEBHm%@ZXdHUK8GtBdZY9 zaU>*yI2gBM%_@S+)r1X9Q6^Y2+BtK z)Xw{_(+n%tl|KSLcG0n_9@@L2UqRp|8nBR0u%KXr$EQtt4na8C5h5a3;yZTp=%Jy?c)kG5 z2{+WEjR+=aK0ZBX$@38Sd-5*xC-W9OVAy_|mxv~!?oqtQ5sQqS%(HmYA9)TWexCZJ z4hCHo#aCJ=|0pZ8T<)=fp6E9y8;ToXWMl?L;3IG5ZOoGpdY7FbQG`sJf{}J&9#C&Q z8C$>yAGB-WqfaVt+CA}khzE?o#BpvY?FI*-Z>}(i9ZJ-b@vONL^K|e{+Fld`-h~5% z*z^muH_vgLI&CcKf+Oz?UT)u{>k}@*(a;!pe|N*U9&qb1uep(z>ecgXo9v#$l$eH# zKi)b0*A3ry-Fi$8&)ki)9KS>2af~6muI4z_)lV%|s_cH9aX&|$KyxQ2 zZSMp^xR1b{U9jw~iGKUqi+SiPPTJ>*g+k||0qWHKoAM_e7IAoYjK*Qc(EYl2lY?XP zXy@1LIagjced+X!UH9}sm(J@*VH?Ni3MUv&FFlT{TTx%a-G66ZxcvO7w0C?PkM@G4JFOy|Q?N`#?F8R)}*O_MK7cYZyye5TMS$?c_-P=CQ_LbTI5-W9~(L zu(*Vy?8pkJTuOS}lOn6D`#8R79+pdW>dHCQ_di3yt?=vG^ zl!=TV@H`yjjM5FI;{HKBy?iAetzNg1m;5-o+Pj*?lhS`MhJaJzdpDB$UUtaFz53A> znDJbQCt<+=Cl;`K45bzdm0=W;S^2?nnJjvlgpU$W!Et_bl}U{c8heC0?n7nVg?`vM z#*TFGurOaqD@!#!^J#HjG^DurQ4aF90#yAlbSjbt?KHulTj7cY#L!l>Goebjhi8aB zHe@1Yu^Ho2JS;M~a(pYW9anv;(g`ISYo3sIg#rvk5dAL4IG%{NDGEFAL;ngLxVFmZaZ~)lwRmJvhpIqzH{|gfJ_w$fvQLP2<*4w=?5q{AC=KCDz>Rk& zYW$|3ho6C7>8ItTv3Vq|EX=A6@Q5#;VOJM2S9Z)_d2tdnuWA=>)n^_T9+O`CMmRnZ zufT#2=vyNqnUCg`ONwE0wdpFd(&tJ z65QXQr`JC^^5WJBQPS)9Vajj3DO^VwWmo=4&!6!qF$D>C2crZLnt%=~ySmuO6F0dq znQ}aUA%woYg4!SaM+XpTW6$mm6Y1i_ZzpXT!k0XFB7VVbI09)7?({+ch(Df02v4Ua zW1$@HP9*hX>dZKzj)@h{7feu5elbAFfsn+4*&-e^10x61IklZKd7SP?;e;HH5MH*&}Y_5cPPtZd{RtM({yz|Mf_m1ydm%{Uh( zR-VKy3?gO49upx}Jh7^R3n+=F2{@}Z1t)_jOb085kB^QOrtR?F))1KfD>bGMF@k<* zOZtXEh$4ytOc>-1E&>7uW$=UDg9#qRF5_QE3-@s7yaGoWIQuvvNw|l3wn9e(CiQ8i zfq@^cM6uXW1zixfw8<+m6)@QBUV@Qf0?#Cs6_yOT17b49L=RIO5g?|S;}xi1U;^JT zI0#8#zOA5CI>5o|?kh3OrYU9b36b)G23ZNq1c(VIMdq#sCXsCA=bH&JaE0)I?dhN< z=!ca}D2Bi>@R2^{4F!|RBRW9Q$I&mWGy+y*kF=mo=v5(IZYIpiivVS(B1%=#aGL^$ zqBT~f``AXu;nHXFrR{)M7z~9|=KfY%u09^zNK=e+H%di2UGS?L!rwiDL55+2+WUJv8r4y2?fdrsSa8RjzSwIH2;63P#C4V)-zi0AOK;f-->*!>F2-F%%C76TP_ z`(p2L!$jQp4lmlOzNr7~7ba}fNr26d!YGoza~x-$GqYQd3B?6I{?I$VOZhtEON8(* z-BsklkDYVe@Gr`U;?@b0AHGT3c7KFDezOfXKLIoFxSaOvM!H*`>{GmZ-nmU=w*rLY zI{*ee`(@+2^G9~-q!DT2Pkg}^2*))Wx$((kKReolvtxD)MWT--2|qcLPPk6s2;j6c zurYQ<0GFo#t2fqw4TlJ2TF&1#_U5OXj_cpHpaIh#PcZ^8aF09x`pcgkc=(sy;NXV8 zja;w`h@jmZ9>XgKj8`-|tey5pg5;0Y4l;f#75mxtYdz|4c=@+}+-h@t;AP^zBzBKn zo@)Ypc4EORM~yIfA5q1j45ZvXhK}*#;!J&cC~!uH`{O7QO>SAy+jq_GiCc{u>?&rQ zKsj-onvK0w-`h+to_(2KeEnH^_55oq*ti2|MC0k)Ox1S;u=+sEpeX_0xym`Qc zIHrw@=8srqD>^zlxl9Mgr|JAgBlFOh9`O<4odz^6qkQ6yCkyhG2J#qIS?})cr^DkT z3!vZ|SXqx^@8!mZ{Se?Iv_{c3CtR{i4_=whg8Z^Ix4JFIhUwxkb`2YB~>FD@Se9?J2*xR)N^j5TjFdn{-9dy{KcUD!? z3!zBn2uOH!Qf0xE?|IQj^u2wCpF7h~{GFT}TM2mDI`XLvgt0hIIvg2PU!i%#t?1`yeDiS8?G#?HK_*baAHk+frZ0vEtM} zN18T#r%c2ANh}P6R)87Bqi~yfXyzN92O4G+jm$A<_gM*}1Sm_HD}XSeGnFAUY-Ln5LD62BOUhIK>;UGQIT7<6+$a}wIocCxMtGG? zo}NG36ucC>UeIe!zobQY(&oM?=!d$%9sJWza+-)2pBmT9b@X;R%!M>|D4gj@4FWHQlgpH^rX}fg{^7{?7JnBI}^1r~~HXC=G(117_yPD40TNOz0uuKd^Ue{$#dN z$wKSc&4iFY#+tyNf>+c4f*t(54x4 zRA$;LaGg*usxx+b(>_sR5r?Di7*jYAh#m0rbK)DTvTKavo+%c7k$x-^k6ldMicL9axzX(?6Rnbv9~C`;GcQe$q1k9w3Qybr0?cBX}ka8 zBnHOXislB4%e1wm@thkRq);KUdqw#v06Duq2d@@N`Fdyl?t`Z z{$2NY_uAuK?3mZwd%iKYB!#wwCVN7-2E=*UG5}U{P?{a z>fQ0~m~R>`o4+hw{7ZdP8G>BeooR)67R5{v)+G{P1N!WYA_%iUiF6 z$U>kJm3QZx1baOlo{l31UJSxV3szn;4rm)8LpXvncHH!%Ah<;+dnr5rWCuOj8t}_P zAX)e&fSv48{Bf66X>_8?V!IlynHZ&E_wG+8?urWpB&pNO{Lu z*5}64^%av@#rHspaz+EB+(_$+m41p3bInAXcUDR0&FXO^=czlSF=@E%m>US zU_>4L)f#H0ZxGsn%9v1!hV<~qw^5~sH`v3#_G0i4L+C;YIh-SbBjJjPjqxp}0x#Lg zZ*)=ibg6E|X8TwUhh6;E0&1mX9f+7?!pJkiF3x;Q&)3-@iMbfbY->8d_Bf(k~4l-G4L7p^V=)l#P z(!vjhALbUjk0TQ7Fw1V&a$|BAFrT{K!c8?K_)UL;AH^Mpi7i4L>Mciix|9=|B`t@; zQ^t4&e!;0MaZs6p3U0+vXzF5R*PIxm`)dzURm_oC7gs%Tc+*BO#0tJFzRL>}x#1*V zbqxM4{$0=Bm)(Ki>EY;bB`^l)gGPDt@Ed9KD;KAsaI!L9;cFke_of};Z7p#zC2(|R zwwt~?Vf7>9D5OmgTZ>1$!s0+OIj*fe_^^qx1Y9LwOoS*fQzn~SkNlEq#0?XIib%VZ z8=HUS=YHEJ@^s>)p_k)0LN{Is-3u45uw~y8NI{&l62mEj8Ac9;HXX2=h)nV5IE0g4 zI7jaej6DhV#?Q`%n!HOe`|Cqt32s`)QjEXD>g0&7ie|hGIKwzSzHuasU3+m`Y~hoG z#gFl(H)9TPWPcldbi($S@Go_klkpR986S?6eL4UZlViErlW%s)rhJA|_~V8H@1S)Y z~ro$=NGAO5TVAsl`U<`4eU|L!&fqX-yd)jg|y>AOcX1~1RgrPamxG(Ev; z=r|*vT?rhAgV2s~0HHTUpns?DWw-hI`i7oOD=bjTlP0w+=3r$mcj8p$ zYH49%#X=+|{~&!ryIe zZl$C8p@sPfPnhH{E-j>m`I-e;yF2^o$+Kta)ywtNY@f<~K7H?_@4$ShY%IKC_rAt^ z6=GCzS!l&EZQOyxJw+VFO}rLISZg9qU4S?4$ztqh*Ngd;b9hZ9C|Zcs!bZR7W6--) zxbpzz6UW0LY(Qbe#q8YKgff6#XRK)F$T#37HvCarIAx*D;$kh$R=8j5)^~TDpSCSn zTom6jBRab{KNUVMMIQ*UudMVu*yp~Zy485?`)xNAIrYpHreY4^h zrRw3~p_Pk&@spoe88!Y6qhhpmK!e?7~8-%`b>P zCY?UC4F9;hyPvjqchiASW>7o5h@Atq+1d2|`+{k@B3!gnqj{E2Mep!IR${<|slK@* ziTd$wF}cC>Ay7kzd?cQqBlD<7=#n<-yTA|(3AfORkEOikw1`lq5f|mIkLgre@QUQm zjz986S;2zBP^Jj~YSUI2yRW=eJq%g6R*o~Huk_LEsxb@qWvAV6R2@oUc6M3`q&C}9 z+iD)8{Jyr(59RquOZBNZq|MG%_{ML48>Q%~U>Py4SoP1nQ!A>6Wj)BK*s0*7z7%zq zU2=k%Hch|cqbgNS=6$~N3qD)lnQ9(6oVqrIM;a(RBg`F(`u^sDgh2(sCk!ZDjDI^jQP zAK-|^jVN)iuFgF_;C?guIv*jZaL@tu!Q*f7+e21lv4aVLI7(RNlFW+`%&J`oD0X1c z&jC01pnf<_#`Q`6Cwd=NpF(?8BJO{^$PQkfK3z1-T$Qvb6Feircg6+gV(iXh?!w*2 zXKK3~seY#VitvnILz=H?{8IUwqE&Y0p~R;z!O-v1KSMk88$J<2Z)gkHpgnN!xe&NE z9l}PaoX}-1GqeocT_vc>Cb%%rqm_4hBR7a}DxczcSES%6{=kAVkvDfmyA7fU)nDXA zTH+6Y*?wv>s)G<_hk^?bftz|jQRrQBf{(ZyvkyF^Wu-Y`_4Zs!A6BR__K22QMC-OJ zJSdpFmG2eQ#$Vtr6k}?A=5ORLH#42tK$j)1AG`2m0{|HE=Y?Okcl?}!OvhQ@9kpo-9HO+;!Ebl6RlcFbb7|Z+_7|i-RC=A z57jPF=yAL<(j1PRqc5|PNW36Qq|)|i%P36X19<9(2kC$NU;o$i=YRI6>R)bslqL77 zLJ-fNJxyPH`DJ2PKKGQa-Mg0_JbFJZt#WtRT$Zdz806?g%Qe)7geudB6{t!(lwtIB952bZMnCBh*WZ+n z<8D!Evfu=M6I@s+smHyzrORN-WyCReduKv3r{_0DOuvAwI!NJC9vy$ebWbXl_hABT8ZL2p@HD z$o*lAu^NAcj2jIIj2qM&_otz3gpaT3?HzK%>i_8*1wVZhayT_R;Y>V;-W*}hU3833 z%s03zm?PEM?a1i`7uTXg<*_gKy5;~Xmf?Vwyg*L)8J~))OXzC4G zseIHmJLD)Ic(SZZg&cq*6l}4>TJn)TgTmXoWFbg-}S~;zA?7rZny3`{QTRo zN9@;4Z+Og`Y3Gk@di^o(%kH?@5cO^DHUTI7{oN4nj&sMT4$1qQm~Wb931!%_{hOFl zuiwP{BACh7{!Xr&CPy9i{lmZik3H@h;keQp0BFuUe|G$12*c#UbRvf7eD=6^-6D3R zeJ7%fUHIuSs*f1JdxC~F(g65wl?6;W7yn0^@f}6Vjx2MQJ$vzQ_xu_8>7%3_`E-p1 zTm*{$2vy=3;BbQp3Qv1Pe%X|Go%p=@$fgs`Ul`f)N0hubE|3-*;beCQ(34IlZp7=D zjsrgqZR5HC<{a4RQim>knZ-$$F)M=!n&)FJ7k4zWCCYg?sX#$rkrnxDzJ> z4HlT%@>=@Q-}!^|qaXc&?-ig!W`!I0VlcAug!C1@42a|t5D+Nrp+FVP45AEPg!h1` zo;ceXl%0k;Z5R`TAZ{cY@PHcz8KxV?9;S>*p%oDtV154=X(&CE77QXW*<$H#^{oXuh+i=%}`Sa!8qdO z>V`?7LW!OsX&C0=aaN*^d8H|W6e2T;pv-2-G)cCQkQI&c^yET=JzK3$nOL5lMLL?S z9dbOBm^~&&6V>TdU06tS3-i7ogB7yC?-gp$(0SVmp*T{6Nt7nQFw#noU4}4E%K$NgmWSlUR<+0aKL0*ipJ>1ZWTP zvCv8k1@r{d#oZH3k`QFTXu|-q;*GGe(vGq)>0;$(?4DzCActU}WT(v3frWy~hgHl1 z*5wPqN8lCu!|n+W6{v?dOci$89DZi*1UG#b%CDL6ne^zv9^~mjNEX@XOy`ARs*UxM6p+954HXABG?*v;VN;u(5YBeeN5KbmV0#YY zv^$B(5S=$avO7Fhrx&o}+fJ5tMK_m+;3e`}5Itlko>Xm~bVg(=36CcQ*JJAC*nn5 z!biOPfv^ANlHFe~r~LGZUyk745~9G$6TaC_T1IR{E-}LiIKwUChMk;^JBO29f!UqL z-48a#L&PCxVwIHNW(phx;q}k|)xV0UzXtPv{m1|8)=DA90Zo)y*@-e^V`IzxFG5?C zPYbitX@0)q$uc|)$I>7)Ly&iVewxnOCq4#lOnwM$pFMk?zWVY@P2!tg_{8`(H#?VB zR#y`{JP-h}b7N#|%*TT;exZCKe}tnR=dLf(9IG?urahSq{sdSVcl*5>`slcw&NODy z$1}E#YeG9YqA^b0ec$bsS9>B*;GQA`_ud6HGOF<}Pn0#5QWoy}V1ms3G6)?Il1vCj z6af$e^-_-JYPS(^sodfRMwC~D-6-PYn8dS#0|681dI1s22Y4opoeb&|lQU^_V$%0y zK^db6F%US4*4n2hUSu>PH}VgHW=u<|C0G%emJ{)fCvA>E6fY!rysBPfI>!c4eir5+?2T392Ua#zE7kPy!Gkn6HzT;N ze2n7G)~@LPCM_>>&{-{Bo0&{A zV}qh;)t|~>g$n$L>iqcd&@^=*-v6gR`y_4c?79J4ktkYNURq8ceEZvJ_1>y4;pf=O zZ9T8n*VC6@exCOCwo{{CH*bevW^L`BSGWV?{d@QPuy|^BFYXpTZ8fcIWZuDQcN7}m z`u2CyhkE80RuZelhezR`ShX%ZwazT4Y_+)$>&&~RP|i+IP0Rf<9W>7@L^@TypakSD z3}_$aBZ@SX8}MleOi}bf)3g8-L-1}0eYm#^`WX|i4EqS(G*AdP4z2V(63ncSMwkgb zp)5mzcq_W|j>8UwG$eeSa@C4)--zd2YoQ+zhh_=mVOh4a39I*R8Csr4PUJk;*e>dZvw!jEtwH zmDRMkwBp?q(9n_k8E62(^8D;ns)#mN@eXfGTAnw+YYYFL2k6<~tEZoT_C?whZCg-C z|6qK@@o6a0xo3(UQWuxERz$+*b6*;YcKR3ib><)7g8bQufMCx`HsL>%lA3D>4irKt zMZh^nRS|cJzFPev$E#V9sr~>M%OW>+7NJ;eqkL8$#SykFbYt!kV;%Tsp&Vt6c`G|x zU1qsiAgXlO^+un-xac{A@_%j4y)U^{4`oXAvAjjm%3(N5NEn+KkGl2cY>TJoE}q2*;bW%5jG5rn68Vo?mGJ zCpa=cWCY4hc{xoP!q5(Z$@3qzGmbJuIYxPzKLH#5C`XFoi!?pwQl2P0q75m1*QmgC zc|u|4`}Qc1a7{g1aVCF{8^D=ig;pZA%1(I|q$m>c$B<^!SGYkB;R=ch&(t;H6Q+}f z!i6Osr=vW`Gj*-=i(j?pe$+tA4a59*w>UT*N(p z&9t$#r)MYaa8xt>x$1GDGLe4!yYHv(ytkYthS|kRYZo}Ge-;<9^LBiEQf~d?8E#Wk z?dbUA()UNQi-yI$C;{LD`!(;~+kBa})}N;9^Ok5zeXRI|#}8S=v6N0V=1)(}r0@Uc zZ)&VsPR&z}ITXLBKB;d2zAp)1>VH)B*tt3AF>6QtCkp#P^%1mp6j9Uz3$J%}SRk~o zz7BJS2hZryLGZmcv>ok53ZUNCTOr5B1Kz1-iFg(4`a8QVA_5akl`A(UT`G)hiLm3HYq zKp!ZGSfGO9i!!rVgtUEZuG`sHXgP!1xeEg#F@J?5`b3y}m146^(>z%Qb zMU9oQ9Yq!CAhUs|eJ1>=>hntYW+C5c>m*H$4W(K&j{YRM3-N^P+`1Ot+NvvfDs}0?#dR7McvGr} zA?06iO!lR>B+TPw3UQU%CM-!i>o6O_*QTp!h_~-5K7!$*;{-xMeD8?W; z#&>>Wdc&7Dwl~8>zSPf~eql;}cg@}Y^^N#{c!H#|OEGUv|83@- zX@|)qWAlyElp&;Hi_dRl-i6y=+R&H0B`GVu{=t9okK_ljXy7D}JCSZd-POx21a$Jq z3B`+06iS1V>|rAv5|AH(BGK3E#aaY;_Q%z3b|4jpgN(9M4)&ICAXZN=!(d4CUCP3D zc)%d&Mfh;(8iLp{m&2c=jU|W92?l(!$A8D*j!vxum;S=u3BZ5O%Rjav3?i(@lx%WV z5!CNaY8{(iVN+U!<0t&>+cDuQ7yccmm~MLZESbvm!ffO32dkR8UftX}c4w-d(F4W3_ufx`@9+J+^n)M#Z3}&TF|Imk9~G#KJTU6d z69x^IA^T%dje2a zuf+-unDizqk7-c)Az1Z+1igFSEuhSUQAU!|ez{ZTW-ober ze*d_RXzxP39^=gcIddNYP%x&Y4dY)rbBl0Qx9*tq435OkFV2K!g3K-{(jpvj;&=mA zH##XXe4!v@&^L36k_rY#@KFa>7m6q5r7}O4=9U-r76UddhMF{#rWHIINUhM)MD!LM zD?KK*Oh#b}uf@9F>8I41FE>v+{;8_NV@- zBQfe!=j6n6dbs*9Ez}m%*f1-OqplUwb!J0nn@I@w8~p?Y$;Dx)^IZ4PMkgc&KZP$& zYKtX=)Ab9w4O;6&lW~*?sI&!u{6b+BzD0@QmyEwUACVrvE-!^Cu<5^BhMb&?%c~E= z;(P*j91USletk;d#yeCZ&TB?)5mJUcowq;u33xi6;g1!1DjtE6@Gg1yTR(&izg)Il zuDkfKA)uasRUX+7XRM^%2`@WVpmFYoJG&@QSAiC<5}KF&yB_wzblmj9Mm^Zi>2|*z zDm-wEx0R$gc0z=6_U=tHj2vleC5(-5q>oJf@{fq%I&(cv#MNYfJqq6$PkW5Nb2y_$ zPw++A-Er_B06)=a@a~v9X;b=wIfqliw7`Obf}Qw{&<^NyvQ-bJ;K60FHCr4Y$1V}_ zyLgwh!?^@12H)(X2wmT7iv;|Dk5al&%;!gLy?zewmn;I9mE8Ohu9v25B1pE%;xyUu z_3Kl7{b&D={~@|i8R!WC8p4g28(ZnHeysjH7AY{f=WZHyEU?O!9XCUosGgs-e0R~o z&X$Gw-c5kuM}0lxccofMHO1k6tGU{|1ri7w5kPxvQr_&!DJyQTm)0rmcH+pOQ*PFY= z5KbUSV0H1##Hjd{VU5q^18l)3QlG#ftKAtx&Bop+9q`v|3I8W54g!(^3p?03hZ2S( zUZC3>*1u9wN&vo<$v^jqoof=$@k)ckTyTGt&Q)&ef*}pzI!F1z7qbeOOc6Rgy#K(; zFND#tSnI~hJ}%wo&Z)7Hv2=9Q5D&%CO2fiG0v-g@@Jh)$T%a*<$4(z#I4{^Z78B(F zm;b;2=s|k_y@y`)ye}F?**Pep7#Z%j5{M&rCR9FAksbubtncklr@|}r0BsE+{89eU zQXFx3n#-p4A^7$V#QQf-OoLa~s&~1=m(gAj$gi!gq(_2*+FK=eW4-Pxf89ReqU z_H)6?Jv#8Rj4{)bqiMD>nda0VjnRhHwxC4}JIzp9Azme5DE**q_N0`_yXMN3 z2AV?P&3H&%7-qS79-|M-V3e2pF47aONVh1yFeJs?tjtY|K>^ErkUV{#xBP*JU0>7> zM^;ic^S+`1%0n8oYv&_am@~34k}}gbVVLid4`C=r_!M8@>B4|1J|0`|__@G-=a4C;gmjkZnlyprnqBrT;u(e#-tg=8A?8?x30cjZBePj zF{^o@&XCe%@q>3WtG@terbmq>mN5uG1n9H}D1PsmM}D+`a{RO372BnvQD zAjATXi}RLpRXr+Q(x$GU!=Mk9HMd18WR$LVP^v8rXe{GSRqozgT3k$vEUvB2vVV}T z_I27lXr{gTk$2xT)n+-8aJH)P|MtT7u^#O2ny-o@;Z9Qj&3UTtZm3^4Prv)Oe>?r) z2R}%wEBDjvTrKq}{d1KE8i6#=&C8v*tc=B5Tf1pe_^g_|d_yLY+cbo(OJSdK;;-jk?D}CP^JhVap^Z59nkBDS32>ms5 z4ZQ3)YpCt*ZocwjF6J7HkMQj4+xw~Bx=4r33)2M0eTriB$2f)@6y<2_LIZx}s_eLj zFX!0f>FMz_C0>C=aom}TGEQf5U|0>+k>LkTDo}c9+RTWI)%8 zi9Y@wI~_(A{ZkwehBKzet0#^F+RiInvjw9Mck4i?IQI9C!k4JM20wTjTO&;a=5+Em zCIaZ~p9o{4FiM*_c_|O`R=$ZKQqRm8;c&w>Qs%S7u_<-}${x-hq9Pz=upa?sWDjSh zsPck2rwokx_H-?hvWfKauaoJfL-Q&;8h)6Pb}^()*>Ev>!#Nxb18yaKK_fSR=QxoT z>_u_#e}pA+1nRgK_(_9r{0Mi&;B|3s#+?<8tjObH?uI6>tS)9p%!5borN8@k|Go6_ zcfYGiY0WDTAYAH#v|!N4kn|9s;0Uu>7-bxQ(~P)7(qF?wiGf$)VYEpJhKk856C)3< z>YQP`St(?kDn1ivS=@0mNizchqoy)2Si{^Ruwt@_vIB;gPMnM6*`~{pE{ZN70;dM% zuhD>Q%15VfoCABo5q=5-2!SUi9dzij2}W=Q9eL#qlO(|mPGEeAtasy(}zE}Xu~MO_Ql8!;YukB^S0`)d!=()^O_6KRmuf`rvCVU?WU@u4?AcF@aT zv@6-6i%x_R)Rck^>uYq_NtYDx!~nlSz z`o>OtrQ>hDa3-KFx!y5)IUa99(?2?v+MV-}y`-%`?mtO_9eDUUFG4B4BDf9Yv?E;3 ziul>hCVR$b4iNv{aC`@{I&X*9Pn4DXfZ0J^hDhTM%=r(vqGW`&OT?v9lbwHjIzLXE zK8Ezd39oFmp^bR~ipwL195?cD0K3tn2EAjqkAHb$yp^l`%~#kLQ^JSgU23P8D2w7M zV5A$q*;N+O^@k1V@e`%T=r;oU)%kHiy)u5YhvOIm(g3%>tZ#x7B4Eg2{N_7ybAP0- zAXzfhH}RYSG5OE~c@iX>LJJ*Q%MK0`z{##!GFdx>-Ey@28~Od=zx?$bb@-qC_+L1C z#(-FGpoyMfWJN1VgYBJt@iwgFm7n@sgqH}3=H@DCt~#A&5k70YJUeNmufKYdo;`i$ ze*E6ORWJ16NH=yj!1p*K`Q7M2u)|o&q>`ic5CBjc9utKp#uJ362zADW`%-0cG);{v zj@s|F#v&9BhsWZ#8V#qx(K&)p=!;dUIz2PH^xV)UZK2Q*_qs*&fg&UuIpgiG4IT8>ahzJ*UM)y2Vn z-8iYu&sk7`0tG=uO2s3~u7v9q#wNulPO5%F0e}!0!6^%$P^?W&jeCaZc?10} zG|wOH0mb+H!lD&z+yhdZUrg_R_)%I|TuZZpm80k2&6+L%&l*L}`D&S74 zzS~P5Tg1_p&azszpz`FH$AzV}G&4J&hR3JTwprQ15#|W_IP#MnoX|Gy z8(L*I0LO!3$n#X?r*7$+xtFDe&|GjL)I#Y(8)r8i?HZVw`_KQZ(zD=P;b=z)KT&?MJB<5kVjg(w)$=I25fCyDU@n{~wdR9MeZ1e|0H%g~piHz5sV`a~|gBa@1Ro@*#cC zgH-qIw8HO7xGVWu$)$$^W;Wn+9HKhh=55|%pPVg7_7 z2RVhucX@MMB{Tz#U_cdfx~?LRdPbR(=}94IGvviM9Q~!r;c}8f>Pvkml};Gn5P5TDhQdQ%00t2+A2}=4-R+Cl}M?)QsEw z_U^tHG@}eb`7kc}okoGHHmHQvcd?5c1rOtba4LK-hoyf3-qL1JzA_dbHICAe`p0Y0 z0<;D!^kwX}WTCNlAJcv`W|#U0epR^Z9o`&#TCwT=i+rFTg%bj3Pb>BCeJ_1*U;Q!n9H}pXcW0M3N+|Zl zkk{zsbUIVB+1@`+2S;u3Qtfo2F%DQbnz2@$G(8-O7vq>k7VF$xu~_#sZNB_6J^%XW zX}Iq?tu8I3#}6K)@BhYcr1!t|oisH&XMU1}K=3QbG|oh0RzRu`eYLTjn(F(J51gEY zjEdtH`_&%dF*zz#K#OHNOE(%P&rT21*5<49@&&tnkKLDAp{{iDw>Eb;_az=oW<;G|F+* z++oRL9FFN^rx$%4@{w{4$L{`qdinB|#+?KAdHvoMdtycJZ~yiW(zieQ$cnq|orCmZ zV>j&`o_ZG(JI@%C*!9XTLl#uAxMN2A3vTqC^}{2L!SFqC$0v1x?1#lD$fRhl-~iql zMe$;-k{0J?QgudcY>b5)v|pNa9Je_(g4{`ci{kF@9i->apQq=~UWzZ=*En!tK4D^7 zyr}Ah9oT1=w`sS2lJ*)c^X#;bSd_qG4$|r~j%QgQCtNWW!ynN{alhz@`vZ7oly7RQ zv?F~Fif3*%kJ9H~Jx_J<7?U#^+XX+z6Qa1A&|HB2SzVgwDK9D!4uJ7O^l>iyuzTIS zH0@q?6nGr*qI5#=qe#?%DL(OP<9FB^;-T+w?-*G_P!#Tt z&!;_!DO+(Y>9}R z%K7QvM-ycj3#bu0%0g&|cRcyvPh%r3!$Bz0Bfi}A5Cor+28l*mIe)!E;6@UiP>vBq zLwW>@Sm7yG9P#(t$wqQ|+mxU(cI)|Ys`z)pl2^9l=kNt4*>n5|5-?)i)D^KLgR!7p z2?TunYv5Hve8cQB5HP_(0p{~=H9#&dEu|m)_HS#_|1eEyVv4|rbb!Mr-SjvU2ij)IO41URD&PNEOrKUjyF*JIP;x}dkjzrEw99kpPjdr20N5u z`!+b@*aKFe!l)NT2A5<%*JSyb1|_!cmOKM>CRW4stC&dR?FK*U(jC6=#S@c%*zTKPj-}#2VBw- zeX!~o8n9wfBc&%>8l<_eY<#Ag7S~oakk5*d;V2JQqlgY*el)T0BtrjIe2M8~ zHLdGXb-@aH>WGOU%1c(2py0W@5c4F4z=|&o?xRy;;wu%O+dQfXCFfdmF+0o?Tisa+ z8A4ZOrM#Gc!MMQ?u#*d)q7Vfbm^LOc9CL^O2RByRat=De8JKrgs-h?b{y{O=;N#@9 zX#pE_mX}u2)VL*oo30Hcf@v{#q?8OhRLzW)$aWA^!DYErShcyA_7ju!!`%c zWsGDA5pX)JVTrcyC<;V7z%N3^Z|{pA(ltI5K41v{Zn&^GK2{uapePgg2D2cVNR3buEYZv`3^J?xr8T{p&Kw28<<~9(rOTcgm4XPOj@BONP!LhSk87P`R#2 zyAw%1wwIDcxcH4!B4ODKYxo)_hr$pGe9D%q0A z-;;_vb^_z>)DUPyo=~zqWd879{2F(B{rC?%*Z}NezZL@8;v3*&_UaAsG#pPOY#|sM z(4V^P|KKPcHjgb( zRm#DRDK67yocG;08n0T%$HLdK;6M;SSw_?J#JDHqBg$4owZh6`dbkdO1IjRk zi#yB^q;gCWg3wGS8vCe^bB*`xjzJm5#oY+tG~lH{(HM6Q)aItsye8Yz!XGqC`RYd; z547)vOMAP!UR8_WtX5+u%y>FNpmB1R#x&taS$SW43JQe*r3<}Y-VXQbIq_Pn%Zq7B zFrb{NEAI=@8TT!5cirIadAem~y6AmD#t)-il*RsC=Ydj@RFVD@Hl2a1SdPO zIKGgbNF14kG6&)Qg?JB9g4+?ij^l_Hfss1CJU?}LSh?NU-?t!iV{<({fB7uEc=;lY z3P%qfJ}|96ef}(c_2h|_w-46V(v09cJZhw^?X7fptg?tF?3z3lAQT-$sWX@+ro?kD zFQ>;JyqDg8{GMpJVt$I9NdM;l`~OK_D{Ta==Bq@5GqbblgKvF1&Cbo4Kjp|g@L3n# z931SWwY8P>gWvjFK0*q5geOH%wJE%R_0<=u!;$pEAO4=(-XH(TAGuCAwh?9MmruS* zjl;vVAUyrSkN!@2{NcCV_PNib!BI)7cjiV@YFqH+>_pxp_73@l+rg=xSyV$cs{@?@tSak5(}P^*1*mpc7N^c z?x(}UBh9(!jYK>8yRlL_?#G4yrq5!59Bm!JwNG`>!|4g|*cP6uY#b5Gorts*?kHhr zCT)T;oTz-P#wQd8HuWXUi5R~IRZi#x zp88Vlg*Me)LWB0it)o%TZI)YHPsFf;IBKj`8AX^-J}mD!=A9C@-KF?_AP6ivF89 zND)BOMmVOGxd_S|%0it|4wOT&TZbJv%%4l28;S|fqlE)@nS_9q(qaUY;(7t3#u2(e zAJ@nnO>v9|1tm1}K$@<3rR8!l4-$SOCG}rQ13|9wtg;#R5Cv(FxDvx3+yaMpMas?L zoCM4$}3z5r_8+rci@L3&DbFZ zT+I7`DHL*)D;Cs3C&qyD#Pq`8{z~6noCaJN%4G$gX{nn=lDA`8?-spO zTY_JBq(1%oAAgV@-(N`!)rmAY#sbt^m-)CA#}BeQmBl#q=2_a>J5KwJQy+WCQKAF= zH$DlVqP7U!j8BxC-KgUuf;Fjs*?68dUpz^JYGd5{#g5v?j~`p1p=M+G3P%%DX8L#6 zvk!?~6dAF5ZXbSSpIvST>Dkv` zn4kZ5{?6~GAN~ICsh_WUaR7Yb{reBBpy%$%Q}MX$Fyi<;>Jgq*s8g3Ex;O2|j=%aL zNBlL7BcI-+veQR-N0|Ekb2NqO=ZOzrH_Z-Z^}`kQ+3eh6Hx_LgTBXiWu+m?--&Wlq z8>hjHH#r!&M|tb?-0csC*5g#MqMz3^_k`wf-7 zovxJ@ixl9`Id&UmS7kbO=rVq=V;O}e?SL_o1sXKLqF`rH82vg6uBJ7nRA)67YCN3R z+<@;VWA|0Qp zKT|vQvERbem3S*SKKgr?YX})tpT zYwmvcDrr0h^_aKD?Qy#6-!boSk8-`uL^)`;cSF20k2~hwX@@Zhg!LPzi6Nw6i_c$Z z{wfq+R>BN$(Nla64wi!4O2iNb_HHo_6GlMAr%c3ipHANR0C+BvSi zBMw%6Fbb2cC7lRag6Y@!g@C-^g8;=3Cj?}C23)dW_-5?RFh+0((swXuBxOUC>=1%g zzO$pl=O8`d9hbD#(J(Lvn-K2y%JDizAEe>9VGDn(y#ej7M?b)8#wxpYfAyyS<_!$$ z%-o>VfkHP7LS+)*j#iy&+49bjK<|I>L0VW`^eR6FLc)?wVN{6+{diS`Xb9$!H)#$&;>gaOja_( zJOmTW>Jv?>l?6vSe*N{6^z!Ap2HCdKC0FGOJ`gl@YT}nOlo>-Q-et(ggMspbs@yT< z2qhlwt}_`X17MS21i+6r>2zq%a;AlOiUuvaaV|sI@ILMyUNa0?@FJCGWLrJ7}nrBT}AOVorX17kBUKO z(mAC!lQdQdq0}prmQAr{2E5ZI z6w!88*^@0aY37p&5Ogg2$k0eyURq0Q%lA@sW;P9pQ8t;VAc#a+1P~CDT+kNuf2pHi@|HMO%PMf^tXS&V)PTJ8j9E8E2FJ2uJY2##C&T$;y zuKrZqoDRm{*&<_qaLlLN!!>>hSc)342`n3V=uLmePO473&)%5)ipUr;Dz2{=;-{B%1V#hcae%-h{0Tp77akBkaTPDH^C&W{ zoPNmySoaA*VSF?Gp0v0J;KFcl$-LnoWVba!ZG^?_Sl~Fk0k6uP)5LvsiQ|Zw@Lqd& z4?-UBF|0DjT^;O{YKJhu_dRGL&DbM2ILja56N<3ui3z7S$G9v$VxW&BsxO_FlG9|p zUoZ)$nzbVs0DJ@>7L3CC=qbBDE|f=GWp4@>z{JW@DvdP8R0kZ*IIa4aVPTD+g>TqD zJWO9b`PvWR;UN$zq8y2x>>S^8E1u%YN)v=-^RpF=pK@m`7A;)&4W(n{*;2U>&~Q(I z+qyE39TW&m8H?p+YJzWKSIMM>+Te@2=Kd#kcCfI89W@-uw03VLafy5p{-H!-H#|H( zJ7BJbi!r4&F8&7L3U`UY`m!qB0$19NaK&nO6e|dh`&GyAHr|aRo_bQe3<4VXVQ7ZM zPwXNa9k@>YH=KeHJhd67&NS6`%)X43*`1o|9V zI3?V%lZXEA;r#~|%pM%n)B5H{+Su7td7G{S>V#cr@NUcnhJ_a&ai_M&&U=nNN69%~ zn@Am+JTS#aHjTHr#X?J%g z9oFl%1K$T9d?<+e()#+k%F^#$cL)PN|KjIXlCcByqmRCqKK|bK($dnZVcb-C{^)=I zx4sh)+|s*p6zaXT2kHLWy)-__-DIuw^{W;e%skKgxETqsx1)ZQ2;Z#4M8 zcfxmD>8|Ibd6JHs$0~D0Wtuh(7DXh-AtFHL8^ssLO5KXC*nK!7T8B61Xe$J>?C7MQ zVy*yQ=>SmpuxO4W`k>)ZhQKF_Zl@;GtlB4nRQi;1iN25FVkN%%Guk*pOXh2C572}1 zq%Dqd+|$IUg_7(RrQOpnaOplfKY;^!^L$oyL40_59(a2cI~YcBSd9X6WMo3msNEliO+SW^m~p_1B~U1;%|L75gN1?gKlItO zQ}RN2Ltk+vdVvOl-{~64;sq2IP7fIuC?JcnGJ>mh%EDYm6)U^?a^*wb^qVD3lncN@ zxERy$hxTL$B0mdD6(6Ms2+0pF@!Ve3l~!C(h5^CGra9u+h$e zj(Vo7&<+OoP>2U#1pL6nc!+|LylCe@fFK%pyhBNb@zlyiCG2)8)5*VM^zAm>_47hT z+3Aa+Kgw6)@FpCv!(#$}Cq21GE)gzd2BA1&=M21vcb-pa?kyNmDiDUcM;Sm_*eyyM zVl1AWn@aQZvuZPw9`_Fp8=}vX#68=<4QL*(RsZw_=c27rZ(OdjU7SnPQxoY>Z4%h%&rqPA zoZWbr(5szBdbxFww$-m5dZEdU+cz}e{#EqA?i-XS+*dZKG4SMY-;1MWXJ>@>VJ|46 z-ZEn;Sqj6&?&CSjG;hs|18sFn|dYP3xltt}L zG-0K^>WH>RJ+mY2pnfdcXo(+#|GRbHM?2!KEc#!eBK4`gLSx)>HKV?}CR}6ZxIcCt zMV-^mP_S`=4hy=Fzloki=c;kHZSX?dCk%>I9(EJA+wjuxrYgV6FhSq0x^o`lRgsCs zczx}@nlYL5Le_Gj;TPUqyuA8icB!-AiK7uOH0FV4AL)F2?DBFXBYDyHLjTBK`uG3d-%Sh4YvNl^(pJ6clL&_4`@oS~3H=dE2TTjk z9Q6s#*ty8@;j{zV1M?92CFVEaUdbq2^lK-=2jd~U6LiahJNiA^E(@Fv7$e)4-VrvV zhu!iVyLc-atBCLBxM@ZY6x9&qzUYJFMfcSnTjG6vwT$Z1eK~&+E&sgn5qx3CFG@>0 z#}qm#_F}qm^E=z$2*ab|guUd`HND>@&teKJ#k@6ckJDZMj(LZ>W$AAbWA6_!Z=U+2aH7XcLvB|m4=EWYCXeczet`jdm~RlYV+x%i^rVJh#wmX&105pX zxG7=k5(dD|ojMH%m@$|Z20@3h=>fi2iR3;-al|CB`cWfx8rDRX6*sK(hIytAp#~-} zOy=A!1up_HE|z5ybS+NGOyTrYTF^v%c5yLHde=;9y9g1Ix+l5+oy-JzDHB1C`fRYBr zVR~FT>5_(B!bCVsZ)}-PMaX^!Q4ZzLQVX5b6-72#i0bHyM>I#}2jc{IMZa9eD0>sh ze)+p&BCk-0@tO0sT~7{7{(Kk6igA|m1I{qv+ZmU84QVTEC$Am@D%4auFk?!2G0t9o z&c|-DchZr?j$JsSEcuafI@m$XT~nfWOom)PrM(0`vzuPDMcecWg_Pd*D{%D$&URw( z@Kp+CFQ*g!bju}7guq0(9JCmD((jT$p@j~BP9W@M+_&9-chZqd{AWKWgk8Ukzd6ZH z8cMf=TU_w-YM}6=GYNcvp^{TXFplikm;Twm{52}R{+pus3RB)J46uMH!w!EDLqwT0 zW#O47&K?QjJv1&*M+JDsNK$}@gja%yNuPe6NxcO`!U^|Xac9kpCXXm^d`3Ury<#$P zr=M?%_t-gXr5#O%S!IhNg|U#;?+EuWp*(TMu78f3VQeO>1~n_{5JI2?;m8^4hSiu! z6KED40mCf2r8KE!feXTK1VzWE=N80rqz?jPR>>nIM(}{Z3mh>qN6-ci$eZ*~NKKB8 zSmDLa6BRpgj1u?g#4$F5-qnUc!n~OLDFaHlGZwUH+{1VwjS7Z>10l=N@riNAs#kUo zq41g*=`+p{X4Mb&)Ar`J_>dFtpyDW*=1I!})=+kVA7!TpiZ6CA1`*HG4=nJCjH~db z!xQNi!HjBGqpZf(k;FYo>?lWg2t9-_ zsWdY+B?w~oAHp+~V2tg@N(12>^*^ld8y^LAnQFD!w6HKQ-fYCY6N3MVks*bnzE2JF zl{!&&ZSC&Y)AsIOIz8bos$r*(kQ>8Jr@5K2v^-z+y$>jj8qIb(Igj{OHr{YYDQ#0_ z85%GTNziX$(#W^bkXs~a3%bXjVZqsuWqM4ZiP?oTH08DnVvoUTC~y>-=;J~$K(&6 zhJv_xbd;*o(_W2@5}ae*IkxBM;6Qn|)7XUSQLwYfugWoi;yIg*qqM%Uo;Fop@@KWP zk7pO|IX;VBWs8eTKH3l=9Q4W#F}DMiuR2#v-~ZmSRJZ{fg>;o?V?R zK2uqNi5+d1Y7b|kCFr3gJf8|L?6O3`!mg`p;bCugCkE6QU&Aw_Mn)6xP(cALWIv+Ie*C|cH>4Vppt3olJS#@vt{O0~J!G+V8B zR~rItw?D;GlM{^WY*N0>6VYbu`a08t0GE5#s?{kUd&zN){lX)HL*^_T6?@u7sUAXH zb#g8XhB*NbIHGT};7+tiz9^Q#CC5v0)FpRJb7}``G zkv2V{zI#G6k5HZd0|gYy!*aYj_~4$$qvNLBLzxII(ht!uP!^x6!Q4Z}^E$=jDT3!> zuoIp#qWqv;F$4f<8nxtcWnD{0B!W0vX;*kT+}o&wT* zg~B3ZAYTis)kb3n9YT4=GWuY~Xr-+OL!FbZck&UByqpiT0t}Ri{wz2vV7tj z5E9D0n4cjW20uPo2Kd!y6nM891P43P8EKMqw46{21R2O9#H$5UBnbYxZ{btbi33y<@mmn^&8y zsxH`xeB_;*v`J250S0&<0Hl1(Z=oMA)&&3Zrw#*`Q6Gd8^cm*hl)_%hq260CbH@|3 z4NaBBDO8oqZ3Yt@B9#rR)EdSsGpwZZnHS{_UyVpwJ-Y8_Tfod-)Xo#Zfx(T zgGR%3P2UZ@3p~-xfES98wsEX6dQ|j^Vq{)@?$Y9{(q*UJfa#qbr(Vb-gMw%lIflk% z#xr)xPqDjI{Rzj*vG9l8U#A-TkX0bp&m4>EvJt^`p645=&RTPe|^($C5U(OgLu^q?S{obC`8~-SuD7Wxg3hv>Y;X`>n=+{HR$n#J zf8(n}*ui(AIvi3SEYzS}v@huAP`GXihBNVz{mNsZR!J+1HQ{g|?KVz)Vgj(SKTxsnQVYje4r@?WA_5ZAEhbLyrYKz5QDmQ*n&`K{Va*lbieLZg@;LZhmL`Ywp<& zamIJar)zq@OP<9PSc-XT+#aX9{vGoUck40UYN8x;d3Qs+Gml?j-j)yTl?U_7q)AA_ z7N5V++{NdwV#td=A87r`w9sp;`1;5HkR4wN#xDSNN*4t+;IgQlbiQr!M-<7!l;6OP zJ>qm+^&9DgrNpqsY1@xay&YN(VOK%;^tZn3nF|#j9r)~(4R(i-aT?hn;)e+&Wtd6Z zjuGpd;G<+v-2LN-xM>j3FP)#$#u;g||Mg9Jkx4{TfQZVV@6@`mMzHduPeS0RN|h6? zj@k*=d3Bv^$vEV@n9c_<_27eV0LnmQP;=R1(9VS*Wbtqyb*uU$J>mnS-1H4Y198Vr zEu|ql-wbF|Gc)Pod+)jPA5mxOtTWLXPkb8`R%WnXKxx1yk%x>Y9VA5lW>#Sq13m@S zzyM>SP=raMb^2;j#nQ&4z2E({}idA!L^YzgL8c<=-fD0i@OM|NiOuc=- z*VkXC!$wQ#6j*@<3(T_K9UKMBf0f2`rZ;tnz=VPZedR1|0iMXc3xVp-AJmtA#fVXN zKEA@PL2X82t_MEB0cG>f3q^EX@*e6-<6_`gWjM+m2&zIDTjO6$P+{I-*qPX|dXSaT zw+c8}o$-b~X)b@I`pRAnx5-V!T+L2CzF zro7xXrF&^{ zcG1jm>`?5|1$~n~l{WYYinb?&r8jPY34#T+@JlK=5)tg~1pwvCarJ>wIQKV>6|p;c z$V9C0_kT1~o9wEzu*puI#3&y6iN35G*2eHhybhQSS3+b+ zb~yZl-ZAkjLlE9L*dn7ahTr*zGf8!W$R>wShTw*)Llv*cHotAMcLC1j%YH7i-}>o< zS6O5?9QF)n?6!*jNXo-lPaNn2H<8U-VU7=e^j*qFUUG9f5x5(iH@*sMyYWhZ;(6z7 zAKCM_;qN3C*4{iEhRVurkyKBhVwD^CfVKlKIZ1vnwuf6MUEcDDp`L!KQ~(2X~FXlzEPz%C2~7$}XP2lBS?Za|aq!I9L|WPJaK<7rx+M0){<@+)~_*pcOX zvNRT;7-9TmtmNLI(J_u(WQRu_1%t3>L>W>?>@Y$Rg(8Rg;b_Ob2A8>W^j`8LdSQ-B z@F(Rxpvm}|#(D0_;IeLZLL)rl-YkGWWt`{xo4`Cw04_5nZ_+|cx23r zY#3J=+c8uZs1H6eXcAnzzVt_Zz!wsTT1Az4+ZRVJaSR~*-q0}jqfCjHnM##v#X>p@ z2{hr4)yUkZ(_Psff>Vx$y0IXYT_CJ52G-m`cb4p(nfcK>`Bt@v)(_T&t#~ zxr*wk-@E8`74}HwKqzG8i1Hs-9F&Zd6I!EwQK)b!{Lb!P+S=Oj%4m2rgdZI9`QX8Q zAE!9df8`^kz$Lf$Cx3&I=500x`Yp7w-+20^uta%?sR(j@_G95 z%P*AgnH8D{7)=L?4{vvPaNwP3k5ndvVBAMGtP-`G9DgMH*ti#2A*7`&2&WF~hv~)h z7e21)xOJ@j#Q!lDxrzA){eR4nxFcmat*)%4`)g}nsgAOZ<1yKJh4O@*bl{FtDp2fl ztQShikx|-WzxZ;&_TKwxY;rms93EK#+CdL ziEn4uB8pK3P(Ly1oh0{G7SqCFP4zvRI369kL%GJnLKe8W?-M{Qc;jv$79T@t7yMjjJ3iXyXX1fnu~Lei#vANs52J-p+H+%T1@v>SJIr|r9E$Q z%v$|OeLo5+&5eX7c70H10UJAC)n}-0VV(s1^zk(Qrf3^HA0xy>d7<>EbLK-nvXH(< zY0;1IU{GQJFKvJ^q+^tC@M6qm;utdDBc=YEg_TyI>CFxw`a$!`uAdn1dKF((m=#9M zz4YgJf<|qvn zfHVZD`>ry!^G7(!S8x#Zq&~#sEM;fsE4Wr#;6nJJJyHhmkkjL157ozxslNgjz>m_T zR#QK%GO}}(g#w&%Lt4<(Y_*!^YYSGMv2&G03hbgq2>=d2FSv(RXh$fh8N={!`HcT~ zfLo+*_==(Kj9c7zgg@jQL+tia8}TkW#ex3JD=CgJMojmgd{fKxoA=h1tpFoE#-)wT zO_imk_M>^Q+EFO*#LuAI6#kI`u~V3Zv*3gFK)*OMI+#{!6Y1eUfqpyf=oP76aB(>T~spY<$lZoX3gdYC3Ot}iOxwR`u|gNKjO#B{}Z zus{Q019xD>ZnP_pnZV5ADHay&9SXL+x@aS0Y4FGxlfuVuW5y2tRC#QoCetwJQKXrb#NfjyDwO|tt;cG`m#Jh?Y zW0xIA4)5>pr|qqc^!)iVjg7ljKz{u3x6;G=t1b(7pRTWOr>D%VchS03Ot`;B={I34^UodtmTMO zcs+O#D_k|Eu-h4B8A?9*2ZXHVh_7M+&!OUQ3ITVvvMUT_B@-WxzGSE5#?G$C{HftV zwTXvmRb$iH#YK9)zL#EX#sZkx>YU~#O)H(Fe&D%~jR`>2FU^6r>AqT7(`RAv+uzZT z;fNhW8^^fcgMhNV_l>cCewXjg`!%B=56^z&m87m@V(6t@|(i&%cR?DdSj7Bbf+<*xHGw9vf}H%3`zqy zy^3%GQxfRFlPgzA6HvB@=NQ>3kgp_5ditZ-4igSx94`ha+z5}Qd@DetS3>EduqU{O z@J&8B?rW$ec*OE=_{c@@bB9+KX50c!hp>fj!st5}s4Eof!sLI$9N&Z~@%`(c5P#sp zD$y>?0aNE9eaDDzjH40)f8IGv$-4|1*;STY27*Qs_R9hCN0<)715=<5i}(>XI+?&n zBof)=Z@Jr9ZjPmo$lD=0`2@uJ=)fHKuqVbJj;WV^6?vzP{!CcI}9@1k1!YWS~O1`;xlVljwILeT)VyWeSX{8m4FV2tmWD!P8 zj1IV91q6yQm?#uw2yd9o(%I1|Uum#p+dn&b_V@PF^B2!FsoC=C5-OcOJjx8VfKhk= zW(pR7|J9m|D;NftS#V|gmMbMzK^)9&SV4m>!;fP!99QKE;bOo@4AWZ<*@0XBFw!K| zo#;e8LF7ZMaM1u-nW+etP$IJO4VnSpN@T0Oj&h) zK2=#wD`p4<6$}F9inIOMxy2m=DBMt}u~I9SUuk$UBR}%IqDdJ{SFt=|PCa z>NprYw#E;LA)w6AB9l%OQlw4$g{fjf#buwQ1B1sle+)TOMsSIO4Q2?TlZAc4PlN#u z3aAe~{R2$CL-9o$i>>_7pu&nd?Ux%&>(pc=tu5Y5%L~hCbR?KUNcAj z6O>LbqIJVZALXRv;R8jIlXp#}pTSjceB- zc(Fsc3mz~CSWd<6c9BJna_Hd0F|u)B|7QaYi$2_L2un-BpZv%-@PSA0Nf8Enq#efe z0T6l@H~7@x3Bt|k@eO^*rFY12d5n1fcltE{;-+uYm@DhXJxZh+ZQPJ}kO*7_&l35V zhJh8BaZ!AVi!nG6G^a-R9M5p(fEZT*_=xlZcf^yury>1X@A%3)zJQ|BZup@*8Hbpt zhw@~cWP_bA;~{_h9Vscs>&3C4OQw^Cc{I|zRvL0sLIFzd`8|FQ3U7lxiiSHD5T1Kd zFBsMRlZb^0tPEz?5JF`HC;dv3bhw*~@oR91F)W0m_zz`zK)ArTO;X-j)oi8a3743+ zENnmkhTx1bkrmk#35CYwBs&f`QicgNe2TpECLO4Z$?;LE?MXQogClf8U}+wJKopcW zV1UO<#!h&xelJ|191|$>ILcW0c~?REMC1OscNA&xwEv~XUG8Ce^7YfSv9ax=)W#>K z6o1TVV?rSbV!?GhnC$KE5Uv3eVfm)M zgkNJhLLBfVe1t+U?%v|)DTFi#)ZroO2X!wL0uLV4kwSz~R zV~vbWTgXX!9e_SfgD5q`n<@}n?{E|h27`y+l`^*5rrRF>{* zj#WO6*}8>x)PC7XQ9n5J@rdxQpf<0Yxr-o09O#eC|uTr!rS& zxp(bW23#6Dtr@jv}-x{Wl5` z)9aAxMSTUv<4&d>@4S)W+j0fm<<9~@D}EFo_{#1yhtr=GEP8MQF9_nHDIWS>@(8@p zruEii-Q%HcYRZ}SfdLv(hz0Rw#p zaFV8v0#rE4O#1_$ZfJU3w<;IB2@7h9@SL#=#TIE+HK*rpFXpKnrOBOx&=&OoEF6(I zYvskHV88NWPj)A@MN1riNc*K+^vRrlLO;xWmhl8R0eMpd|A3=HbCito`5}NXpgN5{ zOK!qFbqDU;XBh`h$T$uqq5PfKm3M!>|K7uNZ*A4-@9iI?t<5dV3D}KG`$UGsq7Bz8 z{e_haUC1b;S){{Q8RZRS9`~EGL%mj=NOLnBlgGW_mnue|`h{`JBv8oFrr9~ej$(GK zKYRAVZF)@c;ZHcGc2a%G)VO#)wfAY2%{#qR9v0)U3m9bwJ8fHMH|fOf|I&DdSD^oI zov0sB*{?K?G`TwyMWONrZjKFn|MBDW-S2(uYf3nF650aK?1UUtdEn&^8ci$X!5uWw zQeW%)-o>9n=NuiqdT%w&&DGR*->M%HU8(Ib&a+5>-N!8GVL=S-1iEIdWc-6JIO>>j zg#HRTn3|pzU#I?5_0FA^qiU0r!lxHNXk124*U*>&9^%g2s&`dGHtbgBcw6ofWnspb zUwoFneDc(bW7gKz(s#fA-E`AGlAf*armfvZI`_#r@XG8~8&jXnF^B_coZVjHMUlxJ zHTKgV|H+@EPd@uR?QHM({!PNKF0Z5q5AJ!aqAr1*;{v%;ZB+GKn_o~pRlU1wPGjI4 zCoPCC^63bQ?>!K*mIPCFTQOL?C+eF^o!QbX0ty z_yf{(KPme5(bH%p2A zp0J?h`OB^JN)r9X3f=byI>?(yb3!eMCd zoiJ|iy>a4=!S0xM{QQ2+EuP|!>9u1@AA>1y^qSYg%X&Bd-ETQ$%iB#E+uk&ao?NG+w#G?1bJ6pZ!?7a%V79b(k;g6hxJXPI#IXwhUqH4WQsolEocD~Hvp^w z9uM3d3M4zE0Y?H6Gp4?_9V77GmG-)_7eJi9rJ-690+K;#@@ z_=)fEk6(;zDvkcMoy!w<1-_WpwhVyu?k;XAN8L5GcC zhOIDwfn~>*TdbzS4+E1@7+>Cg#E`=fz=X1j6$TV#78696G&9orW)Nmj@NO^|awekQ z@e@bqdBD{Ga-~6;RUjObv$M6Go;`n__I3|FkOBoTdv%hHpfyeequ~tKze+=A)$KUS zTW!$4$`FfSpq{}QSmn=X5_3eHGGI_MtZTzKn%@8&sfAHkJY1GsAUaIt!3F1|Gh)~{ zuUL!=6MTXYoRz5H9Ol~-7vYj~qgf%!`Nk-tCN)^XG_h-nGTjRIFw0lxOm@!2n2BK) zlgf%ZB_OagKr76-zR8M#8vz@%$4W%b%5P~<=6H%+tTZTwV5T;kW*3&6AIElTP~M^k7*rT(a0FcdPdRg&Go5|xf(CHv-V=;WN5q2(Jip+`Llmqc zZ>0-!2lEdTg7HMo3}39!qj3NQ1!J-mimxnak`Fr%VFYc2E9#et5#{U?{2YM?uiMSh%}U`a~2LuTO&<7VJ&v@(c4FU<#6Fu;^lz( z+x<%?UXC2mY+j22O?SMrMV?NZiY8CevzrVZiA*Qi{I*-pKjQo40MSo}aZtHMI090l zl7OL?CHwc7aK+^G?2Su_kG&fYH-F`f37?y%hpu-CglDAPbBV<%-eEd+1MOtx7NHzZhH=1)P_XOCzH*N+fsbz5 zq=6;M5Lxq6;J1SV@-DdMS1A!DfQUe{k_TyJ5M*%Bt2Z6T4|nH}!5**9J0LG%-;R$? zSY;S3U43sZD<+B%AKloBbvHA;4YPiFLiyMIy7H&5E@_23Jwkj(tnhW-IUQX5DVuR4 zJC@)cx~8NZ;FO$cdhz8ZNV)Xq6g{+bQwV>YmOq^$a8;YG-2vZT5v*H#z z$IJMLAB}4$aeT**9*$b!qVn48q=jJ|=i|B)zePPWailCLQ8+q`RjBQAU=X0>sRx)@ z;K4XfUI=^O+it{1Ktmi+gn)x1f97VUEN~bZ)L3~H$0>ocG4U5Ct)}nJJUVKm_4SRk z#cET*$Z>UErAuDH4A}&Zp+BD7Hh9~eGSIJNy3`w*==ue1v-9f~A%ezUFUHY3TEAjx z+#MWcMXq2TA4?pGj1UeO5D>F-oHuDB@IhF@ad0f0;ixkNOz;U;mk6{GNF92I4uV&d z6DXH_ROLXQ>v&##6+2&02Av5PL*lKL7OLsq>ave~=J=YOy}IiG9)|XJe0-XAclWJu zYo9db-Y>dgC%~8mUMP#8CzNyWBkb1O->-W`J3IseV9J9)hg~@cenm7Y143wa9>hIH zC(WaDE83c#m^ADf_`zbDnHf*N^}P?%KX%?lzd;*x!YRR{s$Qz08* zB5jT-@X?fu@*w2&5n7|{&>2?y zhgYYsVKL*ij}qfJC*Y(m=}*~V$*xh3KIBdv6rmV!$n--1C~ftZXvc1^e1z3`yOpYy zIn%+x{(taQkpSrFPC7v#GXlbA2xOhO9&w9iK2f+uOUQiN*Pv zm1fMVC^v%bX@%uDO8SaR)y1jscY1~blu>~>(1mw!p%6s5hr)q7YPcg3fjK)NQSiA< z(th-ygls5Z`g{7dn4c&$;evdNVuc=$x}^-zF>@3vCK-GGqrgz?;rhY--U{ZU+@oC>Z>FWDit7*DLAQ#dOQ zSr8x?0|w@`icbXo^?-Z&0on`;SNaqdT4OBXsKDjLg|x6xQ)=v@JuywuccFMdK}dfV zcQbK!B6s7dpMf{fL-~z6)faPh5nr9rO%=jB_*;rZu?xHUU zB_nmim`E55*s$VDc)-m&B-I}xT<5sBM-T6(2lwxp7LOavw5vA85xMMS0Vga*uwq1I zVGM;Pa648Tg0C`8g|orF8{sFV35`*6mGSiG-eQ_j`x3*UwsvMEjt2Xbd=&Dql?IF# z=V$aEsvDI<1@ZSf0oV~3aTjvGgrl~k_S5eJXJIB32`9@HxfLWD}U6VhXG_Nj2z zYSh!{FuVDJ2VY%VQ(KsH{e1ex)AZRFU#XuKX5lGB*O#}V7y5U>46lIFoL$505It-h zsXd)*PB7_R{?IZC)pT=~M#ZxO2W^>#<+e>5=9_=s{-z%&-@yl9-1n6*5ESoDoOolf zJLVlfzh86frd>=4iy^;Wb2lueH+*jyin;qOhirMf`BfEP-^9e&@pcovY4`n2)5H*x z@V_WVNw=7Hm-8(KTFKTojOs)~+#3eP*T9c{|3^RW79|wrHAKT#-1N(5`Njl%Ic-Z(vX9-vkI>;o zPC3m;ExYjww}3~l;--ca`QjJhDQlERzkZRD+~i%5jS?)o zU_;4gr-+AN{>zZ(UxLdP5d+sI9^Nil6btv9hyBX0!>v5b&tpkYMaB%(d>F=(enOO~% zFrruL{2APe@QOh+wv5A^vpNbUEEHQ_fu(Q^xCnzt5hj?`ldKMcX*kh@;y@FfeRb?8 zIAGrbM!l&+#|l`m7pAPZ{mQ1BY{xj|OuK<+gfDVcxt+V)B7YIq;RO%j7-#}EJ%&5z z8y8}fur|&&hxJDWguF?Mdegrr40`Zo&;}+?ScEqpMJT*7NO3d`13bb9wr8_q23VPp zQ6~(-zRyZ^;MJmHBrh+{&6qIZiaOPVM1Q~y)sQ#odp92pCM!|(haXU9j5vQ*>u^sQ zbb=4ei`~RvGU){$X3kZ97%eU=MUe^*Y70r|twxpgb8pmYA{f`S=_9%&a|t*3Aunx#;=JnowuNiMlQ43~^?q`*x0 zz;WDB)+felTuc(ek(jh8Lcl>J#U*)g+o1@B9nSp53K{^Xux=$kii<+O0b zjc`sk?BvUvvXLKQa4sfinJqFojII0;zQj{MXg7dy7~T=i7CnKXh-1hcPVZ6x`xzL! z`^~@J@i>o7m~ga7EqVJl?_=*tuRub|3r8`(Xk;#TZEhVSgD$P3#2?t5gw;AVf#dzO%iX zo;`ozdp+27!?27%kFmZ7eHnk@AlvKTdIvAbH`J|PzH>MW7;|`ka}=VU+v{^bR~IPk z+TP*B?j6Q$?v6s~$WAp?iEzQm1L6_RPE(5=Gy8jKduvlTKTg~OHZ4AhqYvAsEi1c@ z8+GxZq2MSyEIbkdVUFNt*A4geuo4=n767LTUK!V`sKN7Dt$7u5+o zF01-2w5T7N&qa8F;E&^rz#}XF5vn8DCC^5q5pG9K!3aH_8CM7sITnd~v%I?w{9Fcq zMxDYtAy@>fm*Sh+;_na|!iRBJ844?QL9x=`*jIet8#Op&C9jH*`UW_z2LUC5agH*J z9Zd-JP>v#4;mAz*dUmtyAGOk9>pUHwT_p}`;G_hEe@vV-G%16{B`H=%b$yuAvO!h(dNyppc47_EB_=cy&5E zO*k%)``Hjad-s~`eFMYkOnfZIif-=<&qpU#GI6gH$_o70vB$1YzE1@k2Nm@ViJu;1 z#W%vkpk0J>2vF(E**(Ra2xS~NgRiA+5)}Gi1^Hnk1biq{$fvD`Rr4)&dYzu7I+xlD z9_|S{XvC3+C4rw_x5t+;fQFb@XnlSfTFo5#aN|3E&5_dV|9i* zj@185j0pymW59y|)q{>+AyD;Vfq_s6Q5NoTVaFAMTuuQ2f9&GoSSWVQOiowQOtqSZ z^-X!9Gw{HjdpB2Ywc-8r;>o9JXXEQMKCC%O|4llotL<;RNY9^qp4!LtR26)yoQR=5 z0RG>~6tz?CkpWH?3YL1LZoogaO-FsHeo!yZX@GNfX59D6P$%>kghK$!?iR+3FdEnB zQxvhxgQIT)4>2Y)|G83p?|>?OA$6fZjQ!9TeK>(*rv~$D(S`D$KV!a8=AN+oo=KfzV-Y+gqZU3&7Q zTuxYJCPCqW#U}KVv>VS`Djj%3>XCW}$M6p*%)$R`Z9c86tfYtc z?ptBBx$!c6`svTplc!I;bB=m|#z{+w>pyrmFN_j?SrEm-oIw;M+*hdak|TNfMghd4 z6%;p&t@LH=EMxZ__gJAA1MY!gg&&zr{UfTgVb$FfM#|K{o+FzdBvlM_olC7@yRmRxM=L?6HeZLxR!qS z+kaDOemi~Z!^i3Vy?beSdD+KpPET=1E=LrGVhSA6+wdTJL|Me5?@`f0pYnmf@sXWh zfBCrv{C2vxyx_6e$}iFW*6u-iwR@btc)p!pY>OW}yGS@QJaYta?BU|urVr}ckTo8_uIpC-x!C>@A6%Y zZTQ=*n_e-mh5ZG7n7iM-Whmy&Fn7N1m^Z?A%$u+l^X@pWo4+g^<4-Z)G))X43IEMw z{Br4I-Wi&7-s1Uh{^$SkpAP)~@BYD$Ul-2O^I1mIlOrSZ&rFj_JxO<8%&{Vf72Dmfc z?Jn5;$e!W-<&7d6KX*-}&C13OZ3s6ozQ(wKA`oJBAn>*bmU_iuF43B9NEH?~zhvDO4 z*B6sI3*y9dGI-u9Emkx75@CIpNmDMZ@U=2$Z%#S@1hXI8r5 zKcLYVW|iX#!3i*POrpaebyGBs4gn6Ba8^r_H?#sBK{vn?s~|I-$QQb%$645hGk@~8pk8lZsO^bg)J4lCMH>NJ!VD?TDRg}e+3RDhD{c%g{DbZCW7Tx_aoaJKHl*|e-wSJEb_5`d^keK zE@Nwc>`tR9PT3t7<3J8L0dV-`v;#q5?Ed=0%MnU=f5#8b7%0nSmV+U1xbP&5+f4S4 zw|#Pa+yYneDR~QN0iMG2~g~vS2#fR{?-p){CC?f|L#p?>E`ohy5T|j zoQ5pC?VA1K6*veG@eex2ZX>(P(DBzFw5RXDZ{V_YDaKu)W7&Jh7Yx>j)f1lY@bH6g z>Dw}DZ35XLbb zFH*^Ak+!YaN!0&#b6h^?u*lRO{F07C+r5n8y=4S95gO4#*bOs(3jSw5`N^+O@%4B9 z;~yjB0Ll)(@rD7yfcRH4?@Bj}^X31Y`G=pOP`C{F|929o@^}2WR0JjZvN3spI1J9jt4%I`w=e{y<;7_;9UUH|)8>(JL;b>6BTR?)%OF@N zSK1_aM2IpgJ`1G)N~>Mf>E3?btK38z+}bF=%{%o1hpKQMEMU6_S4qJX4>A~ zO2rXAlYrv4ZK9||>iT4;r`vty`Qt@t>-N#(C>!y^qs}AAI1W$`AyXqao>w5U{g@&G&cFzC^{$KfsF>SDJf( zf8Pn1@x?uj?8b$zIIfPPv4D^AaX%Sz6X*j0e|eY_Unwox25;tK<)}g)=4l8v-LDA` zKoUo41zs%l#GiQ!{UbOTU`J8Rzm%QbphX-kTf#$6>0>)?ILpcIvU_JC?F8kCANqr! zLC4b{brJ44y_^Q$(bpIGfck6smGOr@Jm@*1fOGRwI5>w;j@jh&ik&pTcg*Xuf`&Bp z$NUt3E0pxsultBnR&pbC!>;mC9zVvL+O6#L2|hZ~eH^=^z#S&fg$<|52Qax!5|4h8 zelL`>^rh5+@`G3v3Rp4BcdcZUp=}{3ryU{)=Quywi0`#i`N2PmeHK@M4`|SHeQ3pW zLEVE}!AQrZFs0s5##!m5a#;Z;Hy+=Ur>E2- z9u&fS3yVFDj*na}ju`X~GvQ)z2t_@8PaL~@+CKHsjg;M2WY8Xv8>u|h0mm5gX4h*A zg<0!F{?}=0rea0W$moRoMeuTQuCy8lX>xQR)ljnQJw2|x`$cc!1#Yj}sWLg@9htO! z_yu;kbCj_LDM23ef-)hLg)EFvUrN6s9)UiqHe0o_1tkhNM45Das&Sxsp4zIDn|@?$ z^ii>c7usMP<4#vd2plo4GB!XF_4{f2|YZly`DlErG zGXB>a&9uI?o7OjXJpBZ9pkY(|)`iC$+L{8nr4zQivG`rS zJ8y;Q`F?wt?i=H9`CYz?u^oTAb<@N2+A+WEcW)UmZ}?;0=GJ508pq~!SbNR8Xd zG@Q&gPE&@Eg#YF-h?7Hq!$|K82Aps4MDf-4PyXS5sbL`ki0s^9(6RE3I|2rN{KChB zGE4-WBh~fO$7Qu;*|EM#AbTg(z`=$te&HZ~cNh3}ug_ z5d#9Jn*HLX-~3I0Qf|NOuJE#yaurzYlf(Os19tn!WD9UaoyZ{7!o-Ku^=G^s#r5T{ zQ1JAojf3sD;mL;r5RaNM-N=m&7Ypv#ykbU3o~~5VgNF~(B6oagumd;X3Wkk)M;s5B z99@2LvrvMR7|0z`f9BWaMt&N!7{FQKgK~r;N;s#V9YhEWe58ju=8Fq18D|n2->fd? zI35NOR=JS6nP{cS#DTM(xx0W>7JHfma`tWGh%?v&J5fH@w85|oaA%ydq9|;JnAb0D ztY~pDyLp0l3qBY?ln3y_XBr3-vxAxWa{h9LO~ei@z(jyE>LWv@Xrf@Hi89A^_=XX4 z9oacO43iV*!5{}SAm(dE6E;su6^6l&)n9#Lc0558<2^k)Yk|VB7>GeJF-+LZT(VM3 zOcvYKsT=P1x?=LBy5#(63t+?uFrnZmC72va$0P><4Z^##w!*YyvJ9OVcZAY=OpM8t z@||GS534*iDTbNj{A-Scf(f+p4W?Q+fa1uDE%z{fFk>*(Fs3ly9REc6Avio$m2*tN zh;ahrd@gvvqmNe-u25c4g;qAn9hzi9X~th}Ru(9LCv8lusdU9en8buiv5a;r@pApf z@eX;?qkrNOC?;4u)PtB!dB(AjLz)E7rj_NDv^2jc#)y@B@>e_rkibbE7%1By;3|g7 zeY32lXb0?u^tXQKGu^N1ZDMjOLdjNBqZq>!_) zbG$ll^21)nFo$)3cjLqTV+S8Of`eo?$J86E{On@bg)5^ghckSUzl|;7P8cVf%V(HK zD@XN9KM|(55ijz?)9}kgma;o?#Icc^ow4dEY4c#G`@-ZJc6e-#gOz}hq`z}X{n1S- zc!UnD`st)+lWiUN2&8`nx(!X70dU$SsGd&#`eHl-)=nOH730AE33nkY1j0(Ogbi;$ z;IhC+o+V5H&H3oTKnDai{`CNJ+>ynD11adO?}CHyi##x;*m&7Pwx9}3sX-aVi^VwD zNekE*?PP3^Fa)5l0Cl9&ZP%ubPCWd=oiI5kr%OBv;-vf|AH#|LpZyw-I{d%=*Z)s) zwTXV=ZALH)R{TpCx3&EJwpeBS?oG4T-fN=o@0t>>^XAX_2%mH!xH)~?p$9!M1U-3L zfRN+ZjUR=B-->iq0|@9WFyfnZorBVf@-epQC;REmrz)wxAHFGec_RcPAJRqGjNpvj zHz+{jK9P}htFilBWxPoFPF@D2?o?9rzIM42Qjy-ehlYj7O)HCVBk8s3t zpYXu0DJ~r6GV}G#t@LVR(*o^Fnb3_X=8KG_pTvufrmzk z0aO-LQ7?i4eto7=O>=Xz;^#&Z_n?%W?L~-eg_dBX9xS93Z%y5^Ljl^lf~SKQQdz;Z zd6=R8G&M1j-hZ%~K6r06)n>-6bO5IpSGTEsjxg^$9k<$ET}*%OqwL1H+oR9Q5>UyG zN0b@}^;j&my~}+Sd!of#m3cbN&Q1pn3r7|(DGoam5j25Y_;mzm2%Om2f*=Z|35f$Y zd>F_2wN5WmOFZ9&c(~(c(~9Er(-YrM%L;20TFc_GCZ?31XdN7@w8m%j$~UQ2olc9j zs)bXe3m(~R#=TR=tuybq^Kp{R6Vn1pqDpl}We~qQHewud)Db&;P%7aD?+TyHoQ5`o za)+Hz?3!eyeJGdcyJA<*mH1@txM`i9`CgXotv&AqWW~0RcGLrp3q2y(4(4jqxAUwZy7f%0zf#7@DEr`ThO)ga(^g1 zo}V_;`pf6()1UoCT3>%|m}h1xX?|`#EzH+kUpqTHUJUxZ?|$sN+2|ur&aP6Ub*}kl z2-ZW9Ht5~26QgP~$_s%g_+m#V{o}b{tREhwz5OG(ow+?iXOHeLTOho5P)~K$GxV}B zH?4UA$EU>|M7!z(IBL-=_B~g*a-WQec?5mC+Oz5nL;p@0=^KEJoprSPxMPgF8_PY+ z2&?msp3yPW9s*M8-u0xE4IC?LURF3|Cl|XS%N!NFu#0kSbum4>x9UYFjJ*eqmgrXWq4C3X zs5$Y8`mLiQ6z(n25LZcnCzV6M*{(9sMu5H48E=YdEPziQ^^aC?2v)Z#{c$1;3SD4^ zzL=*|Zt(6Mv*1hLv|-D73BzB43q*kk`GBlLO zx%*Yp0#5o>!i^VXdn9sxe1Oa)tGdn zHc{FQ3lkWVtx!_=Sq#9~!vYn?(AvVH`h@w^KQxvaO^r1w4*ebrjld1Z-cslNf*bw^ zzKg|4KIW7@R4}vC6&{Q}961ZS{(WyCac?xfGfpVq{^1E$Png#@X&t7as}s}Ai_QJC zzOkM5_cSgv_C?QU=__`7ZEdN-piwAReUtj%N%iq4DxrUl4XspbX<=zOJ-GKE&DG{p zMfe_{oD>hCen;UL2T>4eX!jxxw|&tp3vQqb`h1Sg1z%prMGRS>P3Qtz_o8FP=l*`i zGX-`3&dx24r5w_P1RjzFS@aJrjnORb+S%MlUw!_Wj}(6N=uuj`f8UBN;$bGIrqXra zP`VJ!%;W_s6XTUpfczhoIs8oPkE7!>IZ3OYa`Y7cP-aq z;UV={smys-{P5^R8lDiJFsS-hLttEKop4kz^g$a}KSEm+ZMc6?9_;pmZ=j2Uwx-4z z7sh0d`@pz&RKU58=(kvi_QjW9r~l)R{v^G8@xphK!2@zP<=V%vJ;ou@#5j)9E~XnU-WZ3;@A6%Y?fBb`_nT=I zQ}V?0hAZZ7_}(&L-tfn~&8^3{FMq2kFu!Tu<$l+E({PwyDlCt}|DqTry=Wm32jlO* zEGq?i6Z_eyUPMZ7n7HHXAN^O>aWKzvF1F~cMn#-XL=z)}eg4!_{4IEsM-hG?(6F(4 zwvwI-XdnHAa}Fm{(urX;(j!#FBLuG5-O;e~?xv05x0`DBD+hJz-88b16YktOqW?}{ z2P+X}u=Ylaq>5_;$uOcrClPwOTyb8<;^BT?+lNVE=j*&Ho2-lu)C2GkyehV&p zObORx?Bqa^9tn0nF&QDw&gn(CNW0{Mkvsnxpom3s`juOR!A&-o+rCbo`ePt@_}+VI zettxjLbXO8H`L)iG#I|g>I#*(9t6VRaIob_f$k(nIq8vF|5VggOv*Jr`&V!_s21nL00rTnwP3jrAP=4)c0{v=z!;x+zS!pSzhofp@_0C}8jBl^>)L=}9K2@n$`N=Vdl!1we z@5a(3@j5G!*yfGm>sE}7CkGl#nIL*aiQr`gvG39lz`zZo&v82^VivAoqW*vE{aKT> zOLpf8t(d1B5j*CHcOK4sPNt-kTBWMWRCQxu)^t3`wz8l^>L+D_}fe zu&~gJa+LHkP-oC2=0$d`-5taEZUPNta`2US%w#K042nD`go%@4;0n#;iw6p}75&nC z&?IJS zLEG(ZamhC-{XV&$7eP zFdf{eLX9j4KW*(^UP-Ioa(6fs621hS;IApH4d(DtUGc9XX3Qml?Pe&cLY$Kr_08sW@)8M&1$MNvxVWWC0OPYx zs?cVawxyIUikt0=ro!00DA_q5&=z|@(RL?`%Zdz+fwY*e;46BA!%d#D3Tj*cPW>uMo&NW%< zZCXpd7tehD&;Ql$PVn`g|M~y1P)PdHhrCHaEAGU<&{^uBAKP426<38vwe_!faG&=E zmAFe7#V>8V3~e{lZCLsZ@kQ2Sqr^98#a-#~r@&A(I=E5BTaD;V8&d#@iwPC=SawcQ zihupRpo4NiSaPHfMZmya7Z*&5sSih(!s^taq5fcp2D@-}Hdf;J=s@-jFH~VgI}-}@ zvm9Nty}cD{Yn$rt_k}ZsW-j&6)01T=kDY?Z(wAD#ztD$KI5VyF$e;Dqjd&Oa|DS2ap%T-+|$D`n1{zH0ALmS+Qx2d z`qK6@^MGTcV=*)$-c7t+9&yI~JH0WaG-4s!s>;aP+FJC9{^_YkEH32nLfj>SAnsi0 z#=R^E``8I{%<5`*f7wAFX$)V-WGVN*FyTlMITSnsuf5|#AB)9_5a%kJhx>bRu)nW( zainyvV)uhElZmQ+@=R$Ydbo^!X}%eY^V8BJ)QmV04IEj?ZmZ>0mGSj0Pbf3-Gb)~y zqwl7srj-X{;?p_CamPn=Q9iwkQfa_0Ao(L|fElflr zL_v^tz@1$dT(H_-aXLhRk!6(nOoL4NJC6~1=?8z$gfBurghyN4DI@$$P)>^1pPQYt z0F0W1aFP0)b=F136L|1r?9xP#L*6ktNV?_ZH}y2z7_@GQ(u#K>T;+S4OXtgmx)rOFcb_POm* zdLz`JJ%Zi z(el{F?s1*mFnf&2E-Q8-vdga{_yV3f13t#XJUH-k+o<@kQzmgjt>Uiuc!!blLk=p3 zBQdG=kt5;APx9CIu_+vOAzxdZ_c3}L0lTxSc1L8f6KqUv5B=oY##XGTz1>zh;$A`0 zmgpgbp?^XMlXV(8sC5_aH|TFNU+5<@51^I0%AyJcY0Sf%9Iedl3o**HTRaFvj+K`j|LV3_Gh$tLhV_<>a^P5elD0&o_Mi<(gDFNf_?IZ`!mNB_R{=(+`Mr^?cZWd%`C>)L^HVa zbU^LkMNb~ro4cZ^59}c2F0BEl6@9hSjJl#<-C2rI1>T2wx_!lE*LQodP)Bh)*pFki zb*G0dr8Vtm%ct9=BN!IbOi#}uWmFo%dnwO) zREFqNRK^gr)W9LOK{uV#CGrZ`EjxaE<>*)9w#FGtjelkeQ=I;{L0MW{NW@D(YcFUs#;CS!x(Y_c{_uLm}N=w=+ zI3#j8+e1V1<)4j{zS%~m{_julQ(seIG|p0N4?3eOa1?X z;Op0gs|slRe3P$l!bzF=M$ZCxJ@t!HzR=#isx0{WXaDTKkekUX0jTf^Sqd!DEXq1z zW8_;bYA2sxEO1gqlfF*eR9M$|V5QA4(%pL8?LYC^XqaLR4F*D0O?A{qUtn@_6)P%{ zH67>@p3MrUkYi<7^w_6WTiLqnTlH-}McKYM*7Ts0H%J>);a5Fj5ijfYZ+pfwv0*MS-RWVgYKH|jShhV>1)j9Bt>EpySlG41-E_;| z4|uUtXXdiyzX83}6xgA3>QOaPvxo8AEk?(#T#6D0(->m|-rH zsf0-}^DhPk0T%=JGchj+R_N5&y3WK2Za%uf!Y~GYG;T~BusL4+k3k{$-Xt?V@!3<@nYGPop;*t_k}lY>{K066%`y|~+hT~v zRYoW@!Xh}M2QA-3gHH5G!{dUCz3eCwrF;QqP~*vRZXC8vKNZ5N1Y%l+z{6Rz`gPh5 zUR@X*5GEAy#I~A?GO%z|IHHEO!h#Zehu^^scv{suns5KHm&w4=;miFXbSimGGmcIV zU{ayQ4dfjhXxi8lMlY-}I988yI)DCk{)egk(_Xa z0LMr0R%qL9si%LTKDGUz?edZa+`tWUtFO)JAGcy^e^Bkb>b8^K{fsTT9NKz4awiU$ zGFtXz2->Mv)5FS+G83l$B&&lj5y82(8Q3{}OE?LW9`FJJ!wZSqd4KJY%Km|n0#ACi zpLW#Jgr>alR`9<9pJgejqrSNA=>eJ@Us+!g54MIY{;S4%jOYQ;Q%Q6hO5Y9>jVx^j z)^J6mkNx4;c0((J(>|@Oq%l3Dhm0HxY`@Tqf2%G(_?J6j)_nL~?)XZ~@zeM!ZT>$Tm#&hx*zN<($b(z~sRwaZ}%h9fNrNnJBKp8v0pwX{69X{iXO6 zF58BGgGcaj%EVo`%-gANJUM1EF^RAMNMRvfA{>V&`%EKwDsa-7P84(kRPzvuatBq% z-F>u_YZ!XtOXb}KQjRZQ!Y_KOf+um{KWR!uo^{jFUdU^S>T<+wJEg={p&#iN|Y%G#QG4)j3v;tEB|e_KUvRj8A4s(c~;s9Dnw&!IOeA&V|IEXrki8l<#u+wA1f3_sqGFipFDNMd8aa;yjKt^~R&%{nS{7`?q zqFj6;JSni}=gEiqR1C$1Nkt}{$$J(IvZIKd5R98REyF9kmDki;CK4IjQGU56j{CVN zp&n090095=NklmEQA{*jj%P8*AJ>bEtAiTfk1aF(1)LeHojW@(B(c|H{28 zOjfg_j&aC-YdfAkd!qb4^*u2oV@;QjL8aB`5O=q59AeX}-f1h@^+z3nwgZhk~@y@&Nd*YXR+-kLyW0$e|;+g8sX8hqF{!#qixBnm}#x*8V z8@ay4-F&;TdvF^2M|w1#AgvJ?EX*}yady&2S~052U5E%kR0dQOwssEU>5J8Psk)3% zmvVRG#**s#yxPi3*9qDuj*>+ny1Tm{tLxhev*o(Qq$c%?33l*#Os29x`cuZ-)|S47 zGQ_S7CUM!RN?CHb&=~6YG;g_w0`|9T9Aq zKHLQ2c?Pvnq@8zV$(@j)%i)P0LdcK=PaIAaSCuvI`a(!0S4UTPJ#h;!q#u7TT#z01 zgz3H!IDVKBUa8$-+>0$czRnTsC>)SFoz?DfuN`LcfwZPR6Dy~I@OT_t+M^-WN7@F; ziN~J`4}nlq<8zK}qYt5Z;mBf+Nyaa`eMc0Ik4sj(xFc^)ZT95EsD%qFYwKR1fB=T$ zQR(ZcC*-FH@Oald(9{lbOeyJQA(h-IPo!sUf9M-nNI?0g%y==U+({n<#H11Ri~RHn zKkiHPs2yh~D~o9_SyZ7g*r7Z&(s18^zZ$@eiGH;okDfk>FCRV< z&%v(a%NSAt!4Jn9ZftJHi2A9Sxj71SeErqeF`&f%)`#!Mts6HiC_-S=Cmw*KAvu1y zSNiPN5K?DZAT24c9B0jraViLH0sIJQf-uebrM7)zYtu(uKYQ`qbqOKwf!er3l^b@$ zA(UmO+rIdpL-8w9GqW+Fe(L6}Tk+9HAIIG6yvpN<+fl-RXQC~0`yhhw%c7iI314*rg~Qfp(Uor^gV0D*f3dxWBU#Lj$UVDwC%@ z{c)m)BaG>**a@eq<#wGkp^bt+W~Z``SsdiPO7)*^FKK_6le~;m`k~!D-wXO|c~$k0 zMNcn$pBHo>=)R_U{hg2Ai*J4Mq0&PAp$3Cq{G+sHF@@)4^}XmFjKkAQ^>ga?)y(*Q zPnDT1b_J`Pory+vyQ-gGEDhabNh>1G0PzR>$p(eLN8P|Tvgrh-Sk)Ws@Y0* zw8?L9vHEXY@b&BB>Q?x`-#7XERd`90w<3_^>#1Lq@`WPxsw#r7KTEs#(s`xcnj}Jc`;cc_`(!5@tAW#{Dy2!0P10P< zMu5kH!88KZaq!!?^s~E?4Zp<=$h1$)7Sdn~^J9I&pnzx#k7$W-=i9C9oOF5;3=94h zzrpn?xI2?&iThPQcyK|nKfDnSaHn6r{YR@$>iL$}mGl4x`b*;3Pj#17uhLn6D_AiU z3=0spHVSBkPVkVH34yyIrJ=#boEWfoKzbN}xs-UoeE0r4F+Dr$)l2CPa5myhj+ibf zIv5yD%nn<2$>@stkOB7;LL`GsC&?}?CQaOtsiU+241tCQqesWAWK26Br>Bm93)?FL zQE9}UE#nO6SC&`e$)hK+uE7j~F~}9$A_oP8kXqehjOU$wLnwm^tELq01|Z z@HGmGVGYO{8t5YYVyiS>5je5>s9!zbgzVWC4-<{hh@Dz6S3NM4%183YlLrT4UiS9Q z@RBd}zATRO@pgAHY&~KY7=$r7am0$w@;$FBZX9n0F@hKK(W3`CM%m%T3aAM&Y4fu& zsX@C}0IQRxJP{6Q2osirK(V2Uw^(8iKs}iwoG`fP3Clt*{mwMNf$=u;EB_u)h>SYm zLbW?kh1Jg_mYMj>Jp6eJzx=|4dmtxu`dpYiKD(>I8uYt{^XiL~0G2Qm3Fq~@T#Rt0#tJFb-V?Vgax>rFs6h)MnVUIE# z-!!J4Z+YR0KQ}4-^d%TO>+!4f0cnd>`ork@rx4pTO95K_14jr6FTDd!cMl#bVDVl3 zRs}t6o8rH1Wq*DZb0@Aac8NRvLSKCYl=1B-`$MAuJ89roJ4|2_F!8u9V#gcMM382G zivnlS;+E;5T#{vmlXO=X+u&yS4yMG~!ENTX3*M^ZoT?yke2YHa^-|!J51Xq$ef{aY z3Ow3`hi2oeM55;lNGVLU|Fl~HlGgC{nh4Qt>DM|PRc zG8R;5WS8(ym7@3uoZW&FSD-u<;+enq9Rk|g8l`bQ(Jy?hbc81|6oKM#@7#?K-@Rj@3ll7B zTP-~tUBjJDc~lkYdv?kKF^ajGH%aIwmh(zKqSyE%R)Y2qq|1YJ80Kt)4vv)`;(Lh)tPXczus|vWhM86fVwe=;P9);Y&L}R1hi{y2PR8Weu+nKD=I5tl zZhk)c#i#mSDTF#qR_%GIKoRRC7G$rW!HWb7sL2#~rb18$niM0-@1> z1rrUF!QYZT>^gDP5sl={&=9+FIC_wKb~({N{Ikbihn~o#A7{*9{+Ns{Z4~(kzs)Wx z<_XwzaB+GVM|(Tb+Sw4Ft2%Xl950?diRaIs$Kxl@VrptGmag4W+Hl9=UfjKXD?a@2 zL(##VZUa89jq%8k%FSq_sWK+I5!eih#y$~!eyTFQ5np`qMLd4|BzAW9H4N@iUWbpu z-&S5zKP==BsUt(fKJM%0&D(ycE6hh;3UTp3hL`&nDmdfD1$^w(rOA9lCpO2|=ji-9p(ZX&Ck*ju_F$n^>=c+4DS2kT< z$j{l?>9~1)E=H74+$YGrW6g;%wVepP_bl+H?o*bT%p@H=)+Ij_AM!*s)bJ?!74G-) zM6~P>xR4)=TM&jHF}_w@XhUeLDfhG)9CeF8c>i!;W$DE2W8%!V0zG&TW+S+u?9umt zBilo_6!O<;mp#s+Ur}B#Dem&7HUxo!$B43{EN44Q+fCgof-ipXDZ-Cm6zzy{%Z_^N z{)I=1e9L1*Q}Bf~uz*7|!Y6n)+^E~sFZ_6Mr_vC?8PNrnF`aqDq7Yj55O;lRnz%mm z6E56nL!CZyN621}yR8ZVMz(uupX86Wj9opnYd+;hap$-=$|85$c`QCM>NbWvXO0AH z!&Fyt=LOr17uZ!N~#) z@1$i>sw{jApV|O~Az7C*-sA&ih>3V#U2uZHi+D1oR-U=9RZBry3lD88ZIcCFiXRVG zTv+I*^gcgFSSdK+9T^^ToH?qHJ`#t0j%F22zI)yaa*3(TZqMbM{PgjGP7B&l(nIA##fVnjNBQco}afPD9=U*@>J-JQ*tndT0~hT^WeFPzWShac_lt1TIi zjSb;kSq<)iV_J&2v!{qo*eg~3xMTLn??Cn>cqGgG$kLwBAq;y>d^E&ee%S2 zuRVJDT;?^mUsH-JyM3=;TZpFoEzL~EoM_(5{TNL@CYWtdM3%*R2{@?(PhxVk6)p|iy z069Wyf@GvJ0NGdr>!7bZ*aVF9Ze|NgD>=FoH&8M!wzfTf(%>QiUc*UmhjjC&y4!%B zKkym8Au>W~hqibD1#!R$keu8Syv$hg0VWx(GJLM6=xFT^H>`o~gxD z;0;ya>AKU4X-JoJli469UOIhh*d>Ux_b0KsYx7k5clri_jckuigs$cV1=&#TbBtv)?%*m;pNs0(1b+ zV0nve!Y^LNqlb?*kktUzr9#xw=$ovh(-~8u?yu|^#5qj>gm#&&BM*cJ{coj|TuwJC zy^IK{2%0eYL6!#tvNXf!pX?wRK%ycX2$Jl^z(7{1l75(`R9XHhk{rq4ydqw*BOLMz zbeIRk_zX1~KF*LM1=;O2#Gt=179*nwz=k!DL|_M9r_LWHE*KSh>Xk1nlKS3qp(q?9TjLuY-j(DWvq{>4GJ(*sQTscm-kWqZG+iiVG4>BNCveQR1v z;S=ThQ1Mjobb4cYbYhggY~)i=U`dI!!QtYX%C^NR2x@>n})P^X$u1DF$zw0 z9qW<`Z3}&i7G-S$=q20=$L*Z$Gd9-h0avXPX%BAvWFB!0GJvF|ee##N290u`1Tq^s z?hd{7j42CtmhZEF6rDS?Z0P#{s1(KBT}^->GnMNdu3~sVZbK zIGj|{IH0=xrO*aUmziB|#-e;ISfsK{`&eJx1($Bp*iZU3wft+KPIt^{Bx+7yDg2}R zT?)Sb^FRMTIq(#2Tve5>LTcNLN_}zfvPaomtlsEW6ng*ozG83xB|*B~t@pQ-kZMnV zp+xl;vp>~eEs+WD#3kRb#7~7a4mnX@WNDw)r@wYs`r5vPNBL^wfUiift~Bj(=Pd(2 zCQ40@!c5#~AdLZYcl^@7VTnuemx88lIKCC9%CzAM4Fz7QB|e;M zf1Y;ux5@wf3f_J&Vy^MVXrL}dI7y@ZcB!N_?W(_|xzzGY_<=t0(Iet(M#O7z2iHPe zzj;08#nUhWw!O70KDHG*t(JMz&?{aM?s!`R&3kF6c< zIm$^;+9>W>^$~7NMjq{(4`Y&K@!GZE$U`QAxEp0_Ys;r1z=y-%n0_I#pj7GKm>7%u zcW=in(YL+Rildc&yvs9_WWMJ~v>^CmC&k3*P&9_%Z#jmEg?Hhj zsaT;cu1@@99PPh)hz6RRBA1;6Iw64$wJNBpSxV)AjAiENJe9_cp^&Q3n?_=rP&Y1i4k0}l91 z%DVaBJ|^T{F_b0wUtRS>I=dqR;?3P zc118bocEUWdlJ)^>#JNF@?tWY$?3hl-PqmT(Rg9kE9pH^$)loiads5H z{QR@{>CZlOIi=pf7c+^Cps6`E9nI!ceDJ{sKEjiJuUB|A3{<|d;0?jxVZ40tG#)+r zO3&Bv_19mO74&j9MioKoq~b@~O-;|o;=*;|za4XnH)Fgx>*K8`lT1{ygA1PCcd`u0 z@|065_7#V%_~p-k7E?3R@tr^Z#~PzFW4Cn@t-~|bOVuycO`09&E$ETOEx_uDO*LL*XSH7OQ+_A%}+31faU;Qi=nq%?pPd*mO1F^EX9}l0e z#p>ps@A#p8q21t^El$p$d@`nB5}!JU5R#o^oYKJpMe-H_6X{CXKxn~a>^|k#!r7@Q*H^f=gZ(3wQRO=Y zP5Dlpr_N1`4SA;!^)CBGCcJZ(EPW(96|c`vsV$vQJsxm-gJ5QD`_M;ql9#k&zQa#p zct=yAoxTTw%b>~-=>_fBGp=X6P2Wk|K~j;<@?PzcYK;3c>N1P5Er3)Tia>{Y*i;|O@sGReXZBef zp*C-2WjP)`d=R^8%jTOCF{e6o_x`)8zv}dz2bZzGzZ1I~tD^BTKK}UQSh{g1PL;Q$ zLI2R0%FAVNFa4?d7k0KW?=v^W&hJU{DjVwKDYw*P;z^s!Vu^;@Qu^uj&8=7wUuS{T z>SjEA{5+n#c%eQc7mKr(^22*K<2%3iN!(ZZFD}f+=x|?5EB+kIoME%b;UKm)H)B(L z*woxYEUMq?85|a!)VU$I(Zt!uo5CZ)4{?va(&_w+R#fdi zjzqWG9LlodKprxlbz6>sw#}C0FJ`{oZnTBThoG`8PCHcfgX;J%-=cpFhQ~A%eYG#D zTaW4%P(e?YMk#y03j3Ry-=t{&-mI?1rCa?vcu{}fa8&_~pKtQ@O*oyV-{iTS=xMwW*#u+8E%ogHWr+@DJa$gIc4gvYH!&I*Y)&}d8DBlv6c|X(x?w;o<8=V# zE9Hs8;-`Y!Jxxh8N}uY-UeYSxvZ!=p)&a2>DGz~LPXbb|QHSNRBE;w6`uxJYKtjGsCVf7S4M)s`MJJZgktC|F^}>Q(H{ zWQTB!K^1rj9|jJF&rFNlS^dPIe0_CY%=)ewf-Dn)Z+}fvmohTz%*fg%nWgk4ssXY2 z??DL-<)C8AFW8l1Y6#d7hFu+iWZLm6s^krJnWCxBvXExuk{LZVxMFh8Br>FW+2?5;O`v*1nt}AiLf0!r=1}Ggz(SlGE zffxgMXl6hGBMWVyf-z^SK6HBEAO?W+U~rDW2{gV~TMP_mQ?nf(OX3NA)C24obg`0> zy2Rj*x??+)W$4WnaSWE^O*9f$5Rlh3KS*0^^>SRD7Qp0+I?`mYe<&sz8l-4&<~m4z z;>CrTGLg6(KdEf1($G#E|C2sv1wQO(gG>d3+-*a8U`&%;s~EGcbZLG~22=Rx4h3Di*f8qKb|D8Fyl|Ifb^VN{?6+F{^Rq zDKw`|`(vEa8>7AnB2&@Vyh_iGt<9JSkMNU%^6=M_kZI-x-6$s|*3x8|LXp~zSUT#d z{%z9B^ne5h{OKXwf;JU#)bEEs{>eWtHvit$AARqie!rUtPlECFJ5|~h``7dx)ouP& zZkg(eKleaWQuYP!Bu6{e;bW2^@qY6m*!egK>xPUZ%J>B%l?rIul9IV9|UUn7t3NgeR_lAB)&zw4@cE8!N%QO-1)>LAZ3q<>hXz&7ZWkr z!~`OIIsy;wdE>Ht_?~^yw7btyQ1#gITzFKEqoz?o;KfRAXci~vNya(}&2ii;w&N}v zR=N|uC^QZxcXCGplYfv84>lA-!=o{(xN)Zm^s|GGqqmq?q?LoOBYBtz!fk7N+dI8j z)RhyQ<32i%Bkq`>MNq~rFgUj{;hkzuc{2M{VV^4xeXoglGL8XbGB_uUaz_CIyHSK= zjZv@q_7QUfxoe6Yb3VmF=|J1cPB`u?V}e;Z;+5hHbJI$DaIlkr2{p!SDnpbBXMgVI zK=4I4`EZ8_7w8ZAo*H%_42UM~i{TEo1}7*C-$MWGXgB1R6seRcq$Ruy+FJvM@;l0$bvQmW4%2}Z;p05J5YH)ip$f3c=GU<@##-~ z7+-w$X}oyyFwTz;O%p;Tj;P{(7bdwE7nkC_ciz=^!IP$3=s!C<6E9ypkDvei)8L*X z)ZSjp_w#OVZN&QW%UD@{7N5!e-~O9_9slmH{%w5q<(C%jlBP_QQg?iW+C(#M+<7N% z-g!Un-up1#dH-8+{nq^$9GQrt(=7kFlEC~w$7*01y!6RpXAv$G8Q<<*sV@Zh1# z5Q_v67*QuY5w5h$F#xY*aukSGBMrDyZ_A>9tGujaD zz7bt2e;$>nPGq|gio>w)L>gCngCL6?VGMoRV}5}FYGJGBZjV*6P`XVaeCm(|2MRBR zLr|%o;Q-C?QI3&vOav~Euk;Xz7lA7M80XQ>F@c|Y${HyE&BQ$Md3*$2!iA+>^-2N8 zklR<_6QckD1AF zl^w>Q;quQNMGfxU5}c1>rA-k$I})b_+nj7D4T&R9BO2;&m`fm?Xg{)Skmt&8JuLbp zt+Aucr`(W#2%x;kQ+0)W&9<&z_|(1&CvcRF?0Z-g&CWQ&lAG|gC;Da2(QAZ3U7@{( zA2?Q-X3mHse@Qdu0W55lzbfQqCljaC_+BmLuZ0@QGw_QrrLFqYQTl{Q#T5Y@eM|B% z)GdyhrH>)+DC1*l=h%UT@M}Wt^MKOcyI!|9lm}|_InGz@^ay>P(v~!U4(Mj*@3r}v zxV|_S3)4zx<=^O_`aHMcS%yg?jsoVMN{-uYs62ZY;E>9;@_I_;aYnR~hR{kIPri*v z&k=(cqIY+D$3j9M39SBzbR*wrcj&kK6h8#>{R)dkhcyrB`

    4ZiXFUl<_gq;T>0M z&tATKDcqax8x|Jk)t=AE-*D_6o_I&w)0b=U=*jc=?6Y6SvS9Q0#M4;cSdX9o;e%tYL9DH9#Dhmq;`!=E?Cz;A?H!2Og=;atcuj53fXX=w zztwIl4{6sa2g)Y5irEfl+mZrH+HsXn)gAL;lubdx3k>zqIs5bNuiCxA{03iF)En_yy-sUY zZ})Rm{k_AL2Zf(+^7Simexv7ae%^%pU;n@V@BcgnUxttkJ)bm{OcRW@c&2l+Q9oyJ z`DrYmcRs+j{lN`jiy{9-kGnbxEUfQ5nA3~Q_^;;TS6vgjREE=+N>=PW$>@oZ)boQ5 z@LAx4o}WDei#=a!i<>>@DU6PO*2%8zhP}UX@i$>Q&iLYkA0BD5R-`*xep&PN@6c>V z-0TG20$bcmNX1`ukut9IQzx7ZZy2ef$3R}zmGZb^?QryJr-y8^L(fRHC*Pzu2rnxe z+UA7OAHVzzY>*7Y`izBHBy~Qls9}{Iov9fXxg#in7VGUve|3WV7@El_gkUkz7yvLs zfZhTP58(6_<9#MZqdp9r%#iDAVT$~i*@YPqY%k25I$M}tgj=~qo-OSsvA(_$E30c} zWC#jM_)!j1K}*t|k(CjW&=g}P2K3pdJN6vB81T1J@cWqpNgJWq9#g5Sexs374H1$& z$lxbK^_MsRs9u0zr5P(?261sZUg9WK(6)DhF|m+(F`Z(xVJO+@RR?V_@T3)kBl5xN zt}g?2Ru95}v*Qb4&zbDVAHv8BZ8NVZGa0hNmS5=SxImaX^3^-}&gGtemvhR82VsJx z>e!7z4QD2cChq(~@I<~-?rJ%7nSfR^C;N+jnLag+ zIPfW!1yA})cs+8CNGHhbd+-3D((Vjocfa-D2G#!k{-pY z6-^uP?ISNiQUPqlQ0=hDG-`wMu`@4Oq#@DhLE$Es_|flD@b%q)`hD`#Pq9N`F1mcT z&8e#SioLWoO{?mLt3SuHn5$dSUcuM)TYuHu{pJ6PJ^d64Gkr$YSJlxcPE58d{YCog zdMcbAyQ_b~uQX}a*Sr{3-EgmbEjX(%cJLpIgz+Ps`npKeuY*bZtGK{}9RTT;cns2p zt@d63qi@#r^k0Fi-h6}Ls$bxfCjKRibV>V?m&MiJ%wOEnwkrGWqVZ>6BFW| zgcNUrU+(upxC4Fr2jT_A2lfvPnRgszRlIm2j-X@W5kAn9@qH=iV&WMA!m#2zqOk>& z(a-_h*l-FCyjw-Iu!7%{&iXP54Q~b~$BOvFlZ$8_p2kj#dz%h@j|~E^WATRjd;77u zxf5HP+p)Xbiv8A}VD@5H-~EFF?|jUQ?IA1nm~#Gl1p zyIbpV(AtS1@u5smK^yJhv3Nvwei4uHv0>lSGSh5CbAn06MvONQQVCvhF8|Nn~YX_}3-rtVPGj_D>ix<5#?+%{|UXJMEE;A-98AtHImoVO>ZkbPY z0nCRo&+blyR{MK9KBj8FwH12^qgG$W%jb{d#j}U;?D5y}*{45=FFyY?HrG}ar@mO6 zpNYk}IUj|^r0LG~j`AA*o}<@QwnoQQ7Mb8?mr`Fmef%VT@{=FO*AKpqCr=*7g9l&5 z>dWV`xymkq$FcJASv-F9FdphzUtf3qn4epS`|rFT@4fe7+`adH+`jXEEL^`AbJy<1 zSaUIY2gcQba&+c}$`Ivc(`ALG#ygP|?m!=DGpIT+EbHDly;Rx^kBi1h`+5BMQEaTQ zsjeJ(F(4DR2%N^oDaTo#>6Td}$8nC!FP^Ck_o%*)xESuC>6r9P!6Xx+-19_zN7JFAJJ51%y7>hBcj}A2bLhLv|4ln637FrQ*@uh7Y z8POP5X~;c62(`R3Qhqq9k?;^svEz>g0tnBE3yUOqh(i^?r@)VPNMk;YV+nRxV`v0D z2t&9tn|2mh7Ca*Ox3Eg|vKx}IH9`W)0AaT4vGgn)U^1TFA_&w-19na^=HBDDQng{e zk4SZnHlM}9)ZttZaOkq*#hog4yRW|drFTi5b2`eU z(pYp3s|{gtzd1H!;p?-vr_r5_B?mHa2zLPoVf!Q3UD$Icj_If zJ@>tM0XY1B8(#s$a~^( zcyt!q!ne7rhvP;MbH^loA4gLjpIxdwSD6(37lffQG*ARlW6Dz&Pk_ru*DBwR)Ni`K zP`HfqWo^M4X-Dk6AVF>Wn9_AZ{RT&-&NTXCT-B*L+HV0G`O;LoJ)(L}Iix;N=iOfn z^vGRx^ZY1Un`?2@+K!{W?RfI&t5{Zhxwg8hw)Bbmvuz*ccdT;On3z@@JQI`6>6m7h zt&bz*zVYE$n46FLckji!_wUE;TX$mV`n9-q^Jd(;dpGXiyBF`!*1r2*ysw8v3o|pb zF*?=|uBo`Ov=n#bXJ&RGcJ_|r$;wtdez_UXS9fDoX-PkOcygw?Gwvf0NA;x-;I35e z;o?3tj&~)`MpREOm8SwHZEtR_$CJnO8_Thy{)&b6YB|-eTskcd_xF@PJF&j+3d<~S?T)e=U>NP|K#WKmp}e_JX_gN8V<$c;Z&H==v-8)t?5^}934>^V4;iR zh`^pQO**yY=U8c`;^6Y0yK41Soo68o+%)CHi?P*?ve>5Q@-%!GsoIB5+sT*uL2(pC zJYeOIgRRpZ%Wk{+t$Ng(^zCoazXoG-v46!K)oso>l#Xh<+3Qs|RJYyR++Vl7s@~); z)$6oY^>#m3)!!!^Fx}6uRKOMOtEz4P>yh`GdQZ6qp(eyrHc3Rk_ihuRz3E{Eo1S79&4krp30MqjTsMp(+PVNZ<&N3 z8Iyu69cApI*%n4oR9hoeJ?O!@7&{=+SWkNBZDY~`!Xzy{dr+(=!>M%Qp0p4jd?s|h zJ2cA%f6~(k7!G|p+1~!8$38Xr;hQfRY)%Km7i&UBRcGsMFJvKjjMMDwY}~$m%S<<`o=7VTVT@Pw2(C_Iq!0icGRvOO zEabu+a0dKh4o=0iTIit;|AdQm**OIB0CTH{dzTQ1Fo=LDIxIpKn8rRa@-ROLw{Sxk z!P(N=J3H~0za zPYkKc9=%dB7Yofc%aUntkQ;;$bYJnaMWOuW}1cGr<}#5q7RTlwaY2S>?-djkpoVdfbdB zu2j~^Ef4rquV^>3w&crsi$9FSTW}E3*E1ldS9vo#A4~Js#rRIT@VZUUs1j*?GA!O$ z@rLd!A*oB(;%*ufN4p%6hM2I&1~Qx{}$6)ek20;Xl94do0kxT?oOkK<76l1GphWvgl~F#4b~t$Mg)D6JDW z%1&)0)n8K0{|ca0g~4CafC2?NRx=tq?zWN1Ql(T^)1%<>zoe!8C1gg1I3*ldfJ=Aj zY+Z2po$<568YS~p+A^o^mM~^xr57Y{+F=%1Bc!Q!b^W?*X^EqRGY3Y{OIae8vUsaqDvN( zUzZQt=R+l|`1p3>TI~hbg};7rw_g4$|8BYsn@@s+v%;4!i#_~=bp`~^CM@#H+wdK` z4h<^ilyf_E;jXG^D{ep3NqeaF>EfDH;K)Ddg%*xIoM_I+t$QED%-preqkG_!dV=E$ zne=9X5xi8hIpK#LL`;$}*}+6Myb>#%S^TxVv*+Wfdc>!UHrQRj3hXiO1fuQn1n5O^KP z>xBg{gIr>-^kH`p6VfRR)L5Xe*E=JW8R9MXV^E2?v>?80aUq&h6Xx^QHa0yOig1sW z_S4EI*mrhZz+1u-pPuDTgZ0fFrw4gS*(dE8XE15KFgq2C^K;TGey2=EWn3-zq#x=- za2ByI{(IkJp*&(rUX@1uDi_1vQFNs8!{i=E-NAKpOw*C#I@xS0y*M7M&w{t{iAm+# z-B_5L3$fmDC|;KdSp;(IE;{uwNsJ@dWyHjG<^$!~M{5c{X^k+^w5Z*J_ojRuAMNQm zjD!6>3sN~Ii!wQ-^0PQUAJ?xfS%7#Zy1a@*`2<%<9bht&NygUBX8ibXe-K}N^@YbP z97Bgt^plT1ia+_|KaPg@Vg!lA>GLnXj29~_F~7JNiwoCOo~D%U98=jB9D%uwkW}$H zAx;-e1ooGC40dT8YD{qIyIXGDyb<&Bvnosdo>-(F!0)r_o*fa4PdOs&*^>tvXRWK+ zLv_|`cKa+{yAd~U-BbSNoy6Rk^76^U`1D7AqjWfo8@F$&E;lWh-Pu2kQPDX(I;pf( z-5zUL@GvpfA3y!uzlvXc`s4WI+uw>m`G@}`PBkWYvCQ#j8sAX<$uE@wCSAE7Dsw6u zEq3KGAlS7!-zX2X8`Nj+PDU{a&$#JK{_?4d69p@H^tGLYMg$MQBS6QEvH!urp2FtJ z1KI|yL5*)j7xcess zWV8vC<=UmC;6sgu6ltD!(rsIK#c_a~oI_eOH^GiUV0~Pf^2YsyymGYM&Fc#>H92YA zl#R`;U6)%L2`_$7`8q#U`@j6mJ7Ty~i6d_hRaa>TSlB=s|MVw6iBEt2i}<5I{s-}o z{?T`1VR6ZAA`|Q!yUG!YEPO!l23^FR-CE=@b1}5T93Q!(bl6r~yw5J+!`y}IK2?c_ zP>IF5-fc(TsB94@<_$<&$}?q|yT0bj3{iGTKm=oyBNl-$zPEQ36OrZg z@?GPyrM>X3FO@GZKA~+TB_y zrr7Dl{eK8Bs2dz(IWVMjy78j%PI?M zL)8`^s%%`FnTq${y&uqS+}PMVd<;kC!Q~_$CmPrvQ`Ddv?aS-aiKVH=NfJ1 z`1rWnaz)PhL7CX2Ul(2MI;F2aRDbg5>9csbz8x)K97k1dZSN@0PaQ_jsroda_o33%@@T3%uG+)yej^Sx{i>V`?mT9l~z-;F)N%1x!5tz@rm5c%Ke|D%bd#2 zt?P3!KQp1WKpCw38CFIk&{9cOoj>&vxaWP`fvWPLG^c!zjSa=@2waB2$5c&;)aj3Z<~snC-G!evDC>QEIgqlmH5&p;Z!VmboEi< zq#ORbaTPPf$TEu`kgwo2bkVm9x1H_ZxX>$|5KHc4H2HG~;~Zrn~Ap#UrHz-6a{MTTV;>}*b~3_^_EpaoysPVZum7wgM6 zJLh!gWsFzCky|DN#&j?5Vs*uoKj}bdq-u+Ske*JC!8I2ya!f}Gyp-my=!Fgu2ENqG z4no0M;_6t~4kZRf4X=d=dc5PNtoW&n%dwAuVZc)vT!a|XmkA&XP}K3^hp_16nH*Tt zzW|eb#F0r57)O|H($slIT#B2qO7EeE(vuEuL<22fTFRFF zGEjj@N!$uWFkVqCoF^Laksb(h5IS+WtanC7V!%+r3}P5R>=N^ z6G1AI3NS{%Km++o>X9xkw+=MRy#9=p*eYBMh#DPc%54#gI}v ztS@dT$H#Vh`0BBeyX!gbg`J?V59`usH{0l+I1?tnB}~7dw7^uqw!p7^@F~U$;QChG^h*5TkuIJ5c&AGK zixMnmBP$QM2v7PdRsA4q6SoY)*X~=48(2B$k5$K?@CwLg{8l^6 zsZBfb-o|QSgC1U2>$lUx7R3!jvLk%QTYr}=v~tXT8cX~DtEVeHYM2g+M>tf9^vm)g z(rmI##eph*m~`Xo^e9dyqn%Lt@W@!O0AiKtj$@LSIw|}cEU75ot-~ha5-9y=+$kS6 z;aM7+u&}CnxtT!y9fp+jXlpxvMXwLZg{?~u_OHYls`!JpgS*(t3YGq-pSG4tJQad> z7Nx{(XY^>QS@3Rx+8ELyP56@@&qkT{e)IwpzfPpfx47|d`zv}re&LKizBW=qGK5+u zlXz@!ktml}HpVyj@vnS|FM4 zru1vjw6}s5U<;napY*lqMvq%b2ht7rP8j-w0GcvK~W=JoQq%T3UGSkz4YfL z{0dXPsQf|~!RggyUy6+J7*|)g`K?d-ugW-IHDh5qvaD3q(HGj=CQdXE4}5Z9-Zpxf z7&`KusqEHZmlhNAOlY!jhY2t)l1IS6O7^{0PFmA;kB^P|m>iDm8XDm^E+)fYM zHawBy1}_BPjo^aGGcjML+0B?5osmYv6Y}%(b6)s1i6BZ(V|>gLdGLHp+z}oEFcOee z?w;rF6|XlynCxB{h=~R#MsVa6!YI)rzLFL1(8ua}CIy+a;Vu`BH)1jp!5cgyM?3mh zCh>moWVpi{c}I)%?EYY)7U2-PC@hrNZTY?_;>ZFeCbDyv%b+KFnY8nfbm$cyj*#N6 zD;9W>zDx#jG}GR0?yT5HP^9!`B8%N&2=F$xw!JdFr*FWQ?hg!&#)aa0bbRg!u^o1j zDQ}qYJ`|2);W#@!@Ucjf4dsi{4q+A(v*dGsoCg=-_x4nQ?G@5&K7H%GZ9yHS>^(|CyO-3+two z$CHzdn3@=ix#?ys&CkSy(gnei1tBUHXJ;HO34ed-d>9_iBhEN>451m5wMTN>Ke>pb zGxZQEzkNfE7;a3*=)|la^nJq z-H$b{nU0;-vGVL7R=IO+WmDg6Pogr8RKwx6hdS@0$(Upu=0srRM(a60|ULj$L90T zei2`M@yqz-FF%Vf1i!wqti0ZdjpY|{ae5fD(~~Z z3)+329u`m122w}Zal<4kMT0R40-Jh@2je>yM>2WMU206;4i2N|=*2u{k9voIeM04i zU1i|(B2eLB;U2p}DFCKGS-*1#mk^R$_=NybWzu6k1x%ZVaDX-k8mQBz)x3~;(=vvk zZr25-w1-{ayeS`rmIW7bqJC8|4Gx%$~=-+8W z*h$5>6hFYT0G06`?K5%Wo3s#uR04V~g0=#|5pxnP1XkNy{?e`>v|?8vdfF8x(Am*} z@P+vh(;!-Do7t_JJ5&*x9h9*vf*{p$(%$hR=$s$%yHjDMKTpDYWCrKz6;24)^DdE7ieK`5Wj} zd0|JW@{+XU7{!Y|_4OBhv2%PGtGg$$vV9WUd*`vIcAMSIdxzY;cA!3I&%4ZMcep2w zx=-K9akah5qn@+l80X^)p+p5FT{)gIR2Zz{CDvefBnPw@h^TE zPnTDHtl-AZZmh0v#@gnVBGeai%GZxS`8e+0eI#v+L*J8UiAq|F1eoze($6w)^<;0W#=ebiZeTH zhejG|dq&l6jVJvfQ=9hJYm)7aiWj`iKcSW|keZnk1|Yd1FcRpv$0 zrOGeIIxZ~D$JET6@@i6j%v3Zcn_jek|Nb5I2}^39o8DQ+F~iIcv51>~oqmw(TsYF0 z-GbbiMc=-@y&KP0HeyX-!EX(yyl_k~0_Z2tm*b0vPvgn*daMGsycSPht}367)SvaM z?`p<^>dW1CKZtif_#|%KxgQf#vvG9U=XmTKoQA55%Fm!^haYK#y3p8F`0QHu5z4B+ z^t%X_>1%1bsVwFb)lR@~9dcKfU?`ZBDeQCCqUr#1rfMo^BM|Jf*$3EHL57Mt0HC29=iW6_ssl=PTV6^Huw+Fsa_8Z-0yaiaig}wH~^PzNl_J>Z)79 zTjBi`SkyP+LSgs1?N#+Af2lfgc~!mLPb!D|D_~H+E*#3RMgQxliuYANSIoZ&!Y=hD zntjyaKmP7N`F^@Ffb!dV`Os4eKnazp34RHoAB=@T6P`~F4|&%gz;-D5`Vww^Ql?hm zq|#W-1n)2kKJZvy3R;&ZYs;&UWqN^6g^lzTA4a?LO>LS92gu@&Sle}>bq#)EvZG6#7h`2aU_xOoc`P&$lo=^8eK5W$6cckLcvgI3$3)DjT6+c~Frv`F zs;nI`mdh`fV`F2(gI5UgL<%8`pvu%@fN3;aU5PDm@YhCZziRu}8Rq4Gi+vm=glMp>AmyfZ^c^_ExrQHSZ{ zGME(50H+~_k4Y1bnIX-bZl(N@-p9fTQ_dEB80&NC&ox+t`R$&p;us3zhmfd!v<-tL z)0|<#c;Ae^I7pk*yTZ(7%&ov!3cCJQe=<^bqts&|LjO3HXcC9 z-ji^`NgPvXCKUSSpeteB5j%YHLy(x|Qp*-e%@GTfJ*-R@J{4ZS>{+qY7#(xEWLj30 zFg0?i<4qXdcBx!{yURQd#cVWs*_d9Xh)0$^Fxko~fiMG~4ur{5^wqlSi>iVwaHEK8 z?ue0IR`@K&R3Mav=|BrLHn(HderKqt`jx^HwAw1|?GtO8!G%S-T3gK3q1usl)d>sq z>4szKJ5(uV1t3dDQP#9gZI=#&zM0?!OfSAf8|#hqk#Xtt^7{3kxC=jr5A#o=~0K@`N#hQFA%G3Xz4{#UlXOMwpkyyAK7K4zDogD?YjL`<-P`US8`QlzpsP~ zY`1;(RmF~9weNQ4uYL!28}y_gswny|9{eaC=&PVgoKkv0>Dz|GNSK1NyY14g+x<0x z7vG{1E^&19>25##3f+{T>Q-^0+Wvq;&z~@qo)xcYwCd;$T4;G~r=nn7Vr55I&YCWN zhy~DKU;Sm+sZV^i6qf4mY8YMGqyuv)16Sd?^yQ0!zM3WuLElQ}#RWnw@xSo7N*5*< zM}|hcI(cD!K8A-m#z_2$_&E3~5Hp#_YF#EY_V)MXU;K^SIWCU7uHd`C$wVV}At8kE zkx@*793VK`i(NejW%tX`A*U^Hmlb#2O!!_Ucn-o63zo;}3^5tQZVx82#VZXBd$qTB zSupXq+Fa!`{HE_76C4wO92dz^Y@`Wg!}+wc?cHYFhcz}LdKDOg4S00#Qe)zGgu8`? zl_%`h>y4umjg>?Uf{D%~@~C$K_6~4V67)~zQJ8uVJ~9q*ycJLGqU(je-t(9oV z=pT!%)@eL`@-m)1U-PQ{om~W4DjSNMcgKjoC+(?QlmY4`!Y}fTBhc9afFPCQ*+@eK zu}rMHeNj4bbW|>U>yM!^j^~<+`GsrIoSn14nVod()>-$-8=Ib3US%iJ$)2UpFCFiJ@<|qc4ROCPWhtT zQYWZu#DzQ8n8as{gkY3DoHm8Fqwb`tU*F}du^$Uu#~PzP!jxSb>_X)3CIny>49PF7 z04_1fkXP_qlp#}hKnFKxHmKMIf(JO_es1ksdV!oi&}4(&%R z(+Jg4@I-Kgkzs+MK5c;(^+}KE5gp)T;Vk8vHo?2q7{97)F&6cLM%TTHGwXgm<%71~ zl#6EQ_4tdp+e&c}9{Mu$z@MlLvFMaGmWg%3OQkqNKVJ0(p7Auhb~x&iwz`_DVC zO6nYm$JA=0$P*^Gp_{m8A4y!YZ6$pjN7C8xQ=6i+Y^d(jZqYZ?ytCj_Z2@JReuE?K z8WU5>6ZHdAvoXG5Fr{n$rk3Cu`oLsi~h3-YmB=C zxAu=?b@wn_emV?Dga;b1KY>@SLd~Mv&QKAslr*%OF{v z^CvsooALD*U&LoW|9O1%#h3AK|Kcy=r$75Np1fSKuxMbU5%0YBUVQS&x8ly7JMrO% z@5hq(idnTq|L7n5aeVi?-;EDG`Y>ka7QD#dRMf2P?92aFJYU<5&F#I|6dralwGa?- zl%DdmSLru2lt+46Xnf3Zfw}9L#Q`r@H)DBqE7mqzdUn0&fHK5!!jwIB#!jg(V7DQ8 zjNOU)*OvNc7MQHAZ^_S=^t%?`u=AL94_<(Kvgpg;KWJ-@R2KUN#$tBidfdEmGj80t zraogyahi|0#cSSm#ZJrYli?}gRYqcRdM@t1^KQKJ!H4nQ$DhQ<-}=3H|AUWw9O3NT zVvJ8Tl^5C8aIfE`+B%N3q&^`GzIX3V+`e@qZr!>W?<$Soeec7#apztvT)U}yvlxR) zPZpzWDE$zku^5HjeZIY(eipLUMPK6H+N%aUp&pxWgMKS4Kl4NTWV8|)CL`?|LDCuiBXOtRUa|buXvPQ zhbY42WGLD#RB76}zOI;xeYP#s)7t*!7yIsS+Fyl9^(KA$Tl81#-=;6>ik{~!ZrwCj z^{dP%?69RqzV4dpP5x4K;_|9`yPs6Q%Dt*z7Y+sNuMchNufU^!&HrzLuuHv(?!4pc zdw=?UJ1WKN1Vbi24W8H!HKpZ*ldnlSt2cvM5RlDjln{m`ddu3S$AmI6=^=<%m~E2PY27?}zj zglTOTK53jjvT+?oD@(%&-a*-8@nO*PZ&2R)yKj=lzv7#rVA z;acOJbmz}HeJafu&=*$BZnmd9v~7i3X5&o@Yq}>Harf@Ag4bZyVwVP(W>yMLP348o zIgt;Da~~ixl|@@{)G#nfZ|7tTi8Bn^8O)>^;xwZWq_hPnf@5&XQzrqc5CXq2h>ocU zrK8hDvP zV5<`QXJ*EEM!N7QO|gD#Fh zVW43=rg9lbXjNAlS>YMH#^ldUm-%GkWR@1L;DZ z8E*yzlm}17IdgNM8OXh21r!Al+S;KTT9o+-U$PeQ=B zW}4$72!%)Ov7l3Uh$Cs{x*!M!0NFn1FME7ZZwY%sgIy+~7}RCG%35g5_(9KCf1xE< z`!yaJJYlWB9f-F+v}0IdmtV>VMyN!a_IR<4-TX4$sijQnYp)3dZEflj+(EXBZ&4=0 zxQK%d>0G^vW@EA&4hfr%`KhW)>+n%YS#i_LX2LK*(wpW~nLNCTyPpbR7w1F9O*VMI zxxy+k&`EtZG6zWOqqr% zNeOD(`X!udlXeJ|&|R@5Aj2hHD56O4SU9@XgTa!Xc3PvVyEHXDtblV~r@pPAx!|ec zWcZj$nD*?JAnj~KUot?R(}gz*9I41pR1E{PuE#QTC`{h~V3Vc_jDOO#qpEv_$uh36 z{LMT-rO#9*!$|xx#;U6dGjTMn1!n=0BHrm{lG^rF3m)m@DKQGR3nqb7cI`hQaCdy| zO?FsQ-s~3-3e#u{B0e(z=qJBR!PkG9CnK0RKKZ4usda?*FWb_N+287?sBZhJN44$s zeHDf6ctXDFe_@@dy@s zEa+!sAsE>dI!#;G)9x2>2E6#S4tsQhF|M{<{St2aciGXGU(Ju|$1vzsuF?+GfkQ!~ zX$4*icw8#&RgXV&d~&ymul?p1bfiI++=8pP0h7GEefnL3Pj{)LC-sIYTGx|mkV^QD z8C7v)c%;o$cVQRZnGf(K$44Ajc5F0+%SwG8r86__Rl)FP+#lo}QsS%Nbr66Z93A^e zA&$iH5lQ+o>AtzK9^0GivDa#OLZ7yWbE43eC1T+FER`3tX4gQi{5k7)&|1dZ%>+Do~n+UJt02T%yFk!+IK~Q6aqq&EYKN}bn z4+*@|P+`L_nFp1g)aUps^LKjS?{H)H3lskhr7^p$*a^Vy0TNAY0s7v($YXVMwI zmWk)=M-V^}PbOSBYLN-Kf#F6BinnG5Q@_mcx(K`wTu~Z*JezPaad&VGuP8Hkl`a-q zGTA4d7(v;b_+BPg$A|laV<0_VG%ko#KByp%$eu|p3J`ffTEXl34w^IUR8xBT;#3_x z$Nn)P$9^+v5PW$GM%neW?_&~A4w$?>kBJGzYn0;xBX(70*xkYXRveSZ@s}L8MLBlJ z;9+OWVNTk^$EgC84FX5nB-V>l`YB#f;G}+V|_#Uzi;~41vja2 zD7!Hjr}PdEXvezHG`)9G$5)H=+Q*qkbJC5h8+wt|2m3Z`YCDu2#l{6Yhs0>hc zs4oaRYTIX_i+981jwg6o%19kEFuwHUK6Fq{RK}@$+?6-p;GwLDF6Au(OLhy8=fh*o z7)M|*Gbi|Q;ZptD-}NM?- zJRUswGFsd#qlb9R&d&LGO2XwxGTH>vm>oU{t=ZW(K8`SH$m5f26A4%4#p90TK`b~O z%6p86mv^n`%T7+pKRaG{7(bHtw2;&z%D!}^i-4z0;gJ_iDh%p2leef8d@;U9u#W(Y zalV~Au4A`Nb85=-4AeXPBKSy}*qJu!yrE9mpYjtyn_{8}q321V6+%egdqy214^@^p z8Zi5-JfacdM-^^T-uYJH5^WcCiZV<)B#pypkISU8c4?d{cnkC#Cv2#L2<1pyx!XUs ziYMtK8lj7FM7<}yz)70`6ga>K4YXNa3?Nv-rhOp~`ejGDAP^*N*ad~zchLza@RSKP z#BM)mKbaTV*0Z(KQhimMNv-_R=kfgUgXlRsQC(IY9T|%QwYw|3NAYs|FrII;VtGsH zukO{j2f? z-i@+Exo3A2JCs>$z>$8G6?Xlx|+R zIiZab>&@4ZLRua z)jsat+*4n2e!Ls1CNZwEKE)14r32~A5v9w^D{dpGV^qg>JC~ngR{Q669*b_6wCMg? z$M*_MsyFG|-=e=_|BAl4Rn={-WBIDCz}ovaxJ$jsTy1K<@Fw*(d%64_{G|F-?p6J| za42AZedyQIvs<}o{!Ng*qTWQe1z&&qy?^q3Dti(uApeu_Hu>1eosOcdK9n@$5QuM`5v9`Nm3XZm8vFlh#Pf8eGUlkJU3{ZNne4}z8T44>EfTFhpTjBXq z<$xu`jB8dvGN#4>z|^Ll9}qZl*6HhiYGubHkD)r2e*Ce0)u)rq{-m1?ZS?6zx}jn6 z!CEYn$Fx6;iQ5`K8INMmlZFm%xHqMZ^OFi#U~mF3!Hd1V#%CA6q$e-=$pTb3)HpzA zW*!PG9R(Ac7gLJy5pz|KSWCn}2wMKl@?}P*H80HmryHGCGIp%Af&oSV#x9()d&v5- zeO{d_UnXF3M-WV_9++3*WB|dBNS{wFOx0XmpxOD{ zQ5oH|gBj;*tEyz-u%$)7IkUK+0TZhclL5tnL4yTJ>byBF2f-rSqED6f^@zjnNvI41 zfffub!aOnjDo4~?=cV$SRc);3%skDBh;y0i;4IsL4F6J$UJhU`Vo-yz=Im6=OwWip z8E|>=@ewdk`oZ+GTGz~(mg@arW4vc*-?ag zf+3IcjBqh|!iP|=-VZ>Tv@lKnprt*j10I!M@{w3EprRac|5p`6R^=kVi!_lR@bWmF zltv9!m5M21@B|#;BwfMUZ0q zPyVbbJ^mN}X;V}}@>po+Iww0@rb}uGS8bZZ&9)|86U?}+DYp8iU0N|H#~PI&wzM5^ zwlBD`w~h3C{VruXEsA}4IX%#pCzW*i*SOX&NKUJ6+*at)#vt}6b7rWu9bA}k(_evG zFIBS2uvV`S=JHU!RdvjXr|Rw2eiy{NOpm@LB3QS*@EE4hirHXx=yt9qhOc3u zOp{&Hu6$4~57r32+B>|W^^1HjmWCrVIV4j3yTjrIOm&kh^g)B2vD8z;qlUC;1+G~0 zD*CK9uAw${R4F$FuD*@KV7w}=1rLhw`Pg2M+X`EmPDo2LFQC#fv87D~vEab*k->KQ z*&$(Y;7bsuLYSlLIhGeSPHNc#WV5qvqn^wcu$HoJUXzl*9cw5e4Q+ctdp@vq9T z)vPb(E8$4njl;0@(crUNn}1 zE3B129W!o(lVwD9_J=)bRAEw|VF7Pj`*6XqJ+uOsw4$wHqv{t2_meWW?ZBBxt*0!} z|F%`ZU;Pkn@=DNM=&28?jaROQk(KE27dJFE=qaAk3t`yAiz;D#(%Jb!pvNL@92J)M zlai=}MXwTPo7Yr{Gpqop%?FE5;r`UUy{*`9Z7K^-gWW>h2Qw-jfMds*?BR|W1OZIi zFp0sv47qDskC1uyz+v8}f-nQ#%a`_x&w(o6zXET9kDh+-2pU3YGd3K}@sXHl3|k~} zB>$(!hYEMVEA6@83H}6O8$u8!bC^_OG8X=bNhu~&IqHwQfpD+FBKQv6nFMB%2fmBC zq?A>AbLn_mNG3ewuXpB%ZcZ@ZVRDuUB5&d194xS?nZSzJH9gW^$RhDa{AbD+~l>EX0DpJ61Zwi^5Z~ zvyF*Xj=Q1-MVQ4sXWXxGY+jkgcnHf_*u})%ASF(D-E#b=$H!uNa@-TL@Y&p}f?$Uu z4o64FOf&xTzA@2zbP)Ty+tJSi;!uAK_g%zLpZHI?sYK|@ZaVSv#NPq|j>sCZK!hDa ztomjZI6_B`RpOo!=sh^%exsA%4zWY=o~$D0crsI05x^;EA<7+L+>!S5#Y&uZT|5DNo#4gD?nT!iCBj zb%lCBda&}Iod%3?IaZXNN9+n19#Q@(ui4p$P}XXlr2S>S+WK-p5b8|cP)Mg`4rwk$RYPDLiv$JENDvJ#)5JO;w zU{?OvjY9iJK2dfN%yJASf>qB8iGIo+b!}2~O*JP?yM@U^DVXzaSA8)rWev5SF$XH;(w!Urs77=k$y0*2;yp^p(5%n9wx%XVVsUmnuFX!w(sUzcCx*SCfVK%?*)Y4S^r%Ty8>upUauhA4 z-_e2Ur@~r!`7|DU`B^-A@I}0M{>;LI2M->_mtTDq%P*eCsp{#Z+CA!_?>AIG%ovuP z$;5}dn}&PNVnXz=Lydgrh~7>0m*k1-oyy3N(zW+oZE|ZX9zA>zzx?deXl-r8!Omvv zY_7)gvnR2(^3td9P)8^?H?A$kcfRwT`1sr3j$3!`#1i*Q&CSNb^i<4nw6E#~cSW6C z^u<}vaO@smdKcRBwH>#c2&)iMar7TYSkecQr|i1rs9T6VQTd`?vyfRGhx&jlx9$to zu8@}qpqc06ey)AB>9jlM@$jNNqb;IMU_6owNXTr2^en(Y7)@KmDLwds$IJN`gw^!7 zxvQEvo!se;u$SW?Uo5Z1ix)4WrS=+u7=7pFj(8FErAH?$kjTD_BNo}|N}F|gd78U3 zh0FJta$GU+N~gX-wWs4M)6JQfo}Ke?v)t`DKRe@{f-II{=R3Q6*)>U>r~J|$`aVCE zr!lp|@C8l!ccmr#%Go(WK-D!pO30X^yr|8lzO8TV#e*j+@oZ%)w)aJs(xdKbcim7J zq<0mHb3`v?XJcni^;r2vJFa;5sGp&oA)OBPTjnY1QK8iJM^B%}^4hw~oVixv0xx;d z`KqnL4HJxcfw>BYH6zBHvr6;TFX~PD_P6M-*!$t1`s!9yxA~jg()%~KOTEclZ4~R* z+^c$oZjvy)vt1|>eq!s0sHGicW@JTRP}4~Z-VFz>P>W8@bx_eUpP{hq;hf& z4VjOPv!YnpqPX+uC3wbVsV`qYRiB@>yDjpQ`nI8C-?r0J&E2@Gs%}MJK|GpGjX_|4 zOgn!p(j%I-!o51xcy`;_J}rv{11Ke$!@`=0Tm#sxJqZH5wSrUQVOU!;P&PoKv_da~ zBT{UD=Mg^turD5})+T9eF8V|PylqOpIzR&%manZ7Z^C9gtjGAO9u0rlRe0OkQQ_Ju z?F{2^i?bfPqeKdN9#-fe5aGOkm=+%|KvEfhstf}LInDkm0dsN!MC39uI8NX&w#ATeLHDsbX&UAvMPZ9h`dOGj z?7)CZmez#okDVSm3F79$LO61B1%jc)O?tp_{%ur};IFmC?6|q$l|XnzOQpHv%>+s# z0P>;a2ljkHQSsu;)3zw6nXoZ)E~d)&QK|foYrrw9&U~aX>NLnyymWrRxWROCeBg=9 zXBsSF<|q{MiN|4+_8JVs$Y+}6E-Hxdz(@Jbz>xt4dBR`}x;PrqJM}0=lotln>a0C5 z6{FQBW_VD8=1DPbb8`zm6Ip?ZDHAPX2#7QSFIK})W;kaZVHgt~2&PDbT&?TioPyo~ zrzlb~`2%YqlkmEHiXqE#$uO7rlsM_ficw%lL+01fdxB42{1bl|eFi!pw{S4WPZ>AJ zAb#M~F9$rNw@f&qO1X5pLb?hvyS*kffaYk53P(LA-Mib7q*6+Dz}5Pi`uZeHadG(8 z^D-Ln>d_A>EsRX`QrIVL9o&4Y=NfLcNxL>f%$+-qMaYKu#6wGYm`}+!W%}8vz}ECH z`YznIDyGDSB5g3G85*l&O(RrVXQ-JEvdfQD!c`#%F!(ht{P>I3E{R@RKXz}&PA}>7 zr*7HJb~dEy(zo#zRn0XWvbBqN?hfmcj7`xekRsO0Uth>L~)5{b;-Cz5z?&>>aup9R76VTIfl*t17 zwH~+H@1&jmmHyK-V)g?}PBvnuuLKhX4@6|{FHcglzsTkE%t1#<2tH{mSm5m^{dE=5ge&N>Eb zLE{PTtYBi9_K?Xnj@e>@|LBkfTkLwf4DKppl9kChcvDaG?(X_No;}ffbaEsp#Yyo& z;Kh+l6U|BUpv@`n1ex@19Oxs?OiHtooBO+R@-%mBaX$wWf8-sLeoW@p$uM$)A^;s6 zBRSvXuB}Xa(w$vhJ))0^I*t?Lh@}B`6e+#f-Alfl?C-_?-cF2<4#xz?dzA^>5%Hev zxMA|2Fc4}WI6PFIoQRKSN7lvJu_u&)7*+a{W+$R~|L8(FJm1# zw^O#*>BRj{EW~0m4*}QYxY9}S9#Qzy6C*J*rLrVmotQ!iB;xGqn4X%7*|}K@3wjk#CPUe=)W-y(zVP-4H`#5(ggknLSqQb*VMAGE;Ut2o zjZK6HJF%^>S;bGeMi4{WP}@(B1u*N^+cT&%3&*!HIvO{wFU8#Kw923A>%eHt&o9RP zySH72*VkTp!gcQ;@0H^&FegB1Ky&P2Cp&mD;LQ#ro1fK)KK2!Vb=?SODnrhM!xZpts}D`kkC zQggF2u{b~Ldm<5%(`F+$BOOWOGxd|~$V7<8+!5~0@zLNO#WA&=+?{y5w;L~>J&uQ8 zeI6St&th}+dGuTy#bA%xhm*ZHZLLSo@vhq5M$ArYY)u{tcfZMv#3!g9s& zKo4QQ^CynyNMl0nmdbGtCnQb8O?FdVTT+=DQ5$=z{zUD?+FI;vtj5;Li`ZCx z9!I+y(H!ZGyVn-Ht0?-0;!sJ={ZORInCj4w+J5fvT7B^>KKt2EyQ*lnEmZZXfqqGs;=&vMKO zJ1VCtThtSHR(1fA?<{gg@IxJ9!2$PiaTn+6y80FAsl$qz`syMN<4VF;)NUsN;hB;dL{3res_#^QFZn5 zO!bBOIO(H8k68bovK7Sq$9zR!@2Tsov?&m{( zxIML5Vd=>uIORh7#aDK~<@aso*T1OO+`9GMUp@7!SKAHMtw&uoUxjr5e12{JX|6Ud zp|7}C^=A85!hc156RvOa_p16$VSjySsfwFVx5wWI$(z-i=qS4f)84`%0!?Nl?)kHO{;V{^jzb*ikIQ0IZO@F{yYcJ_X)j!Eg z$b=>R3J%A`b`?hOHiIVJ zn83=Y&|J%GkL8t~ib``$8qQW`CDzpRv>8YXe{iU2txxJw!6<>klOuXemww4dVaJL` znbpB~*N-|t^j=-2hL=v0)us4>2pCcHDacfZqA(ahz;v?e^IU^m2E&^h8?mvzl}wt5 zsw|{hbA_p|=pg@4yfX$#tG5&p5vMiw(n@1!EYR3qKRe>^TdIPyqO#GQOtB$++>5!w zp`3@Jm2^aCm7dF2@pTNyCq6C;SspU)fQ3O9lPU%eMx9lAFt6h<*BTrSkBu5XE8&y@ zO5c4wdtyWm;#eK%nL2%TXK}X|400Y_cxn=$>CBT385bB829UU&DQ_5Xfj3wFu`5d9 zi%wPuUBZl0PKCpHBSP8XHOva*5e;6%P)>6u_57SWZ_a8*xJCQumAs1V1$38z3-M$H z9E{PCXoVhDJ_1J=d^3GZn0oYb`k|*Rvdawtl^J?Hq@|Bb!3{t153Q7Mo1OkS;Dmu9 zeCQzVly5?_g%ot>07!o1&nux&a)#kx00B8TQyPI!!Plhgr3Y9=weh0yM{YC#jvwZ% z_29xCg^gZm1XMq~RDZQy0tM;hpT3T>i&O_0Z$ExP7oPa13vV3LJ@KIL;7z>&OSG`} z7aGy#%iko8ShcO%sz9~hR@UlOzI+^R7jEOi%r~{R&tEZ1SziqJ&3-E_+{)m`{<_>T z0cKn5^J~kZs=pdi+b_7WvYTM6FAw#l8q=E%)fv^%>s?@+hZqY`qL-oARr*S)Nd*41 zHEm@G!P~q2DFaIp$O4>UIa?jReb~Kz+x9hFB4azLV#mkn&KJszTV_7COE^?VSi`HN z5%sA+wVht^+bPqs(I?TQTU*%@AH+*~MXr#T%6dHO-_{$EVbf5gN2z#Sih5p^;{sSl3QhWz9r;@vZTGtre07dG z6a|W8y9`P1HeCw4YKB6}!K<*{s=_&Lufq9Hd#%2&xbZd5Q`{Lu;=Kye^6BXHN3vrT7_teNci@IHXtVWnZ170p8&XAM~WP%+~W{-k|JmA~H{`pas2Y zELJrDS-3Rt6><27#_G3?LkfMj8I@)|)lX`rFLc&$-lAT`*HQRKz(<(e*ShaJg0{9c zg8P1$?DIs7_$H1VWHmWo3wFetFsZ?WXYxAA$J4Xmh%Z(R*Lzx>23>R`G-FcFe4_jg zizl3!Y{cZ~uy+q3Fe7VNZOlY+-m^01-6l+=kiKI3EUaO244kAVf`P+>Bk_=VbRiR9 z@Cfj52!WWUMkvI+S@2ryX7>&T@qP%txYLS>bo5L@!as6H6MlR@kLZOaj!GIq5+wc; z{_Lns>@z9KBppXKdbgM!#t=UGPwB#G0~8sbY@qRk%c*eY1h(iAod_Bcii}T;MRStf zJ7X49P3oB%8;WLQFlLojv&}{f^a}5B9{t7rMhAP_adx<8VbCaiw&K-b;z~FPYiD~q zTDx2Fa}Wbc4+Ljt;WqoUFH#S8#WuLyBiE{UOlouw?6@OOSd!*jWB)Y~pOY^NAEH8`LcpTRI(gcf3o6$*(5M|uPs+sfM`CYM#_Ilj;1XO(MLMk)6h8ovOG zFxWy6(Fr`0)r_mD2XIOx8k5>}2N09eOzcu0NY|a6jaXiO7OShzV^v@75WK#0EoNtC zMH7Oi5yf-ByE=2CwA3lpadr@RJS9A&F%!w`rsMcMCYBkqIn5CUiC$F{w@uW4S($e7 zg>nEM@|yPB<5_TueCHeOxk6?)n(J>lDi(TZo7^XYLuQv1%BR{FCcvqio|o{C6ih)H zVWEKG$&^*JJWk9p8!y6ldh1I)#SI}q?wn)yoxy}7VQZV?u{miZJv-BAuP9HX1vF9a zNlOHyl)+uK9|*b*%bj4phmgs61O|dn-i0UA#PJf{jAJR!^u5HLuw6$ic;b#XJte(7 z!LNLTHrPbci1w5E%wpsAJ&_15s2|jWBX-Y_M#?YuQz`s63~p)@h(GlZLFcI2QWhB? zjP^nd)oJb{n`}<1UJP5P#ZFz?;9>PKGhQSxseX!46$=>{+aq{jj!5aoot0{*T1RKG zv#&Nw>5M&Pi+cqZ=B7f;soK@U=({+J>E?J$8aIM2<(FEj&5hOg`s=Ub^Iv`uzxe#i zc=-59yi^_B*xYg(@vU$Fe*A+!`EK00eJ>`O(_R#TAp6#>TXFa9?O0k`is_l@VD~6( z#%EuA5kLCzPlfZVc=`Of1!4$qSRnFZd0Bb6={A0x9bjs2)>dA`7oYtizWn?%8IR-E zjT`a7d+)@I!l4ge-`G(5sWwE6I{om{^`*Fd=cX4@u$XvPZ4-5P<>gBJtAF_~g_+Akj`t9%*gJC7TSGv3LBK+|`ojSt77(uw2o&Q6cKD1?RPt$lXcW;@8v zZraQ#rQh__MD+C_c;X0L^|cCvt1M`9DTkCd$}_@Q^xknvA1pXZC~ZOR^vd}p3&ZuL zj#IZ0dRpkKyr!tofQ2x!a4H)%(PHG$$NN@P4zq6k;PGvD{BbBw%xyh z19NiwT$EdTkwFvB3h=UN8 zBQg)w*B`2%=AKkG7SN__Ztn=59rP#hY^rCEOy4C>AH(3)-h+i<^0z0Lk@>YLzk!M**Y^;^{ySUrg#-K<_U{}#&lUr`9Y zdj9Os{x>9f_o7#fQc6?J)jctc6x3(fZpt<1STPJQo--%0A6|&&3?zWVh z^w^oolGe2#Xhl|Sb@l(6FsYzIPQhc&`hWqQ3f8Y=Fq@HOcR|i10Yr| zEx&vjUqARNHZ*|qwrkOCdI-1BMn?cGDAS2GoTnqBm(xn-uC@}b(?QB$sZGna;qR!r z!eQ{=%Ml{_Q3kw13)-X-Eb|^Wr@!DWa8e|^JsiiPSk=)Mloxvj86YC(lI%Q&kJ$_u zic1Cxy_Yd}?ONP_|NWRk3Z$2~C7LvY|u0UMJgguUk&NBa{I$4s^NtwI8D*bv%Prd#YxN}nFzQE{wgIfzp$G>*HrPIEG+^o1@bYV0 zy=;rw_G$LydxbA5OH7R1T8Bd z7!*r~XDd7=F1MR_O)J;W9&j6me+kq6z^6yW>K;Yq)7HN`W|d!KSO5PunvYW-VysM2&4Lo>y_xUm?-;0bFdhnEJz zF%1b}lKFSEX@8#duhm&3{YblamJyp^#DcU6WnJ|?CTCwBe`OipqWO>zSd zlccz}>nw32JqTNNw83`c&tp3AlV7JcUiGSQRY3y^Y~V^Iyx@Rl$FW0G4HF_V4y2uI z)%RMJFzm(`-~Lzp9hwt7zbN!+?$}j@e|b&6c28KFA+Ad$j#S<0UX}d?X%8+i5mnNf z1wQ>TG}4HX#%zo?=VM}eG5Q8aJ)y`>4i*%VF8r8K)^V+;8RXFYrp@%pVPaIB4je!d+0@!OH|0lX37o>=K!snTq+DW^fc6tD4!p!{jOHH6*?d;SIY+;3GMf zjgm&b`f~SeCa!iJ#>gN?TQ%eMjd|b6GC0^v5_sZ`BLWW&88hT0KLRf%zjBuj;|q4i zh@Mf7-x^XFj8#Z++EnTsE8zP)q189o=Sg8EhvC5)Q81Bpe%Oiu(acV@=EQ``+ePf| z?;CDtpwGMY;B^NFM@%oL7;rBS_~C=Of9>pO-@C--*iAOxh~q;h6!*MB9zJ)crMwee zF2)LLYI@SE`^h)T2(-Y1uC6XCJqO~W58sc`@rl?IU%k~ji_O+aw8$UDdyk_5Sp|NO z`N6~^lfCzD&c`S3-iq0Y5l^PB?Ht6qo|Z4oCk+v%h|gF4l7|*vC~WQrCN1|hhVyED z#ffx75XaGs?A&2;uAdz{%1Z>Ct-Tb~Qa_ncALE`jCcZUPIahoU_At?j0Fi)Q)j#rM*Kf@lCdm{#s-x3@a-fVJUI*dTsBDu z(K$TA4y{X#A2jZioyRJI@h$}6V-lY#O#e;Y%3Tcu)^ju&@g5s%Xw0cHBpmEoVn@g9 zUp(OQgH1df&VwV(0 zlR+PR1e3uWWyn#Id#Y>X!5KnHr8#3HGL$r@-jUA7a_6YKL%A{b869Q!9)jorrSp2M ztu4p$^0HudV`g?SzV*o;MMHJKJHAFW22>g|M(1v+b5W(pnh?k#$aWt_yoBqFv7qdXm$It13?aOC@eOkyTO$TF zzT%`1c2+Q#z>W*jiuhTWDtsvrXVP7DT=~ctmUN-aam*}jGiB|NT~)N#wABb*C>NMT zFXfRZag?2Rs{07MX;UbBPJ5+=doiUI<5%*EFXhU-6%*&BBN)<{l6e>wt)855&y(5+ zl}(?%qVkRa7r_qWVdhXWUb)i}9)k9capgJPr{WD#3-y&>gqwGY4Z5yScfGS%P~;VL z7x!W1EBAQeha(G_n^{|1Q~qu_P6#DD2O-*Pnv$O68S^#>89Y`l=}w+D8r(&vbane6 zx0)7eTfEC_KzS%LiNq1F?1rA38uxB6dCB@t0xI0Tezi{uoAgE@@SxA|82s!ohI%jJ z#@tlQstsik1?>a#1T0cu=i~auR=jx0v7%e?@X_N~UR{e`)j>5J3ZqwLXu|z!vpE&l zuU+?oT;>Q6(j&N2X1m=VQ+qy08zEoJC2VbN#iOTBNC_IZf>hQtG}Z^XIJK!`jrvY589xX>gAEr7e!tVsr+&uT(8O+eLM4Zm*Te$ z6s?2vUZtbz@e$>ec8gtSoU}#zH{^T3=BFC5r*cBR%_*PNg~XKl0Cu8pu^W1eg%>9w zHpl!J_nGZ-Jfg}zWUHVl9nO6m@`d{RQ}Hav`#aubKnhXU=x50DV|q%-!WlM+O6c~HrCp=`+rq+BPZrkgVl^|U!WNL7S1^|GUYA0;k)ycsE z+Rk`v6B0%t^`896CdHk6_0*nNv`SxoSA1=YRIjE7+kP>7u+&9Q=PNh)HwwaPJK_(k z#E4>ohmO?I&6nd-@feG(3l2LKdJ24jGA`hp9U9nAGG2_nVxl1>$#r5mgy=sMuZ*2H47~N47TnJur z0){Z;1~aBk3p+Di>I8D|0K=UODooX}7^1@yR?3Ni)5GcqR;@BHBYhaK!XSF!D!;jE zw(!F^dzF_ucSf6Z3JW)`$9o@s5L2^L#&dFb80Q-F?eDcTU{Ob|JhD(y`EY)g zM=QX&Adn&a<5P~Pyf6dJS<|e*B7T%B7+{zj29e~W2Q11<1eK@92t*Yh(ZfIhyrxsp z?ibTB+MI|9wsC9l$cm}qLm{JaLr4P8Q?07MLU3`Bu5LKDlFoFnZY?*-F>`|EbvnWf*fhVfCD)1 zk`oTX1ry=IRP>4IB0O8j55>SM3PlS7G?x8POi3S(Dw&^|x8Q4WZc%;*?FI(CTa_>6 z(g~OvUI}D#sl!0y6u&mFs}uW$P!t&85|$gyBRlL`-f0N1bGm)eX*U(&b0VTqP>$_d;K zu1X2YxH?9|7`oyYhNLzXw(gfj=&N}F-5CKVL_t*C@}nm$-7nZuFQ+-G;uC%mMU&hK zy&!YqB(x#HV;7kS7lUzk#mim@Q*}%JGiJpO9@1JrjMkU%I__X3 zzBU5scB`t&kGLh$-$4M(Uw{cKUxG`@6Op5+Udw<||Kk7he@)HrKvlt4ZDZPTE#FK% z(l5;@^skyz^SXaxng7nW9agmipMJ^vq^fS#;qJ1Qu6IT(;Ww8CJ(H-+b&=?Hw0zP)3=Y zmVK9-zuoY_0&)eHTZy!HdKdfhwFB?`SYxlg{iCU?Tcbyaa-=yu&ElPOrxH1flpm@pt`~XE8QB6xXjU#77@}7&9}o zf??MYJHf{MJv$elbS{2L;lYofyn{si(aD)87cT=pPPyfnIPQ?yZS9G-2@43u$46pn zlB3av#J_XYAS=ZYu$*{;Yjl`N;$FAi@R00u7vrQbFY?0t9qwD%^TgZybTgLbCS$yj z_s;Zt(UEA7U#Fq?JSON@R#%mNeK9;d7DwVY;R{Ju?{sL4c%lxPEf`a}xjmHGJKlr| zJ=VOA_V?qUwe9dZYH&_8utV$@TM9qRX?$kBJ%vGe*Nn>7@QB9)&?i>b@Ca!4G`2vfJu*akv$KQa z=r|TFSGkW4k4ldKQ#gh9L}9&LS&g;zZPyuclrhew;ty`}n>0bO3)08a2|wkS-7l0a z?$@D=_6;Ls8&lciX_)Wd-)B|)j`Kn&Jr1#8Lv(Tkrt6K|@~D2*Spq8K2LuRt)S(he zv?4HK)jjDz`C%M1uQAI<@85}cZp_9&59KP42i@EeevPkYrbgr4+e@J&h|R5y_<#PZ z|5tqW*=O(3p3C4Jl37;q$Yf{Y2y42g)Oj14RbS=5>t;zWoP(9PfYht(cu# zGH!O%mOx>I<~&OtMa1qqjV*G zm=x|GAb&2r(~F&20|UdVqr=V{cJR#4P3I08jgOe5-%@?$s7!=z+$qLbkmLCHlD-IP zXxlw5QrePkzSD{^6yr0|gFulx$9wzAcuRGf2+?<(NsmAaA-|7dqb*e2nCK;syklfA z@0y~1JKmxTf7!OE42f=pJ6=pl*;YG*JL6?9WMpisc7vljIc5*R7vsxX27m=Gb>0gs zWyg3O;m?3@6)s~}j-4GD$+lEP$e)wi={TZ-%8`q+ zv(rAxlrizMm&>uSu_Ju!3eMv}3CpLkD164u2)?|NRAq^|9|U#82chD~XbLv-t|Zb- z$M)=Lt%0REl18x zjtwbVYKwMM@8yqlTVLOZFTZ*aKm5s0V|jHwCZ=X$Zs}HxjL*ce+E)Y~eeOG1*qd`G z{i=twbqHs+ssvQH*q4HaSTL{YCgv=Sx-;?N1o;-4Xu`B8G&%cOIfBLD)dtZF- zPydPgz#+w-BOU4Mrq!n(E2!1Ab?@q0TAYubz9Dh)Ju%&!P@4>YpuRxmWVdw?+bwo_ zsSi6mi`A`GJYU&}HRU5{JWuPWKT{}3TLb9nTrtD8Hqq5R|6R*EO}bC~`{g^<3g z&NGn*q)E<4(MM1>q>&jr+Q~_^c?%13u^{@{@iwi#IPdCI+n~%GVzEofN9qg$bIMin zEb7N)&%7l^$FhqI!94f}g&QI5&Bd9R7vI!SI&)VZyCrGY_tg%w(~P#3vPC_FHzF=( z*r}h=KY08szW(~L@E>>={3jpXk9Y3fGGDN|zU6#qiFac6UntLddIuFopZWr|Q%Y|* zN6I7j#%`>+cExy$3lmm`be7CL}M?785`U4FYfuxG<3V9r(>UrdB>`**k8e+ zZ@0ett0&F*R5w(&zRvqr1wCygH`ThLz3QKb{H*3~W%r_|yu2DlRc{x3y#@X)_NZ@i zL;WiEZUy9T1pmf({QFT?@~5a2eEk>yC37XpE|@9+sRQa5Z6{SMaZhr|q%>isV@p6O z>6y4N5-HrQlNBH}ZH$s{+7^4gTrfJgyIutWFZ8nOwl43i!01XLD`2MFnuJTcROnH5 zu|v}1APRiOF?~3Q1atvK*RjJ^zpilXPa4vcZ$fn`TL{)T+A;UL($JmO1zlSacUH%h z;H?bX)+8-ewcV`Jt-97YKudXLcx`}cAddP}WU_06=z*pyd01djIjJGN{)wYU1MBfv zym2jV+*IeUK@1AtI9mzOlM3Ka`8o#&cKVvBQWwfjA3A)}ivclPrp+9}bh7$DdOEWs zm`Hu;;86&^vXj$5M4cE6CY>dNHdeT@Mf>IR<#_n$QLL@572%1=w{mo(sLU>BL`v?6 zJ}3wL9FdZqR@SEp@RBqJv#OxV*W4P+0E_sxA$~mt-^<6HLNdVM@}#5`DTf=4RvR}o z>#+cf^pqPNle%G(#S3Pe`1$TGa4Qk)U9^Iaa_k0Nowz$Hb?6Acz_W1kX1w#kyWXzP z#k~g_pr5M4gt6ur1rH#_T(T34JJ?_p$U+Xu z=iPbwGr%wdEV^^Wnqov6GiYPbKi!Px{JhHHjhLUGF@ExZ0RfX1oJCKWVSwy1qH^Tb zdIYF+s&{q4jMY_i2w+KLmjm)op#7vrY4{mXFqo&Tvto|&?6R%+7?;8!ZHeEY2Jaln z2oCHi!!R*0=^kuIj~~KQN|m;PHVVO4uC8H9#fc<*JkE0%tPApxphWv6m$*;G&FeSg z`n8*4#>6DLjN?at!4ZaSXm^SwsEh;~41}Mr49+g30Xn@Cg&nJ3;EX}9^Wq1EpQ=v? zy@{Xzs|%Pj*i2{ajn^<$p-URvuG-jvPd7f&S5HY?G0WX?PIXoIQPR_x3Z9}2BTsx> zw`xQy6vpbIgbfZG3mhL=TXpNJ%2-z1#jorTGT7*suy)g2{P-((cv+0bU97Fmgi6v1 zZX9bY(>32U?3xM{x_UE84AR&NEi|_wrEte6YvZxL9fH3U$?kNun>3w#Ezl)jlA1yl z9*Rm^Yf@LzD}85sX~l;C^{?$r0k6OghhW9`8~kd2PRPRNL`-;I<&#SGE?@14>09W} zawBWG+tn~>27%FvFa*8;yq2WkGdTZRfxyltbm`zh?(p{D}B5MamacPaS#&;A$x`wX^ZK517~jR)Uq z@2}%k^tSBMOQCPWclphJTB-})?(Rd1x!6;8jK^gw`(eA)FFx#E&2RV;C+Q*ALNDy_ zQwzF2-S+-gyf*Sm{tG+uIHO)*pxdzN7ghD<;h4-Vu+=WVG8eaQJAXfU z?*Rt?__p&6c+xCsMR~%n=s|*;OP;OxDs_pQEfSwyy1vBu3f)&!;w)M{iHkaF;~Vg$ zODdcB>uXzmlZAMlmRD8!?ZBmyJ_)vcwozG*?ABJY6VDZW!!bC9aBDt>Mkd7{=fW`f z5O_K!E~loZVze>tw$XwL_$zfN@Fu<76CpT`bY}6;=@CMVW3e9MZ%9`?2!s|F7h+*{ z#`jd*zB%t5DjX}wQAzCf8X6fl&*O=wp@HD|I__;kuwxvfDQtlMf)6`BhHK49!_kq! zm>BMlK{d`CpR~TdBU&##5$ef(@`AdgHj9Nx=6{s}OrS9-zr4H}J6kPJFf}I{;k&`) zmt%lNhPcn7-#eO^SmR!+7tf!2;*I+|IQoa3Oic1Jp*lF&C;n|emR~#Epp z-ir~X;UWAT@(mRk;)~$uO#aW#SbTL5M|)dwwzuouJ=YfIV{l|7#wMquS3Kgu(V50A z8UvBmG)gwnO?H0T=|Rk;&yKfs+}11^hhrlf;^X5!bv1t#|u4|Xju0orOE zS?GcJvIqWnAjXwX2)g=u*&(KU8W{?9jKD9mdyKk0s`50bvbwRk8!uNjaz_`t3`INX zPkCT>3cKydcg77YGNY}bt)O}%RAHwR-dtvq9whL5Wg?E{KG!Vdf)Xt}r`El*wlEkscK&*1w-3qqBT-n$+D@H-#G%w+Bu zVnULMQ^r5TgS|1=RJk1#ekI$pr%&Ur{`#-t=B?Xt@7)h$?+8J1=Ku4jkK?PazKBN; zzK$nP9>-2=TPYtgG}?@R@DINm|H*&)KaBB-8R6ErOZ3r}kr8!~q}vn`$#{z~9OLMf z<>h$({6%bSZ(2y$-*@R894ZTy0@s{GtF^L?*#w4@zLxHd} ziDS>^W;Ax2YO0*{tNe3soW}WzxA7pDQd*-Z+u+0OqYXtVdBQPcOnNhhWT$EhIfq?e zd)3x3IqnH!h3WoQKB0lK@_b6?z>yAhgE#9?e zz4|jf{8D&ES=HE-a;LZhW888}-kh?{cr+JV5O~<+q9?8U#iaRxbAa}0p*YJ zyyGm~wEZkv@V$^KFQh4Hh9XU9o7f%1v4>-g5%mEaAqPzmMeMojXh7}ZaEz<17#~sl zF84jvf#nx36y90PPECrY1q*HvG;&{I>+n=<0-;=5fHtIhHl)6fd%UPaoxy<6UXPus_p7n_wXZZz$^KAdX<&d3J+#xwP zGwDSVvdr?MxNPq3#mf4Y!{0xkFW@NQA?FL_j-7tAX9$iEhfiyvgKc=!XsPdfxRC;9k?1O_tAL*Nm{Lf-wcr?y?hT`eV^?13u?YI(; zg_-gA_J?=l_O0v2v8T8ms+=FIep%=xY^34x%9;h6kj>(dql2B;T3a>0M;}EyVjhq@ zP#)4o)VAgCBKWFqRk@uhs@v@<4zRqzj<23H=kqE|Roz0V4t!BElUu313dfWD^&8xZ z9!2{6W`ZwNhu&`WCcCP>$qn_Z+`AQ!zY+Xfe-X{3!``(}a>GvVp&JeG>!JI$r z^b|Yt&2Ht<%bk0g6V#ZBSv5WF>Pu!UY+GOwA_o~2&bX}ruuHn(--%Z2$~T{4rwY>Lb~tIw@Vepb6Nge*i#uPmR;gi&l!e=(MhW#6;3>JS$SB3y( znFn5-hn>=nw9Rgoa$!ocKKUu(7aE`kd@!28VaAX10Z&ry(2BbSSBeV*ZjJ)sm;*XQ zghRPvE*Wj7z08#vCvV9&9}OeC3{t_%z#uR2%^hEmWm+oT*vSva1u`JXG6Fs(wIGfZ zP#j<$5qzoq%`D8v!h9aNLq_F5fpdughZqE~;Ru=mCHa*?tsJ01i?Ee) z3hm&6VWK>tU@~Fcm>8l=W+$Hbebfuwu84sC94siGgbNs#59z#W4;uk_lFen1IAWJ| zgEWMeN{{ax5Ij%`3kHH>qG&WG$D3Xe>2{(hXdr#_4|csBNA&3*JvwX%%;_v`3XM!9 zz7nF8mFi->tbwQ&iO)91;o^yX+9X)}#e<97Xg>@i|FTAB>uxAJm#=MX%x_xd*V^jd z`6hsSfz*SUuquoVrGN92FgD}g;3W@;TTPGr7`m;ho&4E9K9N?n(<4>7@dLAP3#O9V z&Pl=oQlEmh_$kU^6jS??kXZ(#WN$hh4?**>wSF=?I>5=2ul*N75-wl<+D+8qP?Td( z6QU@`y?9Q4rEa2tRiMS$LD{9e3g)&f(sbg4eMzyB4ylSB7=`DfH!)k0W`IK* z0GNB?hd=q<-SPGNfAZh|e!CAWs_LDFe7oKCd6T|vCuMkkuex=?quTCWuqgCxH-9k~ zef<_c*4g})FMWie(wzNe_1pPY_xeq(a-BX$e#qA=u-$kP*sAK2pQF@N_YR!D)}}eX z)r}HU%=CrD4|LdGg(vayO*g*XVenA2rL$eNx87f=($D%=-K@tkzb>27P#0_135R{^ z+wQm(5b8zZ%x}8aGM>tM{`z8TIO$yPe;w69^_ohI(87<}tFJ4oL$VtRUV%wx?t{un z`GKs9;-y#!2A{-amnVJImYIi!_h#|faZU>PXgNJl?Unu`V=>y8h%qj;pPGts@&1$r zCXqZzEWU#~hK9xGSy-lUrkYbuzk@w?FtMtfz$(~ik*1XG+gfUtvIC3`ztv9bCxF3*l)VRqK5|CvziSNzT|`(kI0 zU0&=S>5uWzk(d_ki?b84Fg+ek#gQF!Odhi%;_&1=cJ_~AeS0s~w)SFqZ95)4eIAeX zumFww#hMdMPw25T$^7c&x$lTMXzi$&7f#SItyBn*qv-UDh z_qL+<^dN@&&ONbr`x+C@4No9ueNmpP4ECwq4)^ydUq=jgYjIj}?vK{S%Xs|N=U$0^ zZE3-RD1-?6J__;36Un3v6Wmkd!(J`#zD{|};=R1%Emz5tuh7iyp}qaR;Jz*Lim?pk znxokeR#7$(^zH4nJcexP%h-jZE;-_l$w*fEv)h0&O`b63WP+5VrN+vUiHwVzlgb0Z zGigs+vr8&>&v5i%zr#9X0#o%2q4JQ*-J}I8dDJ5HiX9QTLyjZjk{?I-^7Vs<%J;RH zUsw_yN-Nbrj=^e-DgAEVjyrem#r119;^wWpdhX=WeTRo}@811rPE9NBxoeGGHq>1v znGyJMyq}K&R5QZRjibNNbL=ViJ8y4o#V>yL;Ydl4n$S}Ee=(`$&A+csg<*X^?fVhG1hlqdQ!@1e9}@|*UW za*{%+>|-d49!Cl<qNEvs*)DnTJKq2oovG)D;U!l{p^YGs!Q!q$PMq%CUsdfuNWjcF@M6RCW@vOSfNb zxrI2&KLk1KPGvVwlY6w(=5Vwe$8{nYottgOydLh{T9`|_`T1!JuCg6byoj69$h*D< zXxAt=$@fAdLR5C|UaFm?u6XWCNM*OI(wp)&s4_h`78iYL zr~60Za!76B#9R!FPRH@(KHE=}*;muB+0~XP?CLCr{(?O~R|3&=mPkyEjd?c=^J(!tajN57--v8i( z_`^T={rICl_`TqY2+IG~=0*%FU9T<7so$P(|HR_mGxcq|`^R3;K-nMSs7B@E=_!k! zMX!?6HKlLB!q8#mGshIO(1pbg91}aCyk^H8>Rjc9`c1x#kB=&!r=7>sQ_M3BTkwd` zmb$?_&hUV6U#KrVL+G_1E34~1a`Nf37x8j=Rc-Yi#n5q{no|3#et$xJ1ACUDE+b9Fn+S9tdo9} zO?WPjF&q~i)01P~*~PB&CB<_|Wtsk+JJM!U?#D*h1<6TPEZ#p+oKq;uahT`F`>~^Z z*%dE>J4N?UZR+~wwvR1jvCZV3z+u=u!CZcJEeivzN;o-QEuW&2Fe)<=(A;{Egs$ z1K8hIy(uj2`0D%9@BK&Lmn#ryt8eN`Cfb}6dvu72C}9j?v$HGhS?+8lv#ofgHuc56 z?FVaBhXk;V-!4<>-iE77sjU(+t5P+~F%43Q%ge9Z5d45C;n+IuD8q>kE5>FY;WY|bbcz5Su*jWH?aZH#tL zo5Ufz8jKO3&u{w4WNtgvw>$w>@uCAJ-K7c+EE1ypiWx=hQ^&gwv1OtRVNe(*O-#Xv zm_1fOal`t3fSY3V@t)1P%a4Y;IEfrrUA_YheGS{+TSQJKf)esLS zQn4=zMw0ZpVv8ZsIL^@d8!Lho4(5MMnhb=J>6_s>M#2rP*r!W*n;_f@IkJX1ta$)Z ze8C)g@|J+?6(&;5p_mSocYy*a1TauA#jIw6DI~8B5BA(ik_SHf{OCYwUsjh9hV4ZM zNg$$NI#{t;SGV=CVpnk93B{wlXSbM%mO?1x)h?pR=_s;<(q)?6Ufff_F^BVui(=3l z#!opVb}m1njk16c4F=eZiQ+-I!ybGv7{rhX} zcF;H`#&}8tTLvg7mrxwQ$*-g>dj7)5$7bk5Z-@354C%>bMP}MB!fg8ym}yNYoAYJp zwx7hB@7hLID3oDAjNbSXw`~fnNU+&@;Q88nwE-}{ZdbvRPWD*c69zikMkyiB(Db%N zc}pb#8vR6B+bo4v-kcZGRGn}T1xKZV>M@Z zwGZhmgB_3Kt`ysvyw=wGwPu6*?>FxCC-@NIkgW&U)m6^4{|Uu4Kvz9^+V zdK+bL9N^8bbF{kKD$V)O-=qV=5&ydE?GGK_qUW3KNQEu-s6uzQzr-a)-zI;ygGQ-N zIOVIKQCrn8)4iay9erEcr+Yp)@y+xg-ib6FYt#bC;@cxEH6|mSRNL zZd<=Wy@t1~(y#FpU8nBpTeLM+tdd6H!Rl>xGx`1{wS8U`14V*|=RshFBDH)35WF-( zEAe>sPF>19JU=V@eI%Ut3wB-2EzHO5TX)3Mh@WB7YiKBDrkZhfydPWZ>*n*wQWiT6 zBIJ=CUY-d`j>BTN+29bnx0rNIzL4EjKH>;Po@Q*^j`YCCiT^?n1P+8axG~8jE>7*0 z;KfIBcM8WhAHnr z9G@7ChQ_Dth(I{YnC0kj-$xd5U(Sxkh3w$iYwdZ=QcrPU3_=>@A~nVY)FI06pm!7y zCc7;rC&qnW6?y1!k-}m;JlYuZ0z4lHsB(mWhH;4njrwwzR0@oZC375I66F1 z8VyFX$?={8rh`*W2%pJWgvpE#5Yqhg(@*2y{Ka1=uGeCEdRFE7&^rkb;!@wZ+lw+V zGq(`8Zr_bNckX5#((nGgcT}$teC08M9Bat&VeGbH*AhZb1lG_*xrARDR=Jr{I2>t8 z{bcO7wYla=@b^Fb(1I`8Yj&(4`1M%c4$*-SkFtNpxKecsUJZd4PaRXT za1#Z62#df&8lz~2>4H*N#nEUSjY%3GI*fLor6LSYXkwC|CZ2JccS#gH?6C6jiU_}$ zgqJ%R<@pQgiJt{zltY)nJPv!X)IjWAb;>mZ7)42nV zI)HGAcA1@62(QL19GFrWZF(UqWtT9R#{nm1{Bv|H!W{C2ug9#6OV!fSZq;#W&JA$? zooJPR9~G*0y`k{AYnpTz>c3Q*Iu?ubGr`W=QRo-^)U;@soKTq`iwV`8Y1Q+&nW>na zK}e=}_FwoOqbZKhRa-dT7?S@nrPGPps4WY0&s9DU5^x;fIBmV^mHrk$(C!j9gp(}V zh~7ch5svz#|6ykq@fuXR`WRK^A^jBBU$B#MZR;R5_fF&JqCYMN)jke1;`nkfj?Otv z2f-L=q_kF9r2RyI(buE=JVD?~`+pH*ibrF(HyX6*N{8W|vlx{9fG{A~;K$}@uNrTuUbk+gsCh9?sGXD zA6FZv{5(3ljDwR4-~Gpe0@`2Na*o0EQI3s?7*Ks?Hi7cY;uCgj(?`=Mvv@`o*kzDA z^|ZJ08vS2|I-u8cxW1sW$Iea`ePr7N z4IF#hRGM>q=iJ;(Osg+v0l^sji_(&MiJ*?tk1XsLeFLf+EY9G5PRhXKNPjfde~gdn ztA4GixU#5&U44%p<_=xzKkeAw-fpa~iuX|aFs8nMxlSL2O209zayB`od|YrlPnrTV zJ2e(J7pLRK(rip|lrj0?qeP_Co^a&s^2&NVeEcjPJ%8b2ky*@feM$YLXklT@j(7{^ zP?asoQnvY3=B5}ItIl^lDC^6&+fTwU8m=%M`>NigfAx#9Z<}BJ7PmrMRd3TV!|e^W|t1JzxB%x!_KZNh*3ZC{>VwkJK8HDqQd+3~6VJ;!b2T%6e54 zMLFCWj&UTNR&6s-Qq`fIDaC(r@WgD1SUTg@r7DvACmt}g{^|g{8{R)Pj4-M*>WG(aT=%_CL*?>o=J2ZS{a9X41g*iW%VK_-+aAVbWL)GsaRISuC zecz~Ru!LiH2u^qg#}2A^Hv_64w)~tAR%xQM2a#Pp$01uK9>)=+;45)*Hn@-1BVpwU z9}GZP^)f03d2VSwZr-}(-CrCTxV^n@MveG$PZjqLU?zT)Yj!G;caX#Od>>80S?^*n zS$W6ghL6$FfB+_@z4}=6oQpB#-Y^$MDcs0Hn5rJpJt5|}sX^G>wWYXri#z5<+<_4` zD@mES;d0JA=1}!Qc-(Od`LW6ss~m|qLM#|5^b9^O80e8g(2cczE*ip{gQDIPq{-cP zq4kLSB>tj{yTAmN=_iFB??@C*kYMk$5u<{@jj~1f)B!xgm}Sm6z|=t-TGcrZ)D&(O zOD21iSH>a#=fW%67U!ytFfYt{bdu7dZ#z;lr>uw7{9NEMfzpj!Iy6J-ARx1Wd&|%eie3PMeX&E;!Mht<1IfJ$1zN1zG#B_bjNPgu&PCs`l9IuA z)586m^bRgvtw?u!t9}heyH`qG!ACpDq_05?gP+8gmbS2e%-!v9yHBpF!dkCXF%81q zw#!e&OUg09j6Dkn_yLmOdKov4;4MZp5K5ty8&z4(**T^@D#KmMQp z?-Ui$O@7S}xg6Vr?fozMN|(PjD~K8f`Dyp!zbN-Z1y6bTTX7Z> z!P;MjZS4M<9`b>3oFBk+#nooMsX90+jYeGDcz5W#>L2=5Dy5}#W*FpE!d6xNqMTQi zCfB!a_lj4_Fjp0B#Yf^PajL3298@ifsk(4WW!uy3p0zr|xN4u_;0hLax?%BMV==~# z@Zm=Ea3R0=m!6)17#I{^Hau($98YG!mv}DHhe=|1tK5Y!D80<$h1hw)#OdtptoV&_ z;ZZw$aS{v7p}4m=9(`vA;>#Mbe|#BxrCwf>R)NHaATt6ICo|;s`>79ZU{0xyM8~llhxF ztyo*%h=zEhv$L~UU0sct=0sdun9ZGQq!T=##wJf6KZ>W19tTGt-ne-?)^_*f%O}r# z@6wUtqSO%W@OMnMv#MG&i>KwzA}02!3j^#t8$$py;vQgN&+J0mKVT=*smiP96hF=d{OnjdJmO;ho!Hsqj;{*~ z`q+s_91%()5FGTRawxnJPcAdD$t3jir%yB{*mAxhV0!xGaV#${M{94-abiM!$dl^h zieKLA#f0sF`0>3~%aeust=%{f{LIvJ{Ez;>?EUAj=392(iLE+0=Ty0F)y=8g1fGzn|~g`+1&os_OQ=B-NuAUeELU?X>pVdH>elYlnaT-;Zy8^IP6^axDIX zxWGyus;b)wQ&|={tXRieQZ~JADQds}`<2(UQ+9@E zJgEF)JkQ-YOlC8g?-M)}uE$?$%RWM`F9n-pqXWw4F4gH%=Oy<9vWt{symt4QL{?ob zVWA?#q3oELr+?%AHg?Rwqh^_NJf+5tsvj%@Kp2I@| zPhY7Z{Vh3=A1@wIpJV}}%EOcViYxsUf9`WbkU+XU=0KRDvSWt~i%f^vSv#z9S2z?+ zg7Odng50UY+)cQ-zUF=#e%QOWgx}wnI}^DF5Mes$MA*wQZnR~_%!Eb!e3Ym1D|h>q zV;-4LQM@u-y-pNY@}megJ+@U`I1#3&yVnZ{EC5zMBOGPtX`lL*9#8yVh>-y%{SglJ zxQ=m*EJyFEa#+BC(344ggfUE1%+5ZDKmF4`iuw747#$snThBfh&p!LS1x^d9*Bcu< zu9J#b>}_vYm~@?czNe?$H&a==MVI3R+1>erAH5s14;Nx`@?zY)aXoHczpQ*>@hQ7b z^QcAAzpeH_+u%MX`oUF&v!s57yDGWM9>G}d`e8TOf$I);at-!!WS-KXaM_)SecnmP z!UvU!zIokk`kpF(yHroOlj^h2KZ}n(yBk{yvtQq!i!;-4d1fZYhPX$My3n5SQh9h# zAoZAf#MK{r+v;B*y1!-@*nskOWm)~j*0y(?F=T5~e>OIKDcd_IA*o$_`uXkn;hR5- zt5>hYcYgk7l}8t1e)ewkDBoGcK%IJc|89Kp;RmYoNAXMF{chZP>E+noJC28otL|3@ zl%AoUcJInXAb`t)tN z)5mP@Zo9lD$H!xQY|H{%svSpy(!P!k_hWwUk@~D{Y8|b>3r-dm*QBnh?>&hTwH1!n zeD=nrxH>Hws)LjzJEIrZIP#FZJMiw{arLPzKA`?n@5Yq>2*lV`MtwoZ_h4b&ca?E; zBYiymH~mPST%@u^*s69m+}G(l7~4+NS0HRxJ%T65dqKNZ=i7bkrK*6B7yRJk&*H~= zcGTvkC#Pa+YSNns28T!VJ?d0Biz(7GHaws{ppWLFHpvmb*=JK7`uhh{K&QU!h=on+ zXSwr?MM?X|Dw{pk<(&hi=S2JieT}{+OKV;*^Kgkia^LA5R>V6_RX0|by#pA4m!$qQ z=Cbr_6@1yIx?xvU3cTnOr-@r}fQHJ)tiWS#RmCTI{hzKlfnV`He#+e=3--fa);`1zk)yTU-qlT3Jil6Eg zIxWcf&otKfJLr5>f=Q^*Qk-$JRnZuPe6f`mhD(oBR%ji; zJhH+`y*~^kgF`-4UX>-4kKluQ_ry3o(!d!3M+yv_MUBV_NDSrTRS_+YDA@DhiB8g! z2-xebVTQ#C4PYDQ(wV1;sF z>opf`vm%&_&si~ad~oErF+j-j&N}MVj!Z;|E`lGYOUxg6$V88sZ#`aJr;j^~`2O~u z+=y#NnQTT#)UG&=O;5(fD_8VfjWG@85zd(rN3y4f36Z?GI?v2zumx?}39Aqh+%YI& z%Q!{AprzI`^2A3UDqQRk%))rVh>{o3A#FZJMRtTs{bSO_p5*3%j1187$6X1ib^Hf{UT{J;c$~t40u?l<-SGx-RZdPc@3YmBCtwA!0)#Yt$5Gm$CeMVge^(zHE^ z3o4bz|CV$q9nf)5cFVMzHfHP{0`(g`;n`=>mYUGi89*R|z1j(%l&+(v97pY#`AjlT(^G)x(1bk6H^1gq#;^wtoD;w;k6TLC?@y@DV_ zm$5x${^R6)#7+8|YQoM~2&|+{hKEJLG4aeNK0Owwk#@ONek{EcuI$q(!3h@**3R>! zl)eN7*WYvu`s3nw;7^9!vCjiO2pKzDK-d{TJQKy}Sedry$WML?GN=D><_zA&fxOLt@s0~ zzN$&9#lD6wJ_tGu_m;FgiH7z5SG=ZOg|t^``5RW;TL5!?^h!Iw5;qI?Y&`0>tlD`O zzVw+lH7}$$NpPzFij(&CE!EZf3|@_A#kEVZtGF$y@`*5M2hDOyw+gLh$FG)MHtrVp z7QdxjTH!2Ra5Ih-9t-yjjkEE}c1v2*T;V*83a$2NFSKzyb5FGQ3`Ec1NDK^5#L)1V zc#obqQbVR(nABvq2fK^BN*Z1bK8;)u5!8Alpm!zo_67H??C z6VSwKu!jjD?(Y>}7~;Lu2_GNs#Ho0_lfymltYSCYf%1U0U zrm+Rb5FW?KU|+=1eth!zr?JI2LcHhP!n`MlJKMX&OWlgAH=c>T)6RIbx)lq{>#?<^ z@KuJe5sY2D6GQQ)Z)6f5djy9p1|u;{NHLK;IW}V97ZadNTJCPGS%2%s4NrK|12bv3 zDSs#81G(R1b#22tXb`~l_p-~0Nwhv6J+-!@vCjHVEU$0Jw$inyvCjVPmM0=P+KAQO zUic+`7=a=8t}zKt9400?6@c;>r)_-kWXi1YswV@(Mm$3}{ZG zi_W8m_v6v*{TS8Q@A}ot77DT01il-A9r>IK*^Wy2?xqlIW7Cu3xXmrjE38A6Sw{>G z4aTKQmt$gVJo;Fvestm;RudEBF>~o+bSur=dBuhQ`%2U5%4)1FEyd-_)A8c-&x#j5 zj;-}Ik3o7=?tMcev3GnSHusKW=ipf3X{;!f;~H01H&xaMcG=COD(!C?-&XPKsy`g% zhH!<+Y3^p?$U~0M<4(ANzOLYoG9QB`{yPN>2viUna~#-iY;7P++400EV;%$!Om;4= ztf`8$$H>S?jEynL+N-vH5?h-)7K#yfCLwQLo{Z~PCSqi`PvyTIvvVt+Xuff2QhCR2 zxAyqmfAPEVpZvpr=r;Ht{0INjc<#m5Vp;WbZEM^2#3A@Xkn!-5+TAk3$cU+_iI^H6 zQkfrUd@vH%uHT5A-6M^c*JD-nh@%b}KQkU-oJjxA#6HJ9vK#G4V|eVi-;1Ndrl&`J zwAT3em<1E$2Lh+1r47fMU1&Q@(u){lrX!ExHNNxsDZCKUJBzw|Jb~;Tp#8n{F7mtM zosBGFWsFbx@N%9jPZ2O9faKUogt07|T~>Xdzhk^bTVhh3ek_knWk*&Dzq~u6%p*`Q zIr{QQcyw>{cchUp8Pg%mL(f=|@Nr`-i;&pD`O;r9XTc&y7I@Mh&=-)8#D|9-pYMzp z=gRDpPb_H7aX6g@3#LvqHY1I+3D_!t_|l#cgt5SYI}y3>&O$4tfwUtCVWBAB4#KC8 zhAefJJCHaokVOgzcGeIstDcfK%;R(jhdB&{0-LIf+o}h-7&X(+TnkMEp#%bWkIj`{ zB~RZ0eUV6W2S*rYpN&wBqd__Tl>RjZUW$jx%6DGLkH^I#if}ORb;|K90%jHrFa}|P zss$ZutKRuGeesgw+ZAuW`+nSiIPd&gU0#XV*?Y0Mwj9sixDwy^+Uu%sr?Ent-BTZ= zbg*OehUz-~+N!=q`-kip>{tDrw7{PoPD-BZDME#Z^GmU?ugjuLzZD;S_+tyfUwHNF z-bFk#!Y;gi`R|HT`P<)BTUNjG;L*c)@BR1V-o4w=FSqMgF305PSWHchE8p8=VQJO* zI60>8xXK5CC2e4CelDhzXYBG~S1R)~%gf90um9+ezjKr@B3~l7HVwo?5O^9S_s9_ zha<|59_D74V`4r~^^SQd7Fr+(zjEbj4312s08HOX>OX=g?n;~)W&b-yWGb@svW7FvP1Fnk3Wsy`~5$R`;Qjlo8SI+{NgYCLQGCg zsx2iCLA!##*xT85y_r_OjZm38)DXTQEZbMyXm9NF;=a;$^)TEYPn=kg&9~ckp=}*_ z!3X^W#~~hxCzxGai@S5{`W|hnAK39xie0BFccgL(!(FYw^OQ9F0`yDN|7w+UlBr@v zd;TK97f|Wd@xYfAd{zHIlcr6)47OMJHU6z}ukotTO0PlTH%Y_fS=_4B*4d4@pnEi|FYp}`BU!r`sLrILS(G5t`(sI2C4u! zxSH_;j|M+00e_&1(v#;;ukA`UmHK&nma8;|I+a-wUx;-eVTtbhrk znvJ1Mx88K}<6a!C7+;Urhk{dF&=V&z6{JStWkac9J8$d+K1!woy^Z{wA=%hHsb+jt zZX+ckR^S@sp_=*GJAhvl>x+95vz~uTgdFE24-I2G?u705+mJR^i`Q!HV&MllzY-zK z5toDpZLF(5sie=|1TZN>L&GsVI-1NRX~YfOf}erH_`yY|9y`ot2HnGhD?N-cLN9&b zQoseX00R!Q$PtH3`H{zo&kh@osNi9R3XB`8EI9vnb#+8d4(P=T0GbEK$|I97BB-f85%6EDs%s1uSifgDUS9k9#7Q0gl>{1bnSWOE}u(985emjTPZKHf0;2#$7@*X+pi zQH3!6qD{Tv0|~S4@)f|0C7jrv)m==SP{%mh(7ORk89Fg;FF81oH9?obL?)FTW5XI~ zF(974c+o53*gBu(K)q5r5rQdv2A0H!L=so$DKU{fX56#QArNB{@q+7fuLj>nls^VI z(03jw0tnd%tC>Ep>%@+zZ#&SmdYxMh_fxZt4{;PvQ0mu_OJ5t52;hvg8 zw&a0S$E&#cXKe$F&x0S^6fk~;G`Rj{=rYzglV>uw#JNJ!1~VH_n(fk}=7W-SQ>}f3 zogbqO1`4!M($^UjnVbjEwh3)w*tfI|d&~ulVmH5PNOow}C;`qO=ie5YGidR6KF$S< zU*aZwl#GAcyKbRRtE?}^0_NJ~Ea*-%&S`E2gqpg<%|6QAuW%D1 zT`O+G2o$TD4^~s_cZ06<4&E-9OPmXS=8fzrXInJid<$xj6&;qcIK{ff{c*Js zW-j26l2%?ENWfUgTGS6&OyU7zHNFe4n;Lc zTj?bB7lXsAXpaZpgr7`G@Dq@}z&V3{9HD+=o({@4H9qPo!U-lycXu~pZ)+`fHkM;w zdUgWQH;8KyztV0Y4o9~QaGbf1GU^cxCU!eK`OK~hCL~#@&&BubF4|aIi-WygPo|Ae zOn6e%Wv4$!|2>*tio3J(aesa}9xblN%KA?1vV*FFJB-@ROEGEcJmO=H5F9Ys&vAD{ z%AeuUVVfr>xU*v*h6j7aLy{(TZXL$jn&P>>8QZ%DvCENBdm5|k9>va~5_F+cbVq#z z6hfUX1WigPlilo|pkLk-4IXyqK!ZtI?=b7@@q{?LI}pOa|1rq|zsYe_OwuzM#wiUW ziYF6w`v<$Ry}$2CFpig`Y*=`fw3&#O#f1)K3jAkIt3ru`6Us(;BQulJ zckkYgM~`NGj35)Q>>%VQwTn!=Ub`MQZ{3U+UwkQEd-c_L{q?WK%P+qYufG0TeCu1^ z)blg(+_TSGfWpqN#f3%h99vvoiur}PSYBI+Pe1)M{)_+O{~f>gd;ih`ICeyAZLG#0 z{Of-e@4fqu?*wAS{K2m3hT_4ZH^w~F9Tul?)FpSrO^yx5)c9bGbN9}0zmK(=93NGA z4SGTwffvUjT6Cfgjzx1!UbFM5-eJtdDFQ(zLAQ7Jy{aC8&$8;@GIere-9jYBdmNp{ zt|%53GC9rUW}nJxOzq?H)JRM#F6;_GNWc+a2nsmjjdtjx_mq!0PC2r0h)LAW_EWd7 zh55O7|HmJxUJk^w&pjVQs=wYnB;Sk~*@eRxfZ+!By{xTo$vwyI>|F6eLE601yS=mT z9aHSG+EhE;Rl1H8Uv--9J?LNP?^Doo=v|0Rnj$RO-li_G8zy&DQ3u&c;4zZ?_!vQr zp%6X;^uwI4fk2gez?kf2p(}ZWfEXd@fbye%fIGZ04M~F?r|ihf{sBA2{w!8pUS5oM z-}zCz_2&2Evya}5+n;=(e&CLGzj$oKxJzZnWHH~AJVFtH8g*TbR0=x|8RORPoE&VA zb3KlcBmesP5YTZPB|Creh(!<)g0Q=-9pzM{RihY%kD{HcYa4B7#>9C3U9_Gj_Qhwu6B#P!u>3oz+U5B2@(>QjH(KN`J*V=*~>DMlt| zqHlO2+Pep0Q|*-n40B8C`gZKuysmG`^4g|%O)jjg$GpBz^Xi8dmsev=eG+VIlUXk45aipk;b80+uUH$`!035m+Cn{rl}?CX28IRDT)liz*&?fBQf_pjm) z|L6}q_W$``_)dK7jc=&jhf^r1{6a9uagBTjX-kWX3qA^QL*F#+5ED;yLoe`Bi{k)?N#;5Kl?M^vVd(*`F3e$Dn>=) z;loGqJHPWg@kf8~`_YfERrLn}-K6@-%a>++(uq1T)g{$?mDAwRi0bXA>eyjCxPLq5 z9^AKZkE1SqY^i>fJ4aEnD-Pi&JD{io`nWq`vL_ z2=x%G(FZFoJ?f7;*|FE5JXbpp^+6r%)b5V1w$r%%>BsS@>evB0T(?$ZY_L17UmTBT zE>FZWmpIawcE@fswZ~n>O>K(fV!7LHjk_-O4ZE*z`op;_< zJVW1}Q46vuH-z%ciLonhX>nQo*{b=RL-p7CEQ>BD1Bw69x0yZ~K|MPs;fCpZkB?O@ ziapA+E%^TA<310oo2GCY_U*^{JI6sb#t` zL(f(Pu$P@WiiV#?KshPnRnfw!{vnVd+P7C&v->H95n^@{-Eh9ZYU-+Q^!b*lXsp-6 z+bgV#U4`my9KAA#CS@~SHO~Me%B7f1PwA~h9cwvaOjPM1VQo!M^-M+;e0zXcI>7`^ zi6Oas?Xr&v>Cnf}i2~8Mij#~mvm7-CePV5)gy=GWfN4!ZKwdz~W!kK8;bZ9MkRw;H z&!Zy{k{oj0{c#F0Sk2=dISPo6BFAg+!CIhXCh;)T^bpC+l+**H zfjq!w!%#h+Ooa+AzfncDc2UZF{C;Cwv z`KUP_v;`>^@UR-sk;a9b&NtwlRc1z277ib}8Gtc`*5(gn(nQDuK6)4qqe?~K(<$zN zV)#z<%O6VCOI5Kdzz5aJ5r; z*JEBlf{B9RB)I+(Du3Yv}C`U>Jb>KjQdR7N9pkttVET*3NfnbhRG7S8Q zGXrA=KE#lB z()GA>@tOu4L$c3s&URE-ptzvquE%y+zwDt}NyFeD;7vGL%hGI;>1^QJW20Vn$1gZ~ zC0f3r?ch=MBX3Dp9wC@{j-9>RfBLJt#Z1jec9gwnl*nWnfJ&w4aW`$kkXA2TsUM{! z$WnPwP)jKGYy5&!zfquIPnw-CAUlk7Fo^A9;X5 z_E5?pK*l3+lZL}bZ%?Q=5?Ao%dN3VbNZOz5(St#H^f+m_*fXk4vIjry zT_EqKJAm4@l3;5H&CY&qBj zt{$h+ol%;dRE#Q&n(qJjAN=%=I{Y91ul~=D9+3H&U_ns1(jx{S5?Br%{54NS(hq)#>Fk;3*u2#fINkQ z>vxGut2@wYcDS_+DL8Zu_ZGh`WmVxUU2vOm1Re|b42`q#qF<}u z+*ptGRgT-*jjoQe777J-qLUyrBW^BW{na?VWh|=uv$Ajc>%nu#HW9N})5fgZ)3Baqm&acp5A`8J?9Q#aTN;vFCG;VK(eiZkiv z<9ii0M{Y53wy%dg=H9M;WlMjT!qiuzOW{(Uj1^K~*5e5{cz?cQtayL;;6dEIcP|ze z7F~BZDPi{Etam~%al6A#3;1XGAq;kqkoQdZUA=N8{=I+qzZYM7?KN0t-;49l{_}q- z-uob?#z&)Hc|JZmuJBY2;(veXSAI3FKl7|wP4an6wtLa!f$EgfccgT26c&@I2l`g- zC|&G6WbDA00iK}5t@vRkHyt%GjWX*K~!hi zO~ek*RgPa|W|lFi3X|~JLFXeLRTmCK(^X4_$!Q=%!virjrMOK@sDI%ur&HmnPN=;y zu45j6v1vWV)bl~gGlbha+iS72wWhKoUc`)jj$KZhcX$#F7JLS7$>arJ7QufB7?d2SX?>JLE@Qy8P1>rvBj%VN-8!r|(4SYCDO!`=7-pAH5%2 zn``cexNmM^awcXjUGqI~BO{|48`2i>&-lJQ);6|dZfVs5Q6*60`V?q+SC{f)X=Npr z)OS%<+a@?b@vQRytZIb`wuYyzm(yscpW8uX+@4geCeDRYb+29PK-~)H@^AJ zxcU5x(V_nPq^&y+Pt?b=!$h-qzQjX;0SXauIzLIYa$B4p9Ahg&} zU%j%lqPn-`{=U=o4S_31L~@K{PfSk?#mvNrcY5`zt7XRw3zC64=W=>{pl{=b^N+Fn zXP=G zE$_;tqU@9&B&M{tidKF30!Z{89Yr z58rjVzw@m(;&1-iuf!F7%XY-axGz*Y@74E;g*D7oay;bGX}j;GWAO&*;M>K>EO%-1 zoj6oohxh1mpTxIspr0L=pwoxtE=*;X`%e1y#g(mCUfqs)Ju5OJFg{V+YZHC?CfaiL z{L<1_xos!pTp)d4nsZ#L{#SL&I+;!5j9U{2sPxias%Tbd*qv8f{M+;-ywqZ7#J@G} zHC`2(^qNrVRcJN0>TCa0p*5UVs9{nT^!e74&rb-u70$<_6~4#~_(|?h0(^WGf9Lb^ zFB_hgKY7$)L-3Umr%BZ4VC#Wvu}Swd!DR4CyL1C;Woi1WzEjtVcNV85BwHnBhGT6L z(#iHM+J-mV$>NNi4GN*enHPnm`eS?B32JyQUqGF)m<-Oa)MyaEZTs*o(~Q zQ(IpG`AI}6&`5n%&@{rbJNlv)cLV8YkkZT6*rnd6wkdG{?3Q#KN9RZ4LZ6gWx@lix z=a;SY@>`H`tnnvYY?|TeZ7117Qxy{iZ2HngA2-L28&_5uH9rx9UQXaA^T&@kGD*`o z0svK=f{({g=gWYW9Yq$R=!2ZXFfl}8C@nY;&YlJklszkdIEI4sLknhwOFenm?X|YL z;xoRDAZF|UK?vLh5d%mM3$bWp*kwXf->{PpS+z~Zl>irsB-qoHdY971dMV(_}t$GBTrafeF8%u zTHf&_`Y;GEXw(<($2wpOH^L~n6D=k)7-%sF23Sec)*&Wsaw4wWxE>cTUyU&hka{=^ zTKNP+%)M~b2bTc(t~jtg9tN2QAr!m85UOzu4Dp7^qOAA^!vs5j6({nSbQ7N(n6Z+v z!*TMlhDtxo9Qeeaqk$}>BHaqx?Sx4R4SZ+^Fuxq}0&(&u%PLZECM|i&qz2^zZQfpC z>B01o+oj7wcwS8<1mjAB8^^)g-Qu^j6(IeUw~#WAFg0nLPSH2sgoEJ>ZCS}+ z-_;qrqNcaBu~~2XbzGAU_Sk}9v)rgB^cnnV4>k7op?@Qf@L=0YUnV)E6Liod^-L>x zGM7kG4h?}6U~Ba)vcs)-w|!Ia0v+t2iHS#G%M7dHB{CYlj7p!IY4RkriC1te9miUx z={?PkGOOFrmpCVe>}{9yz$XHv6fLA0@oBNhJRqIvmk^T#VI^(M1m)I*9$Ux~PNkv0 zk%}IF){1Og!tu*-Mzu*dL9BSME)Ae)Ke^o0j+wm`MeDCxI>kNKX`ALIG(Hq@; zgV8@U9zKe!r_X}0w$6U>5aK7q*Yx!E#n8}*#{mc{)>l`9J5_z3kJ88SV^=TFh!>fN zNhSw}L_>TILM$eT7ypOnoTRfTtGbaco`}lUhnU z!i_!gX8VfY))qn}?w(=twZoJ3yDZ2P&xas{@`DfL7_oNourv`SNAqNgqv#U9$7TF8 zO8eN@kSD?y7FIpk${j1DiQRJS>|nyRr%U-MzP7)oEv80?ykqQG`LVUVYySAOt<%DT zgCll+=_{f%!=v}~=~3D`6;JL++Yo=d!=(E@LaPhG{XUZ;{c=B69JZXt2q_S>z?1In z9tKCsQ44$|S$|KQ?APPv8M830c)`a4u5WHLjLHdoRNx?zW>mZzHyoh z>6mbS>BUzpg#GxFPrO@XW_miVT$+x%cR!C$KKU>K20ljsr8{>#7ki}B09^o!18 zn$nf)w_@uH@U5lmk^M?`Bi^AnZg~LK#pumRHujD}-B zb6|%ZM_aOMrA_&wy3II4X(cS^kByAP#hI}f8CLsI-ZK_iTAYvDpMDw-XYa-O%2JFD z_r))M=jY>C@s*MIYG#Q6A>%8Yx8C?Af!I*8@fO&_(mrZz!6W?X{6lXl7u9(FS_!Adu50{<4yD&F*A2;Jx>y-Q2=mA)7Or^nbl!uRC8{LmjD zaA21!eGv7tpZl!zAk@s`A(_nIH7;~nAV68NV3;vpj-e4OBFOHD-k!`G`cF@ME6+G; zjrzv|Uh;=|6XM>j{ORdwkB$pRvA4Yzj~?8Mxrei=V?*)UE3bIh*aO)iWMOwA$HCpa zc`IIi@x{1$<+67bF`h(FzPz^Oowpo0hfs*!K;1pLiEp-L-*LB8yLfW?PZp$Z zZmC`|KBv4C&&Byi@wwVPeF#UsabFz*;lADh? zkme4WcE$XG%7?OMT%Ef$mAAqf=;0eItFt z1B2eRhfqG}T`qWs?uz>EyZ7$KpMC%Ps+T)4bLnb~j84Q$ufC?fWgzxxFUou7VvX)6|1cVlgnBmGXI zj|C8&${XSG%^4pZj2?YY5N6R2?Vo6TqVHHoJN2c_yRzSW>n+#m$*BnoXuJb*a7f>$ zL4T#$iHC5Fewg@mdl#|XRY%!j*5<>RLuI|GI=U>oqnJ?L;66kaIKw|6gg@Ndi_MKS z^#f~euYKxMXcz24r7m&TCH)zGXrqe@^KtLaUH6k}23|1m@$Cn3s&5AOLvkPDgZs1Y zw`OLh+&41k)35wTKPf)rxo2+Z`*bk|h6a2u*B$XWpWmC0uHOE*CAVj;UiPjvzDN5i z{|(i7c7h+NjWOTJ_nZYdd-|3Sh%USFhTs*H$3uhaZ+bd>A13#fuB)%#QXQjxO;3*K z8{Fo81Hn6YfN_`EsLF)AT3BMI?(w_PbR6L*xzs~w?QB9}DqlAU7RZT4h#~-L+0q2D^O?pkJ^eVKP zTlMtkt>)Hno&>F7KPlYva6TTb@I`LGPjY_};Nz?KJD-<-+3>VHvf%6Q{O$jc>@QZX zsy4||9;FrowmI2Eg=pgC3ov5&Cq=)DwO=ME1svi;AOfR+YTAi*7K%lUR8lT)z`m^J zyMjz5?$)-rRD4u)tFa!c07Q>f)M!vxMeWHetco5Ieqj$?%+S-1 zFdQCMfZRE?ycMzlguWA z1}tEiuG(kvQU#=UTAf@OTHOTBvtuR+n0hYme;&~H z2*FB%Df!`p1HC)8H|EOR!|=;PmZ8Gpqsqhqd5#?ePz!m)pqiAh z2!|DLM@)9ehI`0HG(f(3>tLEusz2WrdBr6lNN^~Js~3CGCuy%Bm$az+YZWUEcbR9c-gN@givKJjo{u%&k6ZNDY9dEfa@YpYgKJaW-AKRliBEH1zZFw8=h;Rq9LB z^KmA~PWm&nrOB*lhSUHjEUCJ$CT;pP&>I1yJ^vI``D?RYjWky;vP(R@u*P1FDp465NU7q;zf>mruJoKJ z`kw{9CjzJ1Xo=)7@Y|r>RE!Fa<1B;GGB)VbN2bS6=@hdSBUJ3VtrCD zk{&$ecgy%Pv&+2^XM48Jd{Xh5Z@ijJq39Qw*g+%W@BM>+i0w}W{zw1I|5HXy&?-=H z9v5g8NTK>ExUKdT?9T6;T`S-}?NBo>D-Npj2(#*P^@;g0JpHiqANTU4JJYZ-*YM2o)B7H8x0G!;@xVCvJ*bSuzm&ip8NrJXh1Tl}7@H?4V=0B#Mpl|~b{wVs}# zE%@^YzJRo^Pla3*li$gVS9+(tv#UjXi6=zFId=BP(CAbQAnfYxi@~AcoHX+!?~Zx% zT36v)n4}u)AF%LcW@^ln`>bdeLz5HD-FZ*d($ad|x%VLE#k(UYq3?u$V-k3LY$Qg8 zhD?w9e%L9(WH39wNDrR~CNkN1kOCRSQ~W8D!+Kfpz&#^ea6dCS9v7!ZV@P^d`n^9*!dh|Tr2SXo{3itqMLb}&%G znRI87-@f_RwyyRV5bw+GGVU;90+Tz9anHMJPkp2lEAkmfG5Olo*69;E`g>Ux&ZH~H z9vz5(JoNoiJ#9yE@AJ=;t~T-66W)!0AY^@WqcM@#*U#>W-q=055KHUgtvOCkc{D!Q z9U}wnv9qxn@4ow^c>70hc|2AH4#Xjkv}4g&#PIM~Ja_APAA`tb^v33PtZ(c@SKpB9 z7sn9xA&e1UOSwFJH0Pr&EdWqG+u2%=*?XVG*2a?D_dV96267_Bm5Vd+(hJYa{!ru8 ztMU9xuSDO#kjFjj#OvqiFO6v^tGweVEcE2qO@t^%MXpZ|FahCaLfdHkb)@;mY2 zC!fWwo6p6s{o1d`rK>kBB;~#%gr-~U=2HCG-GflZljX`U?+#KOVnUgTSn3AprjD{( zhDm>qQPhsQ*`0=9L}Nlu>I(K~k4);ZIlqW~J zv119L+J?%KqcQQz*pG*CAbk??V!VjJhy|0hL&kVMc3x)sNf?4!9it5(cxFuIv8#YK&XIasY7gE? zDO}w8`uctR-1yj-C#u=`K^zDlK^o&{=#U-+^Cz;qd*`-~^dvtKA|cFNURt17Vtisc z#`I9W^sST^{gM|>2KObc#@)|8jO9o7V?cTO{PQoy3opFn@M&uo6o1+o{Skr|c3UA7 z8DNp9?6@S zs@%J~xqqle3;`=}N zVcdQ2!2P_BW>g+rxik}Ryz%w8cKy2Y^Ta}2PW5SP@3b&)VsbKeWRK8mPx-~pSA-j? zP9DQ^G%0nEy2Txd96<^%gbQ^7m zJ&NzY`NMeUgZE=o^@<}UIaclnQxL8IV0fZbemo7)LV3( zU%h&@2;IuDoyrINy!Y{^@!>}wxt(0Pd@U~DxTPAz2|(>Gp9`v+@OlVNMh3d$lMmjG z_ulzYEYCl3AIqIrr0DfmUXH)@@BKUR!Yi-E-brUHuI|R%vf8k||H`E3Ry`Q$X^)|9 zj^8}>H?4nQB#y*OZ0)NL+T}zX=KlDGsjpWXB97`ze4OK*yZ6+O4#dx@U%Pnqh6VP} zrtjkPAovyLk@84i+Adw#snbYbMe`kGC#~vXAKy24CAoWnwfcq)zNyM9IyjEvb$wU; z;mBZhH~v2P#3{A0x_F!Uns?rPFaFEl{a3zMPF~Evuw&AKGSz!_VqKh^@*RpBYaI1^ zsJwb5zV`JuVpR6rm-$G1&f4ZdY{PS?%)p`UaHQ*q>H{5*?`PaU)VELH3Y8-ZOExyQ z+~!$a;=9|%mE{%ZA$@$d)8u#fPV!C1z5;Hw-%T?(Eq44{-6}1sXq63-}l(S%c9 zF&g?-uOwI%-yp)C43g18Av9-|1i7J4yVQMgew@|Yy=wDiIEw?IuV_s?$}BDAUgO`e z!y0@38P5c8)XNv3bF#a=wpj>r<;u0VbmdBL*(&~xC;H?!MuY$`{|pp88R+j26Fp)` z#E`+HGO>YBYg-?EjtTH_2KpGX@(D)OLXTrHQNl$40ON8b6+4)62Foyo+xnQ$iNi>& zi5d5$sn8J)f}s;WxJ5wG0OT(!bTea$6~covaL(uoQtikuJvQ5554L8Rf%RGloXz_Skuie5YnH1izzLGkn$s^51&v^RZs}3+F>p@vP1&{ z!sBDleGZ;LQ31m=vir^#-|CkG6H!rw`4Awm!HuJ6d_FkM>_O~31?76ycl@aI_RS@#SrajAiAvq zB^Px2a$)L$9(EJ5Vu}F|$zl-1V3>&$1{>_+qTUmC1Y#UxKo%nWN?}(Dr84e{r~Ei< zKIF0^?m3x6T1h8**)zBkz6V?yG||zMH!ySzpkOvw^$8OM(@vT!L{wh69g=TESY<|B zi4(^hBKT?(Gdnsm9xpumVoXoWxNH(v_1sy{t3FWVXN>^t)RWhVkt)tSq=PFtOIu)$btJWWIEPQErvd;D;b;aCtA&^Gg z3qiZNyplF{1}RCqNvn8Ka+v(Dsc~*wcOH^<2@`)(&=Xebi>5$zH*PVQw)J`hwOnhM z**!JWk%gH4jA8HezOt?syg^H?Z5*sK!B%#I3c?SY^*D^$mr7frVtpei#Xpelyb5wr z=&R^^F@Wy32xJ>pT(PXd;74js))w-3wJrKo>mn80!2=wpqId9^i$Cn0cXGfj@f3%K zXB!Pf1zapjaE7{&#dwW~>ZO2;W;1Rz)E1&r8tE=^NPWQ|9vA>fW3N{pK}xwKE#hk| z&}~lt4LfN{R!ZND2RbMK6_>JwyzR4M88FwXg(bT?((hS1Ha8NGO1huM-~0RjX%p?= zFjT=8b*4gXH!g2}sKpKdw+e`W^Y~SNMs1-FG~J;idRCkE(kPEh*iVWB`lhkrR^tUd zXQIt#{Wox3P-#BzR^!!b?_V)XqX+*jb_JSgIZFeu-hSjp1Z_v#osAd0WreeJoA4xi>@wOl{-h{-vMR)+Pr#O%MV}0rMpVRSw6}>@fw#GkM}(PA z5zod>2zKi9^bAB>SGV}Rp6Ko#6hFg#KV4qgKQ%sVG8>y4u_K-yzK7$?xQ~=o_Ydcn zVsVk<$#;}~#X#ZqmYp9=QnN6Qg-eVF;I)W@y3lT*`@fcw2`}CW)Cs(84@46QoSO zF@egd6!5|bmbgoVW4+i_gAkBOG{!l;uV;5(<-jC!cl0ZMqfB-wu1p@XOJHS@9RQzt z@t#;#=NI>;Fmc`2+pl!C`}idU5<~qx_Dc?MYR3B3w#Pu^68DHqjE#75^Yc4*Y0Mi0&91 z9*^$cftZ}S6qhbvj`7i9?~3b|8-gB=8)PC7;SCdq?9k}zJdXF@{*(CdqaVk*+}N3y z1G^9}pGVdNVb zjyOD4eLrcB17++1V-@rKDHx($1~m?DS02EJ(|8oL6vi7G>na~2Hm|t3oKl{Ot;s-zcVe~2wzw=AK5?8L?u;7OK;kj5+<+g&)^)gGa|nk zV-h!x)FZDEJPs;uTy*4=Ea#Q*O^|8U)l9~c*xZODXjbSvybCX{`mKmjsx|L zlU_hNs&O@S00CW>`%i?9-Ksy_0k;>Mdf4q^VWINBL-pZ6^p2FL>|{g`@Xc?2Q|)Wq zJ7y8Q?rKcT1boilsE+mYxt#&byzEb~fGLy!*~OaYuP`L2Z{KO0QnI8Z*;V zF{Ad%oo}n_>+$LB2eGuesq&%d^B6o9SRhEF?IY+w0P8$cKg$9K1i+LNRj5zt8&G}e z^O29-pOk_{<{Q|7OI@OW;c5f~Q7W()?Cn;Ue`J5`q9L#8_h~<>0V*%$2mMT^+Ovr6 z?rg4y-gQ~zimoBDR#dpH+AeCzG_{I=@PKySS8%=LKw<}@&d4l+K$hr)$Z zp_8Hy?NFX~bf_Ot{S=l_=K# zM%f8Q+g9Jm@sNv)%kEFS8(27(R5ri(^FI^M-MX$gxCVGmh_p;hOvR;3SE65i0r|sS zay%P5-0ykhzHn3Db^0bJgFa3__$c@m1k@L2Cgbu&)p_v|-XtJ@>dY0E!ch3&d;Un@ z^*+@P7PqvWu)|e-g!mfn>g1kIc%8A~{HrW!aWb?pY-^vp3_fSWRjsQr68rit3uLFe1ZLEJhFdl!NpAu85L8sbmITk7S1`UG%KD%DTb%Ow1ojOvyyX~K!dojbl%Db-PRt8?azS_UW|VA5c48F+FW0h9d*K47F^EMYWRec|0*Vhk8`5*ME@u8${l zyb?-otf1pkVdZviKMdP?#v(C|QC%+Zqoe86Q>A3<%N zN>&ppaTR!?6=dia-B$tk0ZK=fZsgcTL1V zJg6ho59*8ZABOYTtAY^tz({0j8Hflqx-__)n40tvn}cHX7=$yJWW_52EaCwJMR{{n z0*vc{m^I%ACwlDA@)3tHIl{?76sy7zL@Dmn1;W%rIy=NnBU}QH6~w5y0*}>$V(zFE z!etj2aYt~)hnxYO2U$+4az>G_A9xrlj#43?S*h$kS!CE%Hl%?J8R?aadJue3|5+hu zCd8STwZW~v)D0i6=mB?|27try^7AhM-#{S0`N%`!oJU(x&x;?$xlYt$rtb51?64OZ zs*Hoet2;Xk^_|v48;f*K18FgiUf6(CT(VmtY;0^#9KbVX(c8Cm0Az8m7{#}p^JASZ z>ARXL_IcN|!LBuA=YO>!UYKRD8MTx#3P2qEw!eh5DQYzcObYK}97w948Ymw$&&t<(io3$8kb$l__J?mT;gU&(+3463jA~N3bu@YUG7k z31X5ywS<;*Qg1~7zBHM+!bP9{u(P%G{O!T|R>;ZP5=Y!j&sK)C)3->Pq>)6?gKEmQ z)~gYZ3>14)#?Gi&3IIJ?SsQ2j^r|*wgrr?u3mtIu1{W9G6$F8W;`TwB4ZnI?Fj}IJK25viN7KJF`lsJQ&uHnZ+8Z4x zxc}Fm;*PKX;s4_Q*bKfVN>KHvO+il6j_=WVeE-hbSuOo5X8NRty;b}`zv;J?Hs8or zx>orY^LctaHNG;)KZn9J@vGWMQzNXiVWjq4yjoS`$i2{^Zo&hi0*PC23Z%cLTe_oG zJ5+4-t*v(a3w~2=hFR0*uT;rrz+R1?0L^Axl2&y;uNu&{;Paeu7qprk4~H+jY=|xH zEq+_-0?=B13Fyzpt>T<1>z1^(;*$@pQ0-gcNp^-Bw-W#I#fQ4WQ$3PDCR51mT4&P> zag$y=5=QtCcnbI!GKS+3#a&1vUPk;z-vCEZaYxUn1sOS!G!h(Lwky7gT{}K@T4Avp zfyq`TR##S6eYX*de8>xS()f-jJ@9TEEyj)^_^*tY_%iWU$0wZpa4h~00bK6>hxug! zU1Xd#CR(|}gT+#HCkd05YZ@!8Z>;-N0CHn=crY$qn)dN;-RyFKr*z(ASu%0W*r!YU zFky&GECP^Rh{q`v9FfFIYj$IChf}xsVQ9k-vg(}sW7u^vG%^Ex#x_Lc1x(75C>x@InkIX7OJ7X_SL?FDS`MKEM zT#K3Uu^1a3@{X53{o$Lw2W@ofQjCmGiBIl~t&P=qaQE}LfA90y+1fBqO`Tx{I!`WW zJ8})~QoWd%ysSDhG`fey}LL)?N#~glAs+h5zDcKj3wA< zc)IcG|NHUrC!c!f-KERdV{GDL^t0=+r_aY_a%`mUan=}tT`xJI&!Z8TDh=^q z!g_9D!4s#$?4pz3rRDXQpI;KseiUPUUD1BL8;|b(INtuz_kDDu$oOcn-}ueH70=v! z-s2}Gg+Ko2{rG?V&OeTa4tM`sFhFHVj7 zPPHDDJL41REG=(ZC`tQ70EKX?qrFq%5+-+5X}qsK#=Ce1ly}glM-y%D_(F=Te3P-! z{^_ec{%68mab%(%eA+bl2#e@1*ljdAGUz&kU&f0FjS(!+S23YXzvVdq`YyRMUStO& z^B2U+!Wp^Oxej(LF){1~vkq&|M_DEwixM+E?ruvRpbpW$FfN6@cZ;dqn4qR^A*5uH zBRkK0l%L{)@W%5TjQ5Um+y`Gk9*t;>%Pu)~D9JLGmzPww56HC`7#fP6!4Zwk2UJe& zDqD{3Q~#+v=~KBN#HX(q8SMAbc-vd+vAFQaWxcwx81KLLmfGrV_g9nyyBwLnVb>PB zlei9mxL>?JCbF&VGE`f5y0PI>p_k(gox4i+pi zpQF4~#`%~->Hz&~Twvd?3Y@XDa8E9@TadD^PYb)b7&~{V4RNF^`MJfF7E4OU@FrAY<*Or!tU?uR9){?xLjXwXdF(A zVQkNiDe4#tcM+^`L?i8)orT<$##kMJD8eJg{s<8Hb{(m|TvmVi!TayV+i$<^dVTZ8 zjdYG1++6(rpZswwudS&+829cu;;GDtXKy|iFTVVG^s8K5uk{_7Qo6WP z>{R8ny0R9xXCKDw;u0TX?}Qsue2#Xv)y~w1EG)(Y^$jfYy>aDQy!P7bF+MY`KI+uR zERx2d(Xp7EQlBv}sD64g7Ut)LzaJyAKVX-p(lI*F8`Gmb(c5|IKIy$5y&Zk(msd76 zVrgYHCiE?R;iXsN%C(!`CEBex(D!vIPuf*aj}KK3_jY1?eKqdfyXRv9NAJ|0uUNArtnbW0rq}jbjn)R=^>E4QmJ^f45Un~4&3BEG^a4!ipJm9>r zrb({}tu%qh!YDvL(rRuE=Sk2S_LIUr59j023SZ;~{3Q1$0Y1Kpzw>$dmkm$LqZEAo z)_9dMpSw7w^0C6T|k}k+XFaauE^$TA5$A$`! z*iuEX#>i$=p`Hy#hGLmiDrQsPprG(ggE$zu>E<^I`H{v1!Ey5(_RMuC=ADK~xM%#x((aWo7Z7%mN=DBS@jM?C$N0%U7<7DZ1ztd!}zZ zsNy+yb@8Exkn5xDP-UqP14p^(gCj`e?K|AHn zsz2gI9b@o9oGl2G8-gVT;5>2;Dl8Ao6%Nc448Mz*jmM0Kim>N#vN7oT$mW42A}W91q$?4hT~~2NRyc zhb&jeTeNEYN!zLLE}UvG*E1L|KL1i&y?8}TK0;}MklZ$TN*~}}LV4%D8h6`^9@eHR zEQi;uJI0gFeT?z2^xyudpXhBb9c7Ezep2H$44nk&6WM8Ncy?zewV^n+>CZIKr^m*( z!D%ac{j5tADKmwPHF?+)`bY(Yo00YgbCC*@NVE2 zGqlKA(jmzFkQ>I5Hn(}~{V#fA;S9<6X4c`aCH%xrS_UKGSi-YU`*l#p5xCzF$f5B~ z#0ZYc){{Omx7G(o5jwJSR59ZR8w^DcK)u#KY+Qzb6xTgD_?SIefx`6f3W zVK%WeJ2>N8NgR+;mv)Jo^lgikexl(zYde>8x=3*ldO^YXC0(Y-_rP{(&ibD2B`80p zWqrnj{4_>MZyu+_zr+c1X-`S6xH~e^*d^T@Zkp7ttr0!hre(&Tf|JJiVecT8*x+tN zJ&KQ=s>A&1LA7gD z`Bip@}QndR&js`A@f|o%Q@%?6RLvGvK(ExMv>gyV8OW7{~fTv!R~Fq0YK) z$*R@8J}yAH*LYWG#kDG08JVUXhE_augb5HPPZJ;9bgQcCs?AbCfl0&sgmUt)#Vp?~ z`lbpr^e81P3^iP!)nDz82se{h^44vl#T`4WZ7Svht$HIlyjHvOI5L-Xo`tMSt#IC7 zg(un9{CqN;%>$s~)^|-?O(pn=l4klVcdgUvnhhk~@rg&F5@xZpHT2ws|WHOWN|-EhggOlZX!!jPP$ML}Bq9i{vkUssN8X# zWO52Y!`Q^QC#2aWh8_6kuY{8e`ZNX+uRPG-9lhe6;Stw2wqt3H`-XO1Md9`O2L?Qu zhp=jOebeDjPmIRZ%hU4L;YEB)%Nu&uoYtQe3$uU(TDeC; z#T#J=!lnnakG#r%Vrs@|W1N#hioH|5gl-j%$phvGUGF{P?}M;;pyewr~@HBX#=amtPg$*L_zP0^QjM4}7QE>#w~Q z@j`#Q29XkB@UxIRNZXB=^{XGCegG zS7#<;l)K9mZziI5_n64tQMy?4mq!Y=w|B|U1%S$4e|-%_`rX~DYOsLx4*JBIcY?zZa)-`m{fCEnM~J^KZ^P9}cy1dimrXv-eM z%AQ4}oyt!HUrdnu=tO-(=*Kw5Gk2FzM@3h9{Ns;_f3A{1Fkr!%;?MWir;)hRVWBCD z8_6RU2($Z2bx-vV8VJlrImU8;I~F^X2GX(_8ym~9wz?Es8|$&Tz8$f(@Pe279maJtpE z^!KShZVPo~s^7{_Vpk{WVDSO79O|4DUVcBRFB}z1dqPl&KZG_ya+#2a+uM8I z6-iyNo8p-B3M@vY|3ILSySpe4j_jPBos9?g@5SxUK2zSV#^mIL+TZK(+;h*m|C)RB zFt*j!#>dB854-f;LrBQCjm)^vp+37^eb)M3+@D*r(1o@(IMAd1Y#_#{+lnJQ#Mn_s z9qv#b9&B&Ky2^5ROl|V&RrQ5KzSnAbanWt|h&v)VHcxrerS{gV{sI9pyV$n%Ex50~ zVt8cK_79i0VohnE9O{afo|%eU*C(P&?R)nABVQ##fA!<{-;Fna^tR&M9y6D(dI3CX z9Z($|P@m7dn|B2&&o-79T)%dinywEM_s{P}pXxWlNxt*&5G=H2aYb)$zsEgmn|racxf|R1UZ1ExY*U?U z@90rG&z;unI;XFpf1)31BH{^dm9zA-ba@|n- zXp0wQ_u9+PMUUFr^6H9rJF>%WWj*gvWbw%6+G^atf7c5L=r>qA1fM{Es}!jkI%T$_ z|M)j4_&P7}s?hXT)CR2*7Iv+w{=~VOtG-;fvfVd>Ndl!B0xhd3aL#{xaZcd4%Ar{kz}&E5Gen>H&=pj?-LKJvMqIk_PKs ztI<`(w$|4wQD&OyQ{$ZOjg&Rs_$jkzsW+gexnYGJnJEirsh*m(#oA?3T^eZu z3mg;5r_yaqU}2Vv^#;uHS&S%^cA``@F%u*0(2@Q|**IN^Sz>H633T#9SmGK2IJAJ7z=$=JpdOjM=jFfa}1n?IQke9OXstowws#FGf)%!1faol z>;udzC@@0lkc#P@2i%@y|5ZRV9Dh{38st=PnfukIsdrkfW#~yQ_$Iaiy(iU{y=W|JX|BS$83zW^)USdqv;z^m!R6tS{0<5C6>qC?#v4sL6Tg9l3p zz791wP`&Ua>B1qFR)xo<&oCgQm%%^4dCs_5ASHj$rq08lne2F|tfNc$XSK zm<;?n7710CZ8mArRNYnR2l+<4N?3TZzv{WzCvMeLmAaO6k|s}jBwtcj>>Rc*rMmmU zQ?a+wu&NZK5-AL6A*e0|L?~(Nk7v_rwi_>MD98lej8ncH=k(|wz}qJ9@hp#aDTJJ2 z!boE?TohxvMqo&j4GB#w90@~?_=O%?J)ql4s=ZpDaj14S+rX>oCqaEMglNxAOY5C8 zEmrm@NLtmH@0u2)*Ow4$Jc~_2(X<9wx2PpW zdQ8dhs)uOied1I<)>@Ah*fL-)0fUh-mQjjzs77nzCI*o4Z%Lehu%V3w{SH<}!qFtE z7XmS!@iWe;!?yTw+?xIYd$pRnRHd^bv;0&VZuek|27Z8w?|dryrY`*^-Kw*7CKFQF zIpNsJvPn4JeCwURTTK7P;ni>b+Ha%QZxY~dLou5_sro0V{uMLOaHIVc>+}AA6e6Tw z=Lc#!G}KgD)PmPAw?L~sKZE0*-?-|2CT&)l@wZ=|@^d_@JO6?wjh>9Zzb&>BzC2W% zR8{)q1JL3IRBbCw*E5I+T;I+B@yM`%if7&(8Ym^KW;m$l=>VeMz-iKY99sQ8iB5}O zIj64R73=e~pBB3_1&sWd#W6{ zFrC%&2th8G@9Pvo-jT{gG<*%bPaj904G(+5nsPSJLmd`99(Lj!dXkr8$=KPSJHWUI zAO1Thnv)M@Y~ck)@<{n})HdS?1Xx%?o5}0VjV%k=I9Abj&4>;=iJ;dZdW=JuWantH zZG?2Ydlp*w4yw&f-)S_zuoP=+>#?%D8XN1IIUy&S(B&vYc13MVW!J?1zW6z%V^4hT z=FXuf*_ga#Qk@CBV|B{Zd>;+A&z(~HPCKi&NuP!A2~^Bu#;?UW8IUvOb}CMP|EJ=);jt;}V~xQOIB-PO z;P9v?Ql}O@a`^4XpE?> zF8Z_tjxD2(u-FWN41LMs;$l2}@W2zC)D8H4cDk_R1%UyAO@y2rm&xuiCRY#kcVcsW zC3ZI0adsTs>!YEdcWzO)c6T{aorQ7xp8O=f9eSh-iNBuFK>d%SmDeVto4CTT2 zIoqTVME8R8FHgo`_Y1pVXj>d_h!Dww3e_`&!71cn;i3wZ_DH){eaW^-`XgS3$>I7^ik|w z$z#MwBa1SXAH<3Ap2H_koMflP0vxq%`a}x_`%=%sQ^F#z7;{jT_+xC$QKuYB==3TK z1R6sF^54sjB*yJI-t=+#>T~haudy==mT%s=70*8Rd|bbNE2d{I$MnU^7U&WtYTzditHV+$pu|F*B3)?2chK5rQ;?U2(E6^SXDNe*W2~ zasU2we5d*^7Dns}j~%Uh zyPL|d!{}jtLh0BPjm@=XAKBL}KO8Yf+!hw*ibfik^5lzY@#K%f3^JU6lQO^o1j8<6X`x=27S)UwP@J z__=R?Gp=2ncK>y8Y9eN)CzY-Nw=Wj2bC1;(_4}{C@y&Ss>u657^9IxA^GMZBVH#srkuxNXS?7mYUfPf3ZX}{`0PnX)i%5Q&nJMO6*?tJ>Og{c;* zZmxT$*t5?*AHVoZzZ5_Fb3doP@@wAt_S!42#^ltL@6uYvR0K==>hm}n zwnufkzi&|Au@Unb?itWe)Q2Ns$W|%JV={SKcKXbh5^;-;enpGG(F~LOzz4`)lEJs>I)Hys~WI7mL0TR zsw-3u%4BeW`{Y=hz+J1yv9h-5I?E2l$;okj3kKaUovIIFQO)f;_f>Zn^{vVU8O&e7 z*ZC(sA71y#=%k{nX25pkX_%`Y{w?-ce6jg)wZdcW_Dee;j%k0+hyQX&V}Vw>PYdHb zd=cK0+@4G&;YndU$*vW?$o(hz1-=Z<(*VC;#rIz%tS^G6(fz%D@lXHmg}?K6{v*#} z&^LldM@h7EK+6YGW*ig4@6-c{SrDYhC5cpQn+;7rxV!E(te}&$(+}!dUApkLcX_FH z6(^y_w_%^br9ayx_SsMxzV)Qu_({lEsS!5BT5+t)Hvn$tw^ZjtnjK!lYx*?#mI#`( z@f(N&kZdbOKNB~i0Niu5a0B1^gl5=D`>a4JY4cA#wk__$wVz^>W+{p+VWdmq+pmpH zy5NzIC5iH5afm+32rhCJ=GE(0W9HI~&DEW-O;0~oJn?~cn9ze510_D{Fg0E4aB_aEGg&p!Svwl!$<;6_ZF z|TUV73V|DC;xvH^>coIj|$$#GmNMPP7;tkX{D! zOcW5F2ca4Sv7!z}k+RE)98rg!>OS#zTO@2MD?#%TdGK+!09biW8%N07)gi|3nHS>f z)qonlWo*``2GKj{JV?Bk%9fCjpXTfd=p zPFsWfQ{iVlY37gJ6-1i#Q+slsh8;hGSAa>ishOQ?KmR{ugamv;fXu6+@|W6b=U*#MiwaoJ|C}528BC%&%P4!(IvXzTXZ-S)dd9A( z^?L|Zf6xV>>l~F`BW(>g)U#pxv0eJ1j4NN3_)R?gCe5Z>g$8a3i^QG{*SaR2RMO!* zX`y-64{1A_Pnn0ZqYXYrAAPouYIojE?=%P=!$B$GVW?pPt+>S7dWG-!IG%DRPOa|P zVQo_}7iiTR$>FuyoyU>6=4~su6Kd9-3YgDX8Cvm(SB)ERo`!77(}X95^CYl+=_Fj= z{f1}aDyZ)0?jMWM33eh~kG}q4@%Kz7ClAD=DtAYXjShGmu(-7172$j0-SX(`V+%Z} ziwLEd$YIi%#Z#CG6(Iv-2PRn=8@TVSU2`3bo$JGPx z2Tx175Zck_!p9zoKP7dj|@2+Ca8#` zcXfz1{4^6<@P8c5w!FM1bvrm}X=ZvX#zzOEOKuziIJdYQn_EhscuB`u{Hoi49t05F z_rfGH6UF2g`M@z^9nvt##tsDpR2+}QU2CiBYn~`XV8tgCBnoTRR$OL`P0^mWg?U02VB1j6?a7 zKkU?Er_IdFOx$|rrf~XVcaKTcP47tC*jQ8g^UgJ)`uM7zfngsh$ZiaF*4}fOqCS&f>{=Tg?u(JZp6Ks5iSYrA1v*dSy?5S>|LVW~uiQ5N z#^3yRx*JC6&P(L+gY-8!R%6bazKHJ{wi@e^UO6DxVt#~OZG0bmOuyQa z@48kxNGPYHFb<`zQ}3wfq=|OLF3d)rD9-eC#NRs~75_X6u2bdADJ1N2p?{)p%f*(o zeD^fZB4PnQQ`VEnH`=P9v2U=JC z;{GHS2(bH-Zv#g>B3PC;`$y1qtop=}v3y6l-;JF|^NVWJszYj0o=fOef5UtPJ5agv z@cC!1TL`i)9Qx+jd-vo1?0x%ThcfdTmoLu5i!ZzorwYdl5w2W{%a^ZMs9bpw1ZUj} zgL=g7N801`%(NE@D1x4Ep^M$yIfw=I_4gkwI85$BBd^Fqj#g#Y7Dom0ZDHpb{UZWt z@|VRH?8-uzKCCv$y=UWfH2MT*l-_y-4<*(aWhpI9Cf$FioF)T*uQGJ~n zABrjQ4)hPlH~ANZ-p8jKzdps;D`8^|8sLd> zIv#b_?PBa%*>_nVcg_lCJ8|oTeNs{Q>abz@%;XXu{mh_=@#KtaCiW2m&>6Erl5?P8 z#9-7o^3bczEDV8p&J|d6^gfzI10a~v9WlqtVq`ex@V=fS4J+JY|_Y()j8Cu2l1 z_12$Nr|iBlR7ZgHR{eRvP0gWQgAfZtU`F*k4ZeufpBqXX5>ytl@br($jCy_sum<1S ztRDb6CJ*?S)IP?n8O|y%00xeuW)OUFoM5{?)Lv26*W-ExbKbAPKC5O~8OwKxRXQm| zB030#G|*95o9Tp^Z%6QzSI{|~Ct}z*ijX5a#K;$BM=YfW7YsJ2Uocrdwn7Y$C)DMav@$4x znIuzSYGC5+D7vmMWgwTk4aq0vBLS25s!NAr*1&N&$Q>2N!xIw-3zaq0N9sR}pI3c~ z;pe>YZsjp;2)Y(v3egjfqHkduVG@*n&`lglUY0Uv*{aUVpN0%^sUViA$m4 zc%`Et?UH80Xft}_VYWsTGSVVPu40vTNzpb<9sY_7(9Dm5hq>sBR|9_VWp|qe*6>oe zEw~Nq29n;Q3668ZZiIsZU1QkJY6G|FMwC)7JE8Cm!OUa4)Z|O~(Bvx!Q7Yl-r<|5v zHYE(#D|;3=5U?|jm9G7lJT(qBMM)y5&oV6G6@2#zHsjSU1s&SLaTk}k*ymGXZND|n zCH{pDT?-kQ)CFp*xMe%ewr;w(K^wDapvad!LJz%ci|{Ue5H~y91Qer_Uofz4Iuxzr zncbObJG-!Vex$q2eiK?j7O01_uB6oVgwyl^J@q~fqW|3pzN%mdAU%yVq1T|g8RK-T z?m#PUK|5e+Mcqud%1Z-P1n-C1}1TBFBxRvP}sNxWtrr78`th8bR~g6TOf z&A3(jgr+~>ad&||R-C8fH~J){G3$AWzY6z^J9b#xRLlih^+s}dt#;>eWG;Dn2Hb|8 z?*E+C864tO<5uA;jilQOPYUCSVC$rweL$^0ILW@fE4l|J;_CJ1ezaY1HwH8GKM zBBo|^WXMPRv4VMfYcsfDpNV27_SpfzBs7mF!^FR_^9f$4r>iIWd)Xb)<95N(eF!v| zH21=%<8p6|cqde1L_K2lycg9ej!nU8B2ojF) zIEty4T`tle!E5Sa?8Ah{u z`jwcubV+5`85`Ssv9Pcdb8}1<%3VA=JDfOf>(Shbk6-fQN9Dhd*HiqxBd5F5WklY2 zAsOk?cmP2H6LpL?cDHjU;pD_neEn;$$He$VJX%_bNAt_7AN$^g)pe>d#=%xxoEVHN z)1%76o?w^Lh3-KgrRICk78aCsZ81JM;bSKeM9e>Y7$1N9QGERQC*G0q`m0}4{Tz*z zwN;n<^UvOjD_1TDM@jZ}_r|)?@#fp_#+})R%CDZ-S6Z=u{ngjw`ZKEQ9o^n-v9A2s z*xdKsL<@@RuF9iVc{epa9OEN>F)`2?mlW6W;a=s(R{X&q{bBszhd=T?UEluJw|zGq ztNj^6tgo$D$k#WZJXO7;{N8!*z4-W(&*JBP{<|8N-|*3e7OZN##snjiyx1|>&Lp`f zp;fOL*RYELVKm3PSs1y#;~fwPBDfEX@?mVku1yvKB6#W1*lSpIX>xohW+plLWkB^p zbwp*yWG&qncpB}*+=Kh^@X-+hKuPY^2(Ec#@k62-|2%G?<$_`nDcHm)ma2zgh$AviQ^#=ruV7e>+DJ%4Znv6yWWks zr+%=nTlHP>fcBBn$@p(!U-Tx$%s5!bHbFoVNEU zECe6=4k&E;RQfNDksTlI^D%MMNBa0J^+zY7$xb%z0;3A~jyL+RA^_?xyZE@%sY~X& z_wUEYpWb#IM<7I;7;m$Ck~^Dd*XwKR>NmE0wBsWLbcz9Yf-(1Se{Mnjk-}9T)9+h2 zqr4#PufO<0d`o={yJmLOZ*b3``yqw3p|-KCw%ps*tu&0r#hK|CQC~92QMe<+p1*pa zxXsPaxsGrYUM}`V7{O6KuIICM6?f&c!a?x7xU!~xXI*_wyZVUXn9?_d z9b}B%_w@Z_euX;SrEehW>Cr(f%{}sQc0&mL1_xtdbuHd}|C3nXQNJ`a=DO3aeC!DI zpQ9u3;`7h@&aof7^)Wz>==#Q7&*b=E%&33j2;D2=12Hu=7!%Wzo`>;~d3SEB zJ?wk;(aF(%9PJ^j+E=|;QaSg=^_$Pe(D=0HIM}h|{#V~i*EPm17ur>32k~fO*#c2z zQ49@nzZ|>E+C#NBKL7Z~@%CG9xu2yiA^0ON??0N4cR#t~ooXZMyRToq6wltgBEQ4Y z-qRB=zWAbeic88zj(0tZy`wxD_(b314i-`S2Df86;boN;2<%+L&s=TP^r81T$kx}zWQ^uiE zKyRI1nK`%=WRq)X1jR3}YL6lRwnMG7aZ58V^yrFPQC;|sH?EmSm@-1?qxwTF!KG~> zl@&;j%;ZRQ&oHDTk1H~Eg$O2xf!+q}N}htI{NRVJ5uE=ee+(_EiBx^l4sE`Rnp*1} zZ+9Tr*Z5T^c4z8`6s!0pE~)oJSfELporptF8rV|b6GOwpDS!~uf@@Ahpi4$F2fs>t zjfNidb`xV^0hm5MKI%{(aXM*sfWalPTFmso7cRhu%DZ*M*f5xasb%2CeM)?6clEI% zd{((J07WQ8etYKM&Q@Q5w0MGn_H(pc5zJnjd(@rNooq9ftIjGaq!0 zhl82P)tWg-V(^cD@`1XHJ9Ufnp{L$v{uUvk^dhM+SQW`&=TuB+cJgLmHHhsZuJT8o zfX}bBzIg>8<>O0f#L6bR&NG65wDD zsWO3$BR&nqlY&nWUeY#px|5-p8}?Wgx`w2ero=6w8O8XR#H?2zjx&nVYMexBLQ7b@ zTTMo6jf-CX#@W9O0fQhr{pr`xw+jA>Q-bZ4B0DRdq@&@Q@%F#r zA=7CZ@>6`LQ$fTHdWEFS)sRXJf%*xpOq&riKR~2!^t6v$_>SPwZiH6+mk0NZDgK)Q zona91E99n4`be@4QC1lr+cxZ|3sSM?NrVLB6vxIp<960A)x<11SCrz?2n*wdpXyPE zFMsn_f1BLPJ}1F?N3m(w?4O9QwGC*v6}9@Sswb@kt@J2go6g}@u$jNqM)|Zrt6lZm z>Zh8)qJFuC;73kPzfC;HrnpuApfy8DsDAC{r<$Ao8fvY#=!uJPn)t*mx&De=9AcK1vD`>5|iU&F+4nI!Pwa7P>e{=?yBDYUhz8O`3ld&!YCFGF=@@i z3To`Sy`YE-^LxDly|Y8SBW?qDH?g7Kb%UTO@AqH@Hxv5@(c9e?(_@1% zH98nWy$ZjbNpN=CbVfImkr%|%p6pxL#AB_m&U0ths)ZRG>C~?{9f|i| z+f?4Lv%`F=@&le(8N);#rz5yk(ysNue?A>@QA99g7#9 zy%{e)|6GiWjVTXLV^8BvPNE=vF4OJZ7#JLmtIs?WSFYcRE6>~#&0EU9%W-g|aM?+- z!)YZN7nDT^jBy#mawI>y3YiS2tT=kjcLs5vk;bo{;8t4h-My!@?t8aRm+CQfmU~@h zA3pL}3gHNM$>lNQNQi!36QvnQc9H#Ss1w_>2b zCq|ig)|j4$w!}^=1UZBY??M_Zpz=~%<(@E9ggPE$ z(Z4X4z(g?PyE2w!Cl^BS4W*AXas;XUa{Q?9yh~K(JevN%$6<0*9l|KWqjGvOS8-De zttZbBbd$fNk36m4AlGNcc{b)wF9d=1EFeCdIAVd9`-mOqV=ng1_%beJVJ2q!3k1=) zXBhNL94Fc3evdNr4lI=ed@V=&-TVAwPdTfNa|A0p29MR2NE3oX;>8ZsyAS4E&)HSNv4^*wxe?#^ z`s?w%@BK==_WB!YUzek;o1^wlV}1J|Hr1Ex>~o}R-Z!_xy@&F@s&=xry&pS=N{7NZ zJndAwzF?s-f-iQNv0L=!&1ZbX=ZMlaI6UNjoJG$+{NWFLzt*nm5a!!=Z%e%!_aEGk zk3Rlb&qs0R?%jAW`!F`t_O?{+d_zuD2RFBK_m7h1Hq+bJ8zZA5D&G#(`L^in?u$*u zZ%fn8I)wgc?;VN@QjZlE76db&0gu1E zt$L(#+EZY}%ey&MpAd2~kI;?~{-h(ePda1wv?n?TCgZ5BJ08w0#K)h09G~C0ACKmi zRhEZwd1lNz)TmoNZAlryoDRapEtSc=+4;CVyA-pFo3SCYcYZ3}or+sq&!CS;{PgoX z@zz`K#_a4|`CfMU+qbm1=*1`;=}0{zo_voE6mL~4_19`+!tYSMJZ|fB{n*|=R=qy4 zP;72)-p2~Ft8YW?W<~AzSb4mmw0HNZf6zCpcWBhR4zFIj9;@(5G3q9o7?FUP-vU8;R+~K_A*u;aq6r!^@ zg#{e+(j2k4vwy1Z=APQaf$F_@1Pu@APy2hjJL=kWUQ-3m z>oJ*^tWULX(N}2I17GB(Ui%4lUyTOl$0;=7%g{d$U*!Ii`~qJF=V^f7uj2bJ64n>N z)9CuB!{7R?|D6{E8>ro`_4X$*&5QRywzHSZb#eEpc=`=KP0SAA1$wf)uf%a z37#+!Sb?@Q&}K-HlQnX1e55mN>DB2uOu$5OlZ%Nosb{o`yUe&a?e>#+kainudP^wg zLf&SqoVnKcWz`c^X{iSVyVMe(`srL54Njp)yr7*sn$juVcwOz=OQ9@`~dv zxLA|pE6Go)4RNDRAoxO%$x1zrFyVMe%9ViycjZKR$4M%Dm5qJo1V`*>i*fE42{dTIeM=A74QLxj;t0 zIjM2fiFp_o1}hA@lq0#@OM^=;k?!u}$ej+i4+fR)CG^i@b7)V*S0$?ap==l&5g!X9 zMf(Db5_MaK$EVQ= zKe~p$h9CEg4zYF)p7eMBi52$gzu~8%lD~v!3I(Sq;AYOJ+5N0^;9?=K#YJz35ijd) zRWS>Oz#7@2f{xLUSS9M2wp#b?N3l?1?60^rzKKRrI3;{Sr2KuvUlK|r$T33z5b;Wz zFs-5PWE@&)`vomj=T(-b>Dft{j3*3OIu0o0784VgntTYt>D+bLxI~|)6hURjbbOLWtQ|&$D$nBE6}7>(jsSvTiQ<(zxdTZ)7F)n;mYoe=?18Rt+4e z*0`OACY`hDdHStz#!cEry8TWQ??yQ(UE*G%w{IjSXRgH9k45jmuInu%8p#@I355U~>xW-=6f=ciCe|nWhH)+v6Z<% z>8W!}Y;*jRk0IRBcuZrflM9`)KZ(VK#n{=}@O>{=FU>fO4`v^E{KYN=F57Px(>XHG z71yrLcqh`@=0VIaF30N1s^WhvessXRIJ=!bf3O(K>pLzV`lBkuU>tzp#sWz?p90`8 z35y^GKoGXfkU5m@>v9!Dq8yljhxVI^97_T5;I}(4szPT5xYnv*HSSXf+$KlzhCR6Mrg)~#nf$@|eK zAI10o^iM3<_$$BitMUAcue$xPP!HiU<2c{deB9}|TRi%NQhU*(U-u*>cSr8$A#FAZqQxn|hHWmYe{V9~O&`ouV`ggD!pMCU!cL=Sn zt+-yj^2*oZXTJR%(L40cGL8>}=Gw|qEHBN+!QM`cjf^PG*J5OJLUB8ewY81dQh9LC z9y_Mk0mk^1T_lXr_=fF?26cn_!UQl!RMK7<3nJj6j#1~D<6e!SL^~H}vJ-~|x0F{3 z^Jt^=1M-sJL&jc86YY&Yf;vWE9y02dod?%*ly~trE!~9 zxIjZ#sXohL(XT0uEHv)(ju&>25hvmEw4L~9%>j0I>}|!u+^ml+92uLo;A?Pj(7V4n zRA1SR!frU?h=7A5PPf?6r+$GnBKRUr2xEsl7ClyY8apZ&cD`{+3dg1%9&9Tw4?HeE zL?Cw3uD)P9x|J_eYUfiEL*8A+t{w!xE2=vW=a*w?WmEO;NVT3ZtMXUzMzEjXh+OPU z__Qte4XTsv>N|!Nhifxa-d#vP!;UVFbz5FiKccqq&f9PMzA$!XUcGW7PSj7cgNHh= z%=R3Ccl9XE+=a)vbPV zeL?uKraWF%`#e%VG^qHo!wX>pb%XENpxU~EbUN61#l2VTa9&;8^6pO`J$kSg{XHFC z)X}Frr(E)AJJnIzAa%icapHN6KH+w&y!TX>*H_nLOKpihjN={$)W007Ke(VU4(0Dq zaX+}w6&rgeF~73m-AuIe?alQ#+TY64ZdC7XUYm~ZeEVy0O>J#w?>Iiab3c|>)?Jqe z)t*%-G5g@5`t4QEb&L#hjlwncd6)EU?DjYL_;^3|)|cbXCqIszmF0Nlc@_*@_gn_T zxty2NcTsJrcW^j*)c5xEa@?l+L(x1?Jm?n@RFP)J2=DmG2a7h3_pV6OQ!h z8#L0det%5g`stXO8VQa%W>L*?TX!t2@5a(?{{C!c)c1tRo8PK}}oz*~^E>}S+JVZxCHD5&@q z*r8X2Uul-VqN1t&YPuJ?B@FXJ1#I6!JMj~$zM&R6@Q?D8cGBC9x>E3fRy}Yg%#x;7 z$he(_^EAGQKIX@%HsQ;L*$U^wXoW9wtMFxTo(4ZDJ?G&`>HEuor{$4%e0}eG?D!Ir zYOB*qr1daS(ufZZ{EK@U_#~%Z*hLQ%+wxMKN*BGHnbm(b4?n!IPfF<_O_*u^#t>j* zC22X%MlLSGR9fvsPoJoEvpa67OR!Zn>rEVrqbK*QPj|-yjV<-?ugEQNHjQG7E`K)I zjr?$NfC|AzBb0;V+{7=sYOvYD2V2v@$cFH+z|L_-Us7c~c7=xgI4}LDV-;Tl`1P6EonkzdcN~XtL1x0SSzl3nXCb6eht;!rF>(%I5q$Z9krf&% zav7krDhoyzpD?#D+AugEd7#NCfWPX6)1$bM6#Vt{FqrC5&4Dpe{ZM#4Vk#K~u&RjF zkLIJ_ zy2ap7&n)m#9c189&D*wQ2&sR4e&&Q5b#OwVp>T+N75+TUCMuquM5Idq~DFMS$i z?-UppGf{F%3JzdY;D&>uI|`4O0vlIF1^aYUNNLq;#pJDrxz-=1*HL4 zH}L&Ra8e7Tb@C!iHkfX4$gnHjOiPm=OUh|7dP5IXJy?z4q`^K(H2uE$_D^}o7x|mf z&;GGM&39D)TFj5BsZCrxOoU~*COpZH(|gVyu%3U5TdTgR{#CR4bu?#j(o%2w{xkNe z);egAby7{hg>rq8KdS}vY3>H;O@}^0_%+QLDzvS%`1QNg;X+6H6q28Z;x2GHWUT2) z)fP4bXW}Kdv*stkPjYVw&u@S*i}nfd1x{ZI&Xm`A_;V0%jsMfUH^THcp8loyk%GQH zt6|D)Lty6hQ&W6FyjYQvW%u5p(#Ek*H8R-eaTn#w@l&k)cb1danNg}QEP_jcCFR7fJJcp$;g|XQ{CK9`f=i7lm}K-$ zEOz#&POzGuJ8;-ZHP9m-U*SKRUySvQjTrJ|bgxO0=O@t_M;rjA{NfmXj%1vB_$VIE zK8j`T^-`X492NI|UAlBBk24z`_A!-=6EbE3#fdvvm^9tq-SZJ$+=-iIH>=lAZZ+#dLdLU!g24i3Bidg0#wq3R*VTx{f>MF^8s4vc|2I&#Mx z6Sh3=J4?BsR^HLyJ#aMkKu}3L^TIsRjh)=Q6T$*TJx8Z8I5H9A)0dTR*J6BpGKL0* zaz}>n$%n1&U5($>hSk=O4o{Q^2+!E%(B{cw1d{|#+!<5(WDz}#$NYHwrbqR~<5lX6 zadRAmxfN)S=YYP1cB=eC=t=s?3urU$LcnK1t@}-rwnAUR z9Ea(s%n`gXdC!hE^zKLG4oPB0J!kP{JvpT=#3XK{hcpsb?@pypGO%Mr?g*|GZ^oqv z#RfFqBfq;eZf2JvJ2TfewtWm5LQKZq9A!Av*QNT=Biaa(5rncBGs_dVF}mb!KO6V=6gG5g?-k2z$qC&Ju*wIli_@{1jd2qEaZ4%HspPj;j2U{ihAn);9M zy-5@7SBfF2~0o zeGqTH`DgLNAN*PT=!ZYF(ChZ?+seb9c=_d5O>5#^}_gnBY-+;U2Qdi75-a zE!02i#E7b{mVFfXBgZeSz^My8{0>`Jutj>Yt9FI^6Bo-q9P!7dnM=YJ*D1UL4Q&xAl%Y3!Ye@ zytScnU5%}cwK!GW275dG%^>}p-qXu*p##Iw-LL+7bTT-u@j`chbRjrX9VdS*XzXV` zsK*cd1AQWBqyU5~%Rh7xI`st{gB@JW1bBtKa%yS5)9>dff@BKM!<7x*$bPXqjZ72ki6u)YYMMwcC5?Z1NHi&kQwLSn!} zu`Hf>GpMxAR;Y)MvpwX zVdwNK-AAIm9&do-jjUC`! z^_h}$_Wl=p6u*cC8C>keRHTj!YtptG|5P#_1+#i}-nT+an2BQ~JE6}q!wrlUd;Kb$ zFp~-ls zaKT!dMorDXrJ#tGI$!f7L8Sl_P8m4`*rQKCHG@vIvjJOy6N``ri(I9~F>3j(Cogjq zEp^DpN(j$`jWQ@D4wSXS5e^y{1j-FJuZAg%uVnHuANV5%8Tx`V zkb?1tS>k+XcB19rLrlKPwoB#85q?|-%8EZGNw`bFOa=oW;wb-lzn8*sJ<3&eJnSyx zSPSek?dgxmQ@3D(d&NL`6_4r$0~wf?ZZS@TK{AOCZulh~2cicv#}S;APqynih%AGA zf$OdqC73hHgSNw66&#)6{!z>fLbjYZ$^7(7(OY)tJkgHM?unG|vnq5;b829@KSgb^PpYYRzW{wj zyxIdqr-4Zv`GH!^)|a~NxYM`DrrdM0@WX=q>MXXZIp&;co*5=y$u z?C%$-R`P3P6anGc$!=Mf9hS@)rp(}CFcJ>*p$!Cs>u>%|k9OsB8YS^?qxV3?G1Zz5 zo1~~M*r-=a8V!Wmpn^MpBd4wWI2szH+D88>5Oa>&EW{Q+#3I#vFgU#+W<*M`O+4O} zLggL&E^&5P*vO3uK#V2_uJq1hwOKHUGuXDbpTtcMIM`65VyJkZ0W;H&uK01kjdQD-&sjTb(tlC&J90KI`uJGu zFa_snP(Dq4GYn~p{v1B`1uyGK)82JeQ0pvDTIIK@H7vk-{w*|`kYOZFO<%#&lOdgh zR_}(#ES?Bw!Y}$K(tiTfGy|!V|1a?T<>=BrDrTygf2p>b4Or>1yDfmK!yys)rG1N= zd-`f_x;zGF(n00RCSSb3i(28b6sI*6^U)mUAgkJY7xSe$?4 z-5!ez^RcnIB%Gt@@8bx%9{Chswhw;ZN5uqRy~m3(g>NFV6fHdBfp{z*hc0&?X~x9S zK~7>b5uK~ISv$M$%yTT+ ze9SGa=Y3P#yRovi5sS+!^1m7j8bfiP%;q`*h)qw>JO9M1GX6?|$gy|5afi>y=&*Td zO1pnxFos8lop(&OT{u4UPKH78=Y2{GE7X|`XTp*0k7FLmhq_>k^fT#C*&Pv7CD^sc9y!ez2SGG`_4nhKc@@$`yVE#Mb(_gr>NXR@>>y-^1@#>+lcO2g zZ9|?T7-R<*$F|X?*=^&UMM{$&>Vm?h>=}bn_sC!B1G|?zwq!D!W8hR@Jlz9UxNVJ^;daM{{tO`tTGVc5`L;#zZv`1u`qc+x;fUgOLgh^a62|v7c`dLvXFs^ z@LjcC%8lJPjQhxU7Fx1Pk;TQtM}c~0=+NMR>o9%U9)fc3MmrGy#$9Qh7L;skvIAwy zyZ$%=k#g(m>PrE(%6EKx!g)-8!M)n#Nw4DKHmE!}I@nd;bvu6iej)AHDZ8^7 zE6WSeo0LZ+Ur1^>;;m(W-Zvax|px=6W<6AAb0Oo)2U8;j9JN z91}}b92p&rXKy|0olBJO>Z-miY6H|QcEBOvU)@x=8lI0$&BXN^w_s#r zGblZ6dU8VTx|e?EKylr6-9?bZf`;M#?wA}KR{I}}@e%c*L;W$-*Dv~c-xKW;At<{j zd-N^vy^ZeYs2|KF99vktsdlrgxNob!c(l41^J}}Yx~+D%f8;#ks6o=mjyD!VaDSG^ z4&?%dLv`a|wO+fcoxpVGLhvnSf=qxE$4DU9xZH6Z%;cGu&D#U=MQ zz^J|plozcG0j4?uWd+9zBV;Du=}U5shW@3aBab-t_lNeW@^N2I|0tC{ioVqg@)07d zp3}B17#DeP_*xR);n9WI-b0AEf}YkPESE$uv7!cX)h3@+Aj4C zdzwktJB67!XVn76xL_$;C3QkQ4PWFLY(;@+VRTV!n61*gdT{<_+rjt0J8)~`?>241^ zDAj17p!8Q9P1?{z|L+8!PNtnL_7+nTevO@@x%%_-2eE`ik z>N%2`RTkd)RTyFhpvz)z<}_et)eGU7fz`*<=h&AERO{-sWGEFCBBUpc<%gjF&Mn4& zJAtC$M;$0o%~)BWB2A`4ujHZemVT@$kAe1~NBPH&DugfiqwX;vrG3doIQ3WpxstEU zx!I5t4t%gZ7?zvGnPzD?&!@2td!y_qp(#QBn<>(JNM5q%QH1Y9A-~{8tfSLg$ z%v1-H0b<7465gi)9|A9Eo3S9yM1#0#5CVhmIwksq1q07O#1k9}=SWODgO!~8R{N4? z59}D6DIdH_P%48Yj=M1vM7}AWC|q96swoB$$446Ii9W}^FyJ#2~5f0F7Tw zzx^bjGa3CFbjy=8tg&mcYA_Q>!<(|pCX5ZfGAv%?NABoS`J;FR5T{cMMXbPac7^ z)wsyP_UIK3_O_FrIHAhjB6PxNm3F2g zzcc7f*f{oMRX_YDiv1Bberp~yUP7`RW<8l+!m>A;c(8DJnJC6W6C-p>oc(rP0oRxU z$KGxYE5RAs4YlA_L?a|^gEWppLHKD3zFz*uuZmAD20`n$o(V0--T5i|;$$;;HWz(E zRZA>pz%|?W3`oY1=TTU7C~5(;(ez zSdW{5rd^J0cw}451qF-7)0!Iec9t%a{diiR3J#JfVeVj5qYlEjeFSrw!F3xtJ{aMxV{q`Qg;s{jxN9}_l7bgwhvEYVQn{Nmp5X5bvriM zZFP7Y+)J{$yqrQrgo7L#xWmq*E%D|1S?|?3_~?11**q!fQ^n?}HFkNxr+4-ATEH?s zHWCx#qn`L}LulF4rF7&XH+WadBn1#0566o1ysN0QGX-3XGZ4fu4n)|%5pM`3xK|9} zkr$!K&EpICM+L}p=$p64ALU|t9q!);d)njKYZq02`Yeb!JW<_H1dfzu@}7FbV!9eG zLMax>a6H-g#8ixoBIFy5@$oUAa$=UM827E~)!RhjHiL9Uo^1Z+hv{OiWBn z#N@=Zj~u&sME3N7Qpq!aSEVO>w-cv31*jZ7*wL>1+ggdcpS>3k zZ-1clM+}aPdPmglPu`DpsY5FF@iBy{7a6KE+iR6BbAk7Dr_=E+#ML)nCmo zELxa8uYN|Y%4y+#wH2Ay*H*od0paJd#;sj_{V_Z;5o6=rIe0a$-MAUouRo*ueL1El zr@c#%V>_vnJ$(Z)GB)n}1vyrgc6wRuV0w}}1_yk7#=64b&PCVVwvIS%Q=RS}jDCeN zIzDBAb-VI;TR1G9UR+(5^F++tcs>S|w)XCR3sX){RX=)q)OH6f#JV&y7MG{T;^Op_ z;yUW^rY45s`n3ALL4ALYcB4(-t>K=wxQgA_fchC0dn3$`7#-=4DfI^($NRCffnaab z_r0B}jqLB{9Z<867URx?N3pW9ZlMqhD>~Zr#8I5Eb5L<+N3Vrxy9cqddlbvN$5PpG zcH%qSXxrQ5uW<8p8|KouUg6mFf&P}fp`z37nEOCz!jX6@>zfwJaR1xNDo2beO&Vl! z)a{h|ouLuc1@&S5>fif%`rJa8lS9ab0FHYVyZeS!o|C?wVr%~>whssk%#-M6hnDK1 zceAMx8(ArkNx4EMd%aI4mc>{RYodmmK0XR?jCQWg*O^r*j9IjV;?KEhuX zMGVhzvOvmH!80~ZB#{it7Jr7U9eNKsk?@`dPortU*Y|$;uX;caP6N#m&z}cV3~)WN&5Gs^w(V{3s|J!* z)m-rlT6J}+C}#c+Pq;Snk+5YxRd2QUL9&h?G7KyGLYMEfmEH)%q1cKB(|>6!J{-1m zjYzfN7kv{aZ5v+NB5@vA#-|@4-b})dP zRnPWiK7KwLkFY@zjhqZY@0w=+bo9m2KX>fv^nILw1t6@XNq5rA$Akf@S87THe3S)d z`GwKsXv3xDl~`O@@VVoTr#e)QVdMklqxxj#qvRt+M7lEi2oLz!J6^=HC{6iMbOGYb9mJdE7v&kfwPK<8{tZ0MgXRO!3P(SbN3Y!9sXbwCB=)a z^1Z5athCBY%oRW3!+5j8jFd32@a{o{i5WpyUH!{ogjJ6`zK_B2Bzzb}qCpzdj&v|k zVr3WUv)^ORm1n{ucY-m%VGzjfF(1__KMb-eqvN_JJ^4WS$i{V_)j*_|yurN@4*@Fz zonEI$Kk2Er6hfAX9;x_Ee>f3;%AoWW0?r5@)L;d{SC85R^wS5Fvd5_l3DRC+xL)uo zV6#Ip4)v-!n*wG%E^i|jJ;>-~h1SMmS2gqld3PZ3$bjk(R}|B?*+$b&V-we5B#IEy z9dfoyvh`(16hcosP!ckvv`>BdFBpY3c7&Nw@C5j?z0ne}pclK;RJZ0sZ1CHHFEFMI zO{_wr6hh+K#=43`|DI`A8nLTbjZ6~A-o}zis;U@x3FsG#wuFNlsN`D3!^Qb*eNly! zcA3LX7Zm$YoRSvSndWrI4!`)YIU{d8?5$RdGvZdiF8bj2KMR9j|+V~i#HT#`#7AfmPE48l(HExE-DV)#KG-r5Ef@%xiS)Z*y-9l~B zu(2hq8g4WEC&W#5xVCsRJUPxy$TCa7jr>P_9IvR3Z^K}7g$5*?~O8!O`3iGzTP9vB{qT}_^VQaSM5@`N&cs3+(TP1C%q+=&T# zhe?R=X!=nT93PDf5Moq;7k=sq1jG;CFDF!zZ$pUDKRD>|P-hprfmoo$!?8{phsdt8 zTfA&_+H8I@o#P zoomV~CPmqmg7DD-K;;p60RIoZC#sZrq}_M@is$B@H11sTB%tz%w%|*+a<5zp%I)gHh^!ou%l1u?C7)`<%fU+cgA%t zbIM+PHE!rx^yS4~iZ2uK(~}c1H8o*=oe9&`t$pQ}%2a&((7=ENR7@`C5ru@UI^rnj z1SLW^j&MW3+S`}+SdoW>eSzIzMM!j{yd*yy4=kuJN*i^SMWUlB^P!;um;Io^9ZY0e)qr_?({-f1`Wy&yBwz}f7M>O zCyAXcd6!@2CGD3o?`EN+(udHNitDke^2UoL6@Tv>RT@~hNq%8Z-jEa2g&ZH_hkmHp z7rBaw9(2hM=O20J{Oa`BlT&pD1_y%smIep%Xt%xXwfOAEZ^mcuzZpC0%Q2|_gt*?l z`+3~{^uyrJ^ojAw7$2XKJv+fVf_t#Z3-XfQ%z{UD3VDYelkSA8Jn2+=dk55)bjJRX z(t66c8=)YA3EDFCo^fb*^r+wS(Uy9;dipdrAB=gmuMa=F7oXpqjRy}GV`FTr8!p?rjU_4wRn$(Ww}oxE#F$Ls_p7Op6x%Hv*oKk>Qw}9QTe~>MeZ-dE2LY zI6Tnn;|Uq_b4(unH2ng*K-op6?iWeFX|ns3er{oTHE!Q~pl8;Cu19mrv9P4Rer;2I z{kjE*tE(%quQICRk$rUx3v#=Ce?IO%%0&ZjNRQgCGDi5%0^aNwPJ_Gg*ipQ=v}B=5m%cB3%2(!KC?f=j+>=Io zV!?sG%c|msN;E=l?^;v5=*ReS(%1I)tN+wDg6|JF^mho$EC5p+I3ks!IUgbby#Gk) zeH8Z}F2tjSrC3tFts$6O-|+FMsF;_Q*Srhx{_Mke@IcRf>F+;`*||9%lZ-%-JHosJ zT zN9g$*rgrEs@j{V0N5b)1MPSG7wHe7GSP zHZx&&EO8?cjG~7TYnvfg3E?0`FQ?16#jSyZn!1E^bIj2e6l`GaO#?UHW^_t6;8r>( z-Wd;Y(EDXI%Q5NXX9PEV5x<7VRDo(|sA|UDwCpB&P6lQ=w#0NCD_w_~b}-GXiWnIi zF=GakmiXYp_z6o|I(B1!D*^!fr2^De4u+fOaaarY(BxJY-;>S#&DD2WBRzmtI}W zL<`|6k8*Ity$!NwIa@&~+99u*Sb!zTai0YyM8OZ2H8Ne9JsQnYf*n12AVNVU?% zC3UG!a1>;KwlS=c&T(`M?4B=DmT?EnoECd%TlnUGy7ML<4AP`e@&m@U(k86L1(?XG zaZg+F19SF`yee)9uEbgH_NEtMH8PAi*0-Fb}$ zK(eMqm0#hKhK69u09Eki=3p8Q#zjb!`m<^yPD)?nJ0`kLLlQD%x>An@J#+#33=5%% zk12v!JPMLl(k7Sj>-0&boRW?;Y02ODk?szQmz}{adK^(?qzs*Y=%lsd#bYDZnE8oD z@u??coB)z+)Zm@N4pTbJMV|l_5Gw_lq$hnmX=9((C;f^E*tg%VM%CWsT700F!Rgmy z_m;HRcT&fMTZKv|?em=~;5h1)X#!8Km}RVf{K)R7ebgc8J`Yc_18iTSnkeL3s!xM# zJ7?iB`lff*&PMz?-^fkE0x{j62H;gNe$Cz|Kr8NfaGdS@MOa?|#9hkywEtvihDO@Y zLn}?YKP7Tc@cI-;0yQk^W-FYJ!%sFBO@Rj8hQs;vsRc-}UQVbDKYk}P?OPw9>A%{v zIHgkjrhg#o)mgiWSM;eEDjqR!!S(}wD~$@(PwUfwRy$PFDdrZyKC>&^Ky_xqZtq|> z)>fBdb#2LafpBaVJBmg|$6{b$5HFsD_l_kd&^)0f-VELn{ue$@0AJ=wYly2uD#1A} zb&}l+{-k0@Yk&vzT^{g$NA;eM;!%$$r^SEv4|3%DaCG;uWaKHi0eMemkaT3U+DwKb*V zRQx6j);h#9=R_RB2oqJFvN(++*8E+N4Z@0U7Oe>fKAf)1yM-tteIF?^CTSUGvg-vh z@VxN)FsQ@<@OX|=^EWolj6V?GAjss-v1#S~z(8NDZ0^PE+-l6P?)VNQ?jjoFjHdLF|_&$qAi?QalpbVY~7dHuaz zJ_3y+s=B+{qgP{vp@H5Q8SeKEgw76)EtJPhWbQMeEt=##lk4MSWAfkU-F|bA9;jS8 zVtjPSZj|TF&c1hSaI9T-uj+}?zP`$FaqDsU^3}L}<+^b8Vt#Sncj4`;%%R<>F&@G? zCYzZw&BchMk+Bq$s3}0EeUUCEs(qA~RD`DB(1yq>9`Dpsd6Hi5&Qf`ID_!2*p}ItU z;O-uTb3JN52tuiEKFUz}!MGDMdF>rzidzcc$Y&LW>KOHldPEv6^ddaQf_j)>hW6lK zpLcNN{eB3(h!e-qrI4#%bpat5ei+AM$I+G^U-qXkyIVp^ylNShQ**(?S)$2QpIQDdnV@x-<^5{Q}S2-SY zb89Eo*0-eYtFKkvJ&f4iJBpQ!9Umdbjvpr0y-Suy<tYkCwJ#eOvWI3_SO0UB7-KE?vChezJF9B>IOZVt8!Ig1PbW@#t54nHS)wOLjkP zt}n;@+-%Iw-c|pOyR7t~>rc>Z?bmuSWO4sM^AS+Pz9>e^X^g zAD{Q$)j9@nC)DiRl7&;Gn?)Jja;I!KvFXecHOr z50}>B(ej4!dRuv~zT{YKNAYJN#faKEN6B&|;4oK;NJVxwx3UwT&#uPZxwTkRI2_N4 z@Nsx_Bzje65O{5>&2zln_U4AF81*oPH3-yQY2B46O&!b=ox09e}9P}dN!Fi+xd zvG5SUl27bPT3+3VHGPLH&{ADSh-blbY11qOq3#Wd*5vr8+dDgvXv5&rry%$mU`JJV z=I6HZVoi0F;}Y4uMgL11BHuYqkwqIjs*@ajO5d1iNg>`53pZH6p}NeR;KtUb%4b90 zJ)ZU0-pTu}_^y+1*IC7dvf9}@j4eI;>_$_+xFy_ejsx9=9y?U^T~xov0%_(>=x^KA zk6~xQpy-fC`OTqCyAyDK=*2g+lOP}QuWuNOwdv#N8?bXfq5P+xV2+7zHV;P@(x3Pw zEzxJr2;o;AQJHsj5#GMqAx9>1bnvdyu`9j#6n2{(?TZ3)fWqV@e23XEV^t{GzUtkp zwV2PkrM}Q=b?4u}Yr%O;-^8oXYJME2(k~A-Qd{xR`6+h5)AYc3b1R(p_eFF7;}rdQ zcpCoG;Lq#U3SSoQNr2z4>iaJe-qYY|G;_xncYKvei-uqcJqoHl)9}*G6Gi9?(C8A6 zX(MaZP|}W0r~Zt_CtfOM{_@1X;1_eDZD0Q0S8DmPN^}7X(sP#(2D=%GuHZZBP6ujn zbySKU(x1)(5KJ_~ao%7H0ujPsheBA|hMLxZY13h$w_R~ClyD8LdV#!TTxBn%F{viN zK7Z9r4qMmqq`me2X9raC%*hhXjFVjwjEgC4nCNT`JKc#~8jS0IQJn|Hz2*m)sQ*9e z{)9`C+{p6;5$@sleaD@dBr|zd70IsInclbW?d$65p0C9ZH`CLzRb9N3$;^z%IQ>4% z-OT(B_x=C=0;sB)n@2>FeAzW(rV2nH5C~2MAPT4>%?Ra`dh*6#ivc-9xU=aQbL#XcZ(T}GPkwZf2KrZLJvSwv0nX{kx#HDC zOoK}DiNPfUZPGzyUkg*mTb=N@rZj^KxUC40=jJl?2(O5eT z&USl;#dQ~J<+7zmPQ0Bjfe5BKP&^m0$-gjy(lq{uw{78HaCXU3?7b9{B?2~Z`7S(B zVTUA>RhA-aga}%P!EnN4vr*+%(2B713C;9#75@mBdDtDmhq7~ZszL6GO|x)azp@`_ z(}gSrA}=GfZQRt>qudEETLctq>ODldFmf78QVV^!jWER6BnOjx_AX(J%)zrGqYNgg zBM4J}%SqkS&;4U~3h=jQ*mL260m7xb{^dDtKcfo2TwdUc@G=UILLW-BIzQ<(oqqpt z;ik<8ZNw1aBP0>XVH)Ve9sO1gqlA+0QLGS)KlscKfM3Xv<+sUQJjo+@I<5@lU6nwVn&{Pr#rs#H@*Om0Wg~~XB^P9*HCZ@mD5r2kx6<$+H63HqvDzK0;uDG3VSvS z`aRH$U$-9K{ZQl>2o4(l@1W{|x{r)#qdvVSo*NK#ryo34z|{l^?QU?4_8ZEUCAgSK~Som^a{uEwheM=VxfB)<8? z!nBnl8Z(ZwFi(7n>)z^W+8nW3Z#92ezcg_BJDn0s&xAL;O%L>J>@#^;cEUMxBwy2D(5lm>Qw zA-{K3Ehx`5hv9fIzFWj1F8PE4W_p5MLZN&+=Os%PV383;jO(Q0qCQ-nyLuuYi;jnF zPAs{WY@^P%bJ3isoY+xDIdNnm*~&tw7g5EFc?-vIvVe@zmboh50GnWObvPDiS(xSG z3B#O%T^Vz;(`j*GA+2w0q_4mF%H_!JB^Jkd!4722J%$L}K1`qF8P`jYsGY(+7;5x2!#^NsdNuNO3*a||XS`Yao`6zc3SCkFk z1LFI97n*~e9k&(lwHJ?vG)v_e!nx_mG&eKlU0JyO{VtV*=S-q7|lTmN{5~1gEs!PUYAG?VstIn>`5Q+k=VQU`oYs@$=2jeJtu(dGV*u;7{Bigs*N z?Fa>%=C#ayQFbxMWr3U>UL3FI-F%~2(aU)5>M|X-chk
    UdzAJrW1(MLZ>KltHK z)02-rNvroBrn!aHG(I_JrNPe5z7^B0R?FXm;&dDq_L&b;Uyi%HT)+`=E$=!xYMK}xaX91vv^^zAc4P0VM>-_@M||Tz#14R~{;z^C^v}&$$yv)A4P2 ze-lsnLLSrB_S+{`p0FEjW_DI>WhTwfOr}{BEh=B{0#uogPR^!@>BTg+axaa|EUF;+ z)>A0BF3yhCCvPiFr|IOJm#j}DlhQ1CX*X>Yhn-N6P$DQJsE_Q_;%L58zkeEYZLdST zy+}jqTPN<`NsH7cc81}nyrbQ)8+37TAw7C>qaBC-6e>i0UXuukyU1ZnX~f)Aq)C+TY#wF?Xepq(AntdotZ-c+}C!#b05Ey(5{U zTp!%O?_GuE1#_OG>V~59 z^Mba+(T?OJS17Rb?1F%N4MA+ueqv`9>zpW}SX)y2r+g$6eM+oB(Uv$KmX|Ls6(1+| zOev34U(}zol*#uhCsgk_J{2X`iQ3VL%EP-Z)eo{ZN`HTO&Q7n~k1L(XLY|bq%Y9LW z&t}Gj+3T+Dg-7nsjFYKWy_;72`C!FInjZFC254SoD2AI&9SKLiTIGg;rL1!n;EhsBLdxt&W0c_xHlNn(^ zsPS4*LCRE%^)_P`Ge^btOX*01mZo9S$o zI1SL^WgKqdjnkw?4;u!93z|gm7J~@|9+YKQn1Q#Uj@ek*c^IJVI@LhOABWb1 zkcTLW1HY}QPM-(qrA%)Z_TWnw52hNFyLS`RB4mZg_xK`lmH$ zUR+p8lj9Rk2NDIR$bZM9D--}Yac>8TpLvC}zTxG__{(9L%|R}Q$acV-g4TR+$jEM&i`=-i51CTv$Ao7*ATGD06-ZhIrI6W%o=*GY) zjOtlDHMoSMtT5enp&|}p@FIlM2`<+!K=mr}ILoJiIctn@IJ=5H3fim!Z7eB?`Vmw{ zbIBtP`=Y%`%rBQ!V+(n?rerlB1|6ReAgB!qQ71wtN$FsCUy zOF%~py-guYxJ(e_*{--PCn1zIVb9^fL2Z zG)~scqu7a`myRIE%ihfdI^O_u&$is>gDIo}2g{egpC^mcnEh&{mu>>e;k(@N^`l?> zr%LfvplXMMKwkJ4nlNsscUH(7vkEhaeh|ty-Aa6YG_?%99zFc=bL7R@3{$Q?ke_+j zJN%NsRhVLe%Xs>Pj4M#{9drSMa5a?hg?~SN z8K1jzpwICmCx_9GIt3-;8+MtrJMGkJ9i;YA%WvlM{i5j^j$WEdV-qZrv1@{tvqroK z=P{$kR-9bGA~L&9P1_lkU7dOW!>GI{nMP{7d@s>GO2ZJx%9n zB%R+GO=njc6Az81w?iB^cAbtduG0Ax3I_?Naq;NHc$!;WNUQhm>00&oqgWW@+b=uY z8|h$o+eajxpNQw#iR=gIV1LKBj`Hrf&ByQ0tcZy@Umh_~*Leym4hn-Ybs1aB)BeoQ zC{8axDlf|pV?iI}7L;maI=3D&aMN=iu3$7>_P&TmO&m!yisASX}haF8k@w+GNg5k~mqntt>9-}J+TGbqJ6ms3S9Nl3X42nE;<(EZr5Pm{3+c3d&*8+1U0+tvR*B>Q2?~C|=j= zJXnlstGsbvV3bY2u!tO4Vdh16_dzHCqo1IzTS3O6z5Lh_!#A`hr)GTgDP=M}J8LBX zyU;?}g<_c_QpXrn`FKe$w5u($>vebIWqR}MOQ+@jlkcS;|J{E`_aA?(K5$m?t8W>Z z@bP-==IXY)O7Er1(mQDwqbcp46Z4`mb+USyGg(nEr8Yu4p}kSQUJoE&B4eVxTIq#i zsH5`TOMBZpR=(ioctY}*vOytr)ILc&EskA1P3@D5bfNGlb2wTQW+_fR6U-W zT}TtNi)nm%Spv;?_tc@WJ5qPdmwuHw35xkk@#EWL#6!PJ+e67m6=FB1cN|@?PLZtCEuZ?J z{qF1?y4~^8FW)zu5ME-Y>+|C@nl96%(l@X2ot@G1Nn`JE)rWb>$un$mekwg&TS#lG zOKNw+?tj>o$5FMrs?!|LNo=V#N(@}ia2-g$dRbvP??sT{+qKeP+l6>WthLTN*k zAG@nC$us&n6m3iMlj#RfR(zx{>xMoqRP~27Kf+C`58)eD@JIQ1pnAd%#e+ljb>c@~ zN#@>3yPJJ(Fb$UrF?OW{{IU_%!?p|JzC%h)k94G>mHAcSx zz&eV;vvW0`Q`CK4mJdZ4iYe+7vbjk}rg$+Kg1eCEKim#$vBmMMq<=ccjf^iS& znNR)Zs;892McO8`FtAtl~sWSse#9^$wntSBp)1L%;P zua-5_6INHq3@Y&8_=Ve;pfykI{1uPg$Xxhl9@$PfWHyl3$m}o~TciD!ne65vBI_UtVwr7NOf!H3Pb)n< z7<4kwy3j+LK?QFxfxFbhgf|&@DDeVd6FPh*R}7q> zecUXO(z+Aw>=bSY#LZ3wW@` z3J)^MpY$V_Cv=V{?BpARVdQf?hF$~usmbZIys)f+Q!E&`P0A~l(QzPvtS&IQv)z1b z7Z3oUWWgG~0P)D4ozUYC&j=fo;9wod9NHe4o9w~44ncdx6%@KmQ`@m&RBW@`R)JaD zqN^YcLS!7J>99R=z$bp-jgxn?OUUFI!cnrp`5OXdeuA7IAycFYpYRJ?;A#kdU^6e@ zp|xaTH%*w)#KOlof>KAoWrTk@K4^oJ5gAX9lIcqQ5YV0qEqB1(P4+kBxSatxPFsay z@yTBLRr2drLK8QG^zhLYnHZi%L7bWCA=C7tmDuS55{DAEe-THdCv!J(hD;DB-R)V@ zh^%#baTnjP0dfU0z;;4qdjS!JqD%DhEOvl<7Tr){t#b;qmt8=Fw@($8{D`nPBA)O- zUmcU4%$MLnR&#P2CmeX}y?Fp0;=(pOL1_trHJudLQe(#gZX(%MnI&;H$6W+lq2YnxuzGV;;pJu+k zA2Kb0E7pN)_G5z}{Gq)WpTm^!4VioFzSs2{zuGt4&HQhMCG;S^x0P4$$_|0slW^rS zG}zzp6V&dTeL<5BXoi)|#7!JfyAiD517|ejhd|aKg#EEr;Q?cO#fuVy^P!@HhOp(z z6j zSK}Ko@M7F|so~&R8Xp}_vy)?TU-`6(m#^2;({J9Sjonsydq=!SCzB>Ik|)NXl;~rTozt-6Eu(hAwyndBlJ%8@q3f=Be9#fzCNW+tpPQ3KR zcv$0JjeZqF&evQdW$aGgFcuEwSF{E1q#+z*W(Ka#vLP>AYk=y-eokT_KX~pO9ku;Z zB5S9!nkO#K&!h>ZpD`*5Oy+ltt2Ny9B6&Gdin!S2!y-S&>aobkc$zUTGO-hfh0bOf zm*e7CkfofxyN|_6p2P+zT?Cq_4q`5E1A4;{(1DLvR8hw3xks_Hr~8S2YXxcAM(p{ z?0Q1k#rz9p=FAjzQ~0bL@w{3Y#)38JA)lBZonNp(PreDyy?RdfU+Vfe}P3kNBD0}9uCu+Cs zg7QN4^+np-c%Hue!*A68ZFu+6{YM|Cdk-J`dseDhse5v+d}ycry_RLCov_>0J6^?` z9XaGB`QY6vs!ss(T6UkYQ_9EdsV!5tW9OabvyzE<>X_ONv}6EBusOd~fBmg?)j6*R zhz_Nn2zNo=*xd>ypA-VsEZp%6fU z&bJ5;5B5|p=jpEc&5O4~sdK71u)C({(CFW;@4Pi%c4KYqw9>1MJ++nnw6%X^StOPf zzcXm4#FJ+VyWB=br)1Li4f(mkQK_si(MR&qE4ygtXQzDe?LWR7c1QJWUgi5>QT-h| zbJWG8tBcfDog}V9cI_%1D1hAeDSwa?g%9-*CI7iH${aq`*2X=VW zQ5!mSzq+@#pIQe;?vFakpLY8wovK~&JR|SD`_#%B^_{w?tCS=CBW)P~$GX9#Dm-~h zTRcBif2Oe1Uq9>Eb)|a4MF#@E5|%ndeLxX+qPB~&>PTrs@kP5i7O(58^Ymb4Ha&TC z&qui`xr(1ULHiCRKfCbQElK?kr5eX=s{C6yok};~O+yjJivm7sQ~3om^HTdSig(&y zkIObJU5xu6jw4Hc1up@3}l5ZH&jyMsC z-GSq2N%d<)eLpV%piJJ?vxTD|DK`{fyx8*g@=WzqbwRx0k9@R;SQkg$9B;PYG)uU5 z`C-dA{+R}7(iOLVnE7f#ldi|qRnib36FazqDYO+$K-2v$zkcWs_bxtwX|lZ^ZlfOr zx8a-cx1zZX2>WeA|26U52DkCdim(6jD^ZAw&RAGaSoq~-L)=bCn8E~kW(uC>X18(C zC~UVi@VTuNUs;NcfpQLyFSMY!*&eupG6R$9W(2$o4W7C%z-L}OAdM-!n|FFJS(Ho& zf-eaFv4aMW#f$|xZ*apC`EhfPAOg}w??~8;FIpY`#(~V2-QgekQE1^R69I*De&FU# zc*_*-h(^DH!s5KaH}i2Ah%2JXFyJr05Dhzjg_PC#Ynf*%fu)b7LZ`P>a~5 zPx9m09}jd5PM9>7`oY79HyfR|+C$g z$>%q}H0Yk1^pF>@4N3@Vs(F&O7)3?>cd z3|JHg1N}JGg^3i2ypF*KgA(D$E8eDI;$vAAM+_X5ZqZOHQO<(%QWMNpF;HCL~W3mr+9GG6$#| zK=8<1GY>Z_?C=F`PbkAy^OtFq{9MM^3w@Aa53a>5VRg&#)ev_0I4)$g%#?~kW|_f2 z%e}%Ov?&F-qL)~M61y(>1#e`ADxl`WEyCGw7zgtWlx4xocYFA6ocZ98>4Z2ogJTXN z|0#UxEIi|eS$G#z@h1$!^Z-w8%#6OjqS8Hbi=F8PJjmgk$>DE0^TQ=-Sxf!{|1%U{1zZ+=P|Am^lnM}}!t~(>Lgw2W zKHD2XZ^kcoMDSj4ohk8PI4`__Qkse0JwS3}e}`xo*1Nb8`Y zy^T!|KooU9;%(&1Kn67q`jDtVZ#gv6(VwQ;UF7Vgt^6@+ufSJf1DHh^o!x+WV20D+ zu#IOBP{otM;f!lu;G2Fm;3CDn*Z|{h@anySr)-VOU=z-Td%jE%VvdC#SqX$3itYzKb$FH|rw?XJk%Jb9CC6<{o^PYShOPopcV< z^QT{@*RNlvz1`jP=JlKO{MCBeX?4=c<#2jCta%EH(e9fCy3vP3{bKjcxa8pbD|6l% zf|7v~F_;S-9vq~dt*x}R@kaTul{)RV(tNJaJfW$V@QFN8E-D_z>UCMf^9Bf9n2bSH zc{Dd*3=ARiFvf&W;Wc!JZ^y*9mr?jIZl6=WF0rdf^RKSP-rbW^zirR%3%+lK(uN&- zEY=d=IlEVOx2z1|s5|CgEGTl!AdB`aprZUTPV+xxU6_80=Wlx~jsy1pJ( zJ(%#^g_qbkVi1KVaxrcff#(OL;aKwyc5a-XGvSQgX~fC*!zRW!>TbllwHV`)kH;s> zk5L{le~S5l7phsjRXpq(Vo~$_w3F^iOy(k+J3DE8b1SW{Z&JNX?JHUJ%9Ezy?pUZ zJTymQ&USvL7-+NXdSK2M%1p{1*-+YW5#{Iz3;HS_x&5s_wF@hFna8Q0;5*DHy;whB zcT22AP)wx4)xmuPa))2^9jrriRWDKOFrP$`#vGNjc|NH)2oolY;L(0?v3%4q zEA>=X=SnLtFz@Z}r;Uw`w7H=^Y)gIP#&&wOv6D7;57U0DtvV;ZlGlCr%ye2(8=f4y zn_7E&O5=gr*L>|~l8A4#Lb zs)Ol5yoS??`ns`U@w;TllKRFwBk7=hW~JMktsU?Fq?}Qt94h~I4q9oSouQqxw0C%H zWjWtoBORU2sp<~TfqF6$yOIuZYqmD~<`ux~cIIcQD|JDTcCu+PXEZJE} zMWr7iZ(Wh}r#|qq1d4s~4h1Fhqr#zGQnu73uOkRJqLL#@+1(~?N*4;uBd>=bFE6Rn zS1ry?rAH4}((Lr8<@C{!XBP^~_xL8gLoU7%cGvBMH4fxQAxL^TauUTCyXj(`FxGBp zx2|uJ$7?34!zjU6C!zoJvp{a*@fwV95Bd#=FsM+%WYHg z@C=|op}j|c5wl_Bh&7y$$1=c|?pxu@jx@k0S((2sW7Oy9j*B11vo6feq?N^aE5L}G zwJZ7;>fg-FgvxA4`Eu?Zfo;_j#ylJ=%S%B??b>TelEEWh=LhYan2Kz0!)uUv8%^*G zJ3J$8H))%0`7?6OG#*6ZiZtNewj zCK>S4&&cAJLjXb>- zU}wNfXAS{_x>-&1c!QFOgpZ*U-W_?C13u-=z|2q`bG+HY02D0mA9%h*6Q@Y6ov(QP#Wx=!q@^4HhaGkSPpDdBoeil1u#J4Yc^q0f}%OLt*5kaAPn> zKN*wJA{S}#gh_)9E2pZCAqGpXw{qdnn@*k(2*I0helrY38X=Sq9+>4ftk`+RM53#K z+*^MTJL)czHs=xbnEX*b4)LaN$t&k|uH(W{CJfFT2|&K%lpp@OXS^mx<5PYMbb4}H zlP7lCSu+30gVKiuv#2lJsXU%<^SdKy9<)y+IL44VSyWf-@#U2Jafkvl1J$^jW!wFfL5W zuGj_U9rP7s98l0DKe(0r2tclIm`4s^RAin}ICByW3=7>0tA5aA3qyM=Tm*$T7~7!E zww&%Pbio!N9=s~H_NpwhMIP1l3O`fZif_0YxEz<`!LAETU>zt3ivfw9;ed{&kOLIX zzQP`|ggtx;-ts7Lkt2S16>5jhY33L8(IN-Z6x4;Nr^O|}Uw_pKWBJ1!vRr(I!iK)o zI5USwcH0({BZszs6H2(u7eXBT!DauL#Ia~aKZ3iC*9%tARQGUW7F+n?(#1b}INdn- z%MO})m%W9P1acr-T|ZL#^>?iJqMU&!#ejlqLh<+WpoEdp#1|;fxjMB01Npua7v)VX zgP@jUu)jRA-#~r`$csK9JgP_4)@~O_74*)8MfJtpYJnIS+S&Yl#G~?|D zhs@!7_*B-Yhure8#upRvaO1039iZ4Ho7|?;RYSNSt?9#F$DN$N z&N-aNG4KO}Efze2BJ)?hXHJ1~1Z7I=U^jI;hw0+tR9-Po0~kBeL>Q0ydnPP;PS1GP z6vwsmeH9i}89OqcVONX43o6%j>&VHZX9Yej%^FC#Er9^w;!3 zBvVfn#-kc*^L;M9$HUQ9t^NIUdEZd(W~I$^%Uf;Ea&j=o~Y)aQTvJ*>v#*FH{dYjZsv9qgs^ z)2{O5TKPBP-CsVU((R79m*)6+p6~B=%gt^e=ieRDp|-cUthO_gwzjs@(=Wde|5u)~ zpcQz@jaLPob#z7y zA1ELe*Zqwk)gkHxvb*hZX)wd$H1&<072fHA;!HAmy@G{knaJZKQ)#!DxqXn~o~x?P zQ%KB1Pfk%N#Bp_Z?viJ-D!WN5w(NIuqIghtp&X0dnao*vIh8&M<;=#5uhP@c|3|ty zYb$w@e_Zu%Vm93!pV8oM!bjt=>y7YnR2^+M=IS(BUJMO6l?M{UZAWDu$E-y@ArCU3 z@H#v^R3F1j1syB6z;l#g_vkRS<;NmBYc}Ku9SHoy$aNV-8~v!iT{gvWv>cllN*VI4 z?LMI8V?(>0ZYXt5RA(eN<8jI^cKr>jE>F0P^35aUV@Dgir@HD(j!+V*pYV&(;u~co zc~pid8d#yY$a%pFptEx`X?1BKt*y*!PJER*?L);irv7+1U8GU*NLJLci`6@MRkxl0 zs+a7*SzDY=50_`sy`>rN>_U%(LKEdE%9)nh&Ms-P^5`m^UEWDM`+T#p?Ojmx)f|~f zpQ=n!T6wn7w+zegEFCFdQC_lJ5@j>}6we|0Gsf7|adzqXg$~M;9gVIhu#2@3JY0`4 zArj!vS_JI@1*pT)!w9cp=darxE3MjU^Xx36{9WGc8diHdyEt<{2oLJF`&G(U7kwQx zrd2yWRo~9BiyURRwz80x=h@9Ur1CyWn_IhS|48*lX`@dniZ9we>pQ%-&dyR^Ua%5R zc|`rfqz~apOV?rLTkM`=Jt^8tS*r?v(yV%j@=Iw$Zg#KHFZ$&e$?Tn@!+~>N2%I;H zkC)`5UkIMGd7fwV2gDV-prc=LHtNQ67Ylg{Bl;5B6>DardN#xwQ}jddi*+*56IfTw zqgZDp-}vs@vUentmu-z7P?(ly847VL8PyJsmGA7@V+VDa=UFE1@FiAmvR(UychO`& zQ(=n0e%sK0O?&5keLl#4gAF8pw2pv*&r$sHe1 zz0|-4x%dIRO@(rShbjXm-r$Niu9#dZKFNgg!*9DVan%3;B@4mh?X?)tTDii^LcqhP zJj^0#%4f;%2N@MGqW<>_$XCf2<$^P3yUH+^M9#-pcpU9I!2Wj`Au0fd2xNy9}i8QhLZM#TVcAQXJyTV3Q+K7^uO|gC>~{pUZ}H@jbA! zuIjz=7M?CQWeNi`4sjc|@j%q2fRCnMvART)?un4Ou^ zgn>!0+JuRbMpiSH98?-x6%L%3I6m0P?Hfd#{%!nc!H|th1@xQbA(w0!V(5J-C}Vu(+Dz$pfZoz0~VE^?m>f9_DlxCJ_=j%C(y)$ zJ8%&?U;K>@I}mbbKfD56+ri61IQT~Xg2M!fL7eib0^^pM!#SIDsfIUbm{?^izlu-9 z3yynn5nWN_7-Y8yeNaL~FuClwOX!k+U z6F8fY22GV`6^I5N8AWu33;d!#flo6`?IJH7ixGj1u-vlDa=GqhHqoB&#vk7jBB;Zu z{-M}2RC!=qfcfg@&^ZG8i7a!g?)ca)0@ow63Qm5G(~sFDI(Nvzl>m0(a3I@#m$Q}z zzP=YS(}Z{7k!>c#CLYjb*}qH0*N=W)f8&d?XqtfS{0I1j_}qH&O^EP0&vEBG=%LTn zn><7CzeeFJ5eV-(H1=;3=S$g9W=#H73l?+7a(Y={9}NqImeUxubT>`>?D zSa9m2DOUs6BW={nfTkT+4ZS>xv$$p2uVI#pL5y(Cu!cc zS?mQWzx?yxZd+9yOWU_ceL*d=gmwR0+!d}7H@|Ez5bo?KAUAmWAhUp=pD4SVSd*4Z z{(f%B(Yy*2IjYOpQdYS2^UI4-U&_U^4TCwv<@vG3SBL4i!}piEl_JPIWKcU9YcjTD z?8+h_i)-_-fZInw*|U3-h91oKMqJ6L1#eE6q=i zQ>(S-xH&G0W2f4OEiVqUD9ku+TH~j8WN_=sGfyT}XL;B%ic~tHmbCNgud7PVlxP#*deYE#z^Nd;Ts|%<8Zr`QY68BRKce`Md@MwxbQl}u z6bh7YEZlPZ8459t;}s`kcOS!^$MC#?Z$*j9oNQ*1l_S>po)3P^eUXVpf2OGHDQ9t# z`Rf@A`dQgSI#Bi};it&5g9RxtTiMcG}(B zOZ)qKR$g#48pBHu1fyXl)}U#2&&pQ|)E;*H%tDV<8rOSQMLiRm;uzvLZzPtyF{Y?_&zNb@r)W7RR*1H0>(zfsq&)Fx;vipaYlQAQ#oJBrw~ zgyMqTBUW07Kjj1u(nr0ZZQ)mB=7mLnznS{10Wiue%FIejw+-q`na@!Nq76~!%D3wP z+A9}3W=_>UL#d_yNW4%6Pbj^U({q~6jVLcp)vk}dJ2H04go2HA5-JMuP_H@G@-FxzbG&#GRPR_2?@3C8smpvm7*fr>52?b>bEOm-ZpiMg^ z$`k6N7ygwt%Faqhl+K#p`UO(zzAk^G2*t*6$Mb9Yt57yjf0ak#2@iJn(RZ>IL)kE& z4c;90kMa`b0Y{uhUx%FRJRDPd;<(hwNnSc&HzB(O$3po;9Z|Ub19o?HtRzFxMaek4 z;$Zy;g#q72Vn-Ko)Bae)Agz=)?QVARZkn4?T~fbuc+^ejS0ky_xlsF1AEy3>GN%5} zzp&eEbaW`qPLHM4#hJ7+H=bt4#7o&abbT59ugVJr*M8?LZFBV8x$2Jki3@dj2S+DX zq|+xYEiI*$wUxBIx}tWqApYzi9;Z0f7ph-ux6^^z>z>*xiYNLz>J@z!Wp}3fa-#M| zzLA;nLImq*l9{}xoq<#Np&+CjX)p9K48Wu2#*52dn`TRtvYxk}5vlD5Ox}bW0q`vjd=6>4V z*|&m_*!eyu&tuAQOm&{`xT8=N$mlInW2UG=1* zC*8Dp)>z<2oA)zCS;H=N^-CZ2w$r$7Q{gw3if%-|w%`U*rtt~6x=x-P1 z)OV`Qh+#TZ-`_quaNVUlGB=A%>M?z{8;@{@zwyeY@RzOf>!m9^xJrG)*-IDxHLl;U zHi6sxxYu;SgKP;o0*fW2Zqf!c-Ti*RARN#i?nC$t=5#xKKMcYRf)AnlP+o(8u-`WH zUlZSLa2wA`@x_vsX%JW@lOh(aoB+9dg4;ng!JjH5GunW|VR5qccV&`07CtkbZT4`( zGGPu^+@2d5Cnv2M(>!u$CO?vyyY1OOwB*?N>qi(}(IFsTc-t4*`DYv#c5p>zL-u45 zEck&mQJ5wOL%#m;54qKO*c~|Rg*PNdn?|6--n|AUsessbL@`4$$yGW-B*} zE*@gM9l`*Y`r@|$<>xnpB!^|8ESzW_NLMk~lgXgW4@=wOuFFp|r7`CnwX#zFK=SV$ zN>&3@1VMTD`r$``2^bhqmK0_rE0-<#B#bAqE-ZT*syyNeoOyD&>^yjmyo83Rsbdi) z0DFlogv^s5O)y-M4D#1M>O~$Tpls8mYiw#f%`YzcEn5#jH83fPRu4`HExD;PUdT`# zVo=Ok>gRhScpk7H%pU16w6>{f%L}ujy z69Oh`q;gaPeI{1dOqfWI!jl~=uDC4JkjWFjEu;ZE>2$taF{q6*!^>Mbo~$sLW-zG% zARp898+4KbU?7hYuqfBKPzJj^h!h$b(0O;})T{Y4l6nAkc~SS!UiV#H`(Ex?LcreQRVU-Srs?@?Pa`U zG?So%nf^)$d_j`#p(3*#5kA72yyEFR%Hg<0`f?l@Z`xoNAbWZKL>e=nDnO10D`@Vd z0~=OMd4?i}Gz#bZC=xW*)+m`8K{30B2+lR{>jF;hZzzrCcZ;_9g zDE&{j~ge~}*PLRFi z<6i;Wg4pf=!Z+NqGrsHR=eb4!yz=E3D%wI5kc2V=dmuvm||b;+cB%2*K@V&Rj7Fs4~_;ZtL@!g>{6pn@|~lt&27yU_|91JF={9V zSvcotO^&-;(mV(<}ctB6MHAi+K_|{X)rtf@D&5&70Itt#pyyCvl*_hE{ci%irV5?GIk#<0v;!5~;jKHP=$P zdRK^B0L6@Q2<1x5MM+ngpD`!(QIGQXcL-^l3Qz4qF=OSB>Qv0lg%?XJf7nT;vhvZ1 za+^kV(uySJrJ@V@?xwfrowWY^^YrrBpEQR(O%wC0>G3B&Nsqqw<21LpCZ5CMK^TtF zj9smKn=ljt9M8{MNX)a{MkO1~lt{v^I}z$)tp>TQypZh3!eW1U!4#9W9{ov#W$sK{ zP*l!`$YZ(X2Q5l^UTWrrgfo?|*L=hWfA0*V4Xe%b&9YETu)}H83RTLR`7vpuZ$MFX zru<^vhn+^#Q&Vb3Gggw&FQZ6jZHjUw{p2f0)cJdE%-63jl}Di{qK$TZRAO6gi=A@x zE41w>Z^DnNK1{3rF3!Z!h)Lm(l|LNg%C56^r{lihg72%HU0S&_skoWf%R}vv@Ai$P z`GxtkcK=>lTv~ElAp8+K*E-$Q<)}k;cy-iQ>N!B)$ylCx#l^Y>>lye_9;`>uf0MU7 z8pkMZGZTdmagtB0L*U1A zj|&|2fw~S2VR+0;sIBm=s;i4@mCHn$nNxo+I(Gf-?j5O5RoX7uJvtukp7yCUq6`b= z^jMmopGymB|9l^ha-omnJ66$VL+MHVqk&oJ<@OZoJ0zYI6DPZ2y^~k64|@l=`r)Z@ zE8mF|@Op~EdS1$p`YoUzfLrX=iZw7U^2u{6(UaG-696}HyUhqkTckYQN5E6^6dEA< zh%kwtc<7gSKHghhQC~K!dV1h*zFoe(l-D32?6(d5*Ti=l+{Uvy>d-EPH622$)u=tuT-CJlf=d)$knk|Vh(?DW z11zi#Ybq0De8FYFnmYsk?X6qpVI(*xgzyi1_N!>Jfqz&P$Z_H@1M>`k5PSBo+_vcg zUvPmhGC4rzYoBtPlQSNE zmK6u$>w3$>m4|{laex681CO{+cx6+ADjwJj{=6fHhlYaiK)BSyvz*(_fNE-L)@NoD zH-6pYjt7@K@pz~>UHtrjil3#I!2^m1HxDL1#-LRID0t9WP9?yLhomE(UH?7-`Qlle zLFpjzPK~@&E)49vpi6_-Wq(&V(Ok5a|IRXYMl? zzI7-cHfyM)h45Cpi@4P zUUH!*+~NSfKtaE(^-y$i93+!4(wK|DvCjJm7rxzdn%L^iPy&{jm3(d`#fNCzNs&f9NCbY}ehta2P@g z0Fw)UnN9f&A%77PKAGBh^OnW=k;~gYjj|^_WHToHwfPxBvJzkIBMkhqyWmTeuuo23 z6{HVLt2n>QZ+umXFQ-UmGY#U!zK)( z2TB|^94VH;v;pt%lNZmy0woWsINr%OqAwwAt69}`p#jE;l(aSdd+kj#;%|5>iiYDI z&Kw9|J954Q%L5`u=2Hk*r;5LO)oT# zJhSqP?;#y`57WuJznbKemc}6u}^J1LFxGY$+5X%u&C~9_gQBZ98n_TQ}VqtxRoh4VA z_ngKNMdxS7mfho0o*SAMU7W{@fW+gpDPF|ldqIS~y5zf8>}En)R_|zHT@4C~LdN*R!`D`f zQNEq-S=u=`N=F=5t~e-X6j#oF@!;EGDAhP}j&Bt0?;j+Nuwx;Y-6PDOE2Sk1@Fd!ov#o2pnYw44ZKS}rR-5Bh36lpz>gHO7cC_JZ0M7{Ce^HS^DzJKcuH$f04GgHq*N5!^WF8sjGHE-7EQG z#fX(2d}A$?9ihPDs&_FF#>ef0SDEqcFy?_)WK%BrC^2?2v3mwZr|~lRMjg8gQCyOy zX~~G3<+!m)%|&C^VSFPHlMDG+xMwcM6$%ApkG5mQisT_o(5U?~XO=gz^KBn?F42d* ze*Wk5?2BKgv!hm;SX6m__V?+d@Bb`~PA#UZYn1l1Nu^IRdSPEC^Ge!**H%=|S#OCK zGMPKZ{MAYlD@&*=vEvlw3OhiiX$OCr&oTV%$ibNnVp?Zb91vUU)B(OWT@u6Lqj80j?Kz%d1)c7 zuB@cx#d-D9(`j;wvW)NMS?MQv*mXsl@y=1!0Mxg#gO2>?8%aBRhu%dN-!Nm1fOZ{6 zvrbP>xZjxL#RnD4sp`iO-!&6Ij_Kn?)-AOmc8T2?8CTvb9ct4Yp~%|Bg(g5K=_qsh z2l5RC5xco|cXs_vEOv9!=TH|p>UC*(AuTN}#C^4-GTH!m+G>*k3?CSZPf?bN?$! z5wb?XGiO@mMH{7WJL(>*oJYNe$WGF$JEMu?f7uCqN6*^{6zBByv;|~v8LIB6-k^Y_ zUQF|SO_>Wm{!;Bw?cPT&s?4CboT9g~3E6eSUe*@r2i!(gUc5lCu%JE!g&GQ5r3r-> zYb&IoOg?>U0<%yI2(Zt5BEOnHwils@rtAs4Q&XN#|XeA9flJ+8{l zzw!%v)8BcP-312OZ^`uyXH(ChmRyP3RBzA$$gNx}Cls2H^(5htPc} zuR%cAZyWlriSIVJjc29!@*B=9MyPVxKy1R4a4^VjC#u->i#L+h;Bd=P`C;O(0ktRO zLUeJX<~PCRlg!L`cpd`5*s)7Yo)&Gir`>%4_1}kBykHr z2f-Iage!N*s6)^ce=ZwYM!@-_KSdg8Kvo&p%|k{5kF~m>gUEoHWieRlY+}gFp5%Fn zgOuZEIdoB)fe(zU8b3KAS7hODHzrir`316>*Cxg!4ts}GL5g2Ca}djjeAy26vdVB*PkGlMw7*zIuGb6EF#Cb73kvLj;0tf;d+@ZlHndAybV9cLq4;AGm8 z!$YGot#H}DH{WYF26e`G-1*k@hk^6W_6mu`wxEnVSi%N{?p6JYI4W>jfbfU^cdhs; z?V$<%xG0l=;)fY2L~f&Q1-yf{h7XGuP{@9KDT{0`P{o1aNNd@ebT#BM&wf=rGC+A8 zAm|AzYaMsf-jFFv9`~EF7bsy$yv=+bL|5S&`N8<1k{fSi=O=rikFd7&;BoZQe0#U; zz6UhzK%oIjm?~VuuZDtyuAc_`0DPeF3Ae!hx^BeL=eA3@lB30!aLusrE;yqJU`xKt zAner-|4iS{uRsY=Y!#-W9ptB{UgI(}NZ{8SAN5?9$6ofeyk%F^#rd(1b~`;jO2$m4= zWcb<(o$2COJa^OK?s_`w9HdUBee>dJ+I;m~VK#){Pj63JB0WfFZOL%BojM1b=|tf! zPQ>rLo33gN-49_1PMQVF6k1ttIRC-0Qs^}xqa1rd}y_Z#zEjFB0uippbd&GCGSfn;Ia!p@d+ zUP2Q)zVAeQEEKadiMbcwismi;I6_O~ZjJk2zj>XWee=wV#7iqnX?b}$&CSiFxtSU7 z#AAWnU>R8qABu4?V{(`IwRaf6*9sN^-+^M+0N>$4;e;{(r4-+zA%DEHU}9XdXXT~n zQEZ{4#AFu^z4BO~LgYa`;oe0Df-4A$cZ_tJy=tEsiW=lnwP z<@S)<3rdfJR?CWl|M(yO-|3@|zn9k5?xm&WHQ{D8KR{tKW<>*OMhSd$)Jn%4)iu=} zc8fiH@W4t5zDsm=%F%twH(mbr(Bw>-U0Ct=x=*N=T>epzm(}0T4i^B%8rTKJKkvHInVi~81)ev6b*h! zR^>u{XY>yJFy*1VrSC$iu`oZA=9Rzmb2CvATvAfTRY@jQ|M)f?-QwN>JH6UgdND3 zT^5Ry^pO9}aVa?B3#F^dMfHYVlYS{#{zyb0L!7h~e>y}otS6JB@qC6vgjCGNl^`%%-p&y-0tIP9l*X#)Pt}lh- z*<&T1?8xByuPf?sC{;bO7EeD9$qPNdN?Y)pRzI)*aOJ!sZ=-)EzaxDfxv1R8E6Nx< z>uD%^{k=;)OZN9$>8Nv}dNz@k7iQgmvBP(JXD7XU`8pjO9Ew-0$;SK>-i|fLo8xbk zV=;T|)SHa!y&|0D#w{BrmO=xBS%-sHal0S3yU@MEY}oC>uDq&nGEHM^#x6-9u!a)0NWB5yCdLP`zGmbj^r+@xcG@>#vj{BQIR@* zxFvz<2os(Jsp8FP^?)6B=3&}ERq4VSJi{YoCiR6tX~o(jGn5Rj<#wkMxe{hr9ao(J z0m6eKY{;TVfdr4d4@%>8!O1pTuw~wY;0?OaAvceeEVVln416L@xYh0A8}8ESWIhoQ zc9~`h?+9q|xG7A?%mV#gPd?bH?GNWtCWM2pnJT$9j8rGiAPXf)D6d%f_f~9m?Ci#2 z@Woq3-sPnSB{DHkg#!;K^9IZ_Iy}yfW)RNXR4ndai1#@USkR)85Us-a?KTZ+7@%BUMjfP{_^1Q%y<~7l#tJBV%cFb%hZHdYiz7l% zIu#|=)ft1`i!`l)&A0|OKEGW9TFMcHDaR%7q1a1JtW>BjTNF}fK3iIKinn7gDvKPV33P{8=!SF|t6%*W^Wr{r4p+_rN0a=eA> zy6ir(5xGT78BA!P#CCYTLFSGUfQABak;@`JekO!VXzqZ_g2c!j3vw5TZY1#L7YQ*y z?;vyx*o89*S1mv$kD6IxjFQ+9Uc5N6&>W!&r0liiprn8Z)IWqt4Payr{xvEQM8CW7i(1+dL$VSBW!x{1L zGa?(7nOU#u8}w!HUCNCZB06v~9X2c01THU3d>j^_Pt5VjlW?%3f(H+9$cZD&emgEd z8xR8@>|n)+JfMC=+%mZ!a3nz&xR9rEV>h3I*Ja^k0f%3%?n9Xup0;P1fFU>3;75B3 zd-xW@7fonkB&y}>)^u;U`6+shjXWbLNXWVfMH07*hD1m~>El_AG zNvm|ZJZ$TQg0J}Z0pam4RIsb^DjWS!$$yJ~o!0=gb=XMqmQFOHS3$3|ld5 zP`Dn@ub8IB2MF(KyK-!@ccvbhz&$r@HNFYoJA-(+O%k<*e*D{}`t=BKo#_Mm=#;dQ>=BsCEck5L;*nXY1*I%UVjTfo4vyo23 zA7$3%Nh_VB^yCS%8zfG zp|b&WBz zh+{!lV^hZ2ED*9#>^Yif%R(y)>&JZGh=pN|r`e&xPKxcF-83~hl~z`ky&LKIi|0Pt ziE+1&GF19Ttk4>_!U?6BkJZz~co^jwi^;s;2rat|P+>{ypj9p_&|9PGVu*<`{$uvJfLE@c6lF!Ev-npAj z&M&>of%JN@nz&e`mV6v<*lr)E-Tgyb%e4Kv%^IxX#fBy&R!K24%S#<;D$ED_Y9I^QF#k2Iyvp=V;jo0aLe^2dI zZALu#ej4B9qYP0>P=B~krr@T$P=wGo@NJyuYR`ZE;*V+l)$_E!yJfy#eE$3N^_O3y zgT38!CRw{}wOh5jOSRSZ;a=*rbg92+w|3L9{O||AyR)uzzw{A>4c~Z&28_f9w^+w-lpUqs@Kn8s5UP< zYbRdJXR$vkyEwLwxv5{al$$#0Iw3PL2hKPY6VzqC*~NMh?FL>91469mGkB>LB_Q=| ziJe=@6BLJ}iS|tWXPt*QncK#0ICh4ijNyCl@%?vpmm(huFw#o9=9octU@EZkel*Ra zTp1ZME#Ds8+i#18(}dL4)t|77Y-M>d-CJFZ;z-NAV&o$~$`B zGvT`Jj*rsa-QQ39x}f#<%hi|Ahj@KW{UdGNNApQ$O40cxc|-9+*{Yn}Z-+w5dBu(= zwOPMNpn9W6yu#DQRZ|E*#LMRDYrRud4N}Yr?-*2$^!w~$;~C)>*(JXfsjTx!9_Xl- z)Gw5g6H_zk^x{f={Ylz8=%nr41C>KZyobD_dU1Z<3Q*$b?xe`K@qAi7}dpd<&G84D9xkYhurKco@7@T3Ow@zxyH(c}M+ITZkRTwSre92Kr~e*r2O=mO30I677(76yuV3#zy-g4`~<79kZz) z@p@fJ^D|TGQ=^u3>Am}npzKXl{f4>=d21Hm=BnvKM!;WtqrU^})?R_MJ!T|l@%J}D9 z^n-l{$MK=KLGYn;P53rpp#8Qn{3SBI4{qa`6<_~F6Z#@-uIRdl5=cLKG5f^8w;xPh zMIcwKYKTFNr+H#6iYYIM*pJYT2&@e*Y_{iHxUd!)!f>(JW|DjhzD|oSQ`=r-582EQ zdLwZWPXCwuaTk6C9MXJk!=Znssq#a7?H#-whiPOtjjY)puvK># zqW(c*31rFXD&gSmyFiwvbY2iFS&iHGW*nHTJ*<>j=nxR6Hm5Fs1Ah$nV**2olfhzFJ)1|EcQv5g)@SM0vw?G$!+T{1z! ze!=92i3(>1^MK_wI$fWF>}2YGWq*Kgf1&g8~mt~ zIgS#UlEq-3d<4iV7AP4kGf1L*obQ?Z+W@VAuyLeBC}wzEQ)kLK-;k7n1ilQmc>62L zMKY@rAu|FoX!4H0Gs;B)CFflYmd5mOAJYIDWfI@t;z7h)Iiunq=lJu+5&|h5s;kJu zTfTk^inn%D=Xi+5TXBkCgG%I}J~4RVSQF|UHG=^$v>v33KKcr=c6}ypqEUSjPaoeP znHdZ@EySUTC~p`=EhBH=M*C2B23p6OiXG{2AqIy{v^P4FhuyatqGW12|AU$QwanKndMD>(wZa1O@p**4$l z?+8<xvtMdSQ(?(ch>CYU%6o#;czhmSUObupR6PH_rvaGh~7GX>(XU51> z3}Rw@^R8PK*>VLk%U}mKWX2h8lVmTKhiQy;-Jwn+O4S!V=W%eaIC~SUqWO|c@KZ-CTi_S3wcB*FO_9`1G`?2JQQxpY~mD?4?IB_Lg`C z#XpE|jjK&ifiD-(#M@bW^#L@NP-aC^!Wn`Ww~~_L+bdH6;Y3(u3YsQu6}q~bKmT)> z+o14z*HvJkpROv+T>SDPQ1M3&x^*re6{u$bPs{71dB~;a4i}sfaN>n+?+R=0r}p7a z+TDDa)?YqN8?TYV65ec;*v-`Kbkefsm`@%*N__vR)9t36o$a*0yJH1P z>tNscz>8@tJhK~*T^v*Sn^268PfyRxU(r|zHLUS8FR5{qB?>HdiY&}c`dBjD%o{uf zRGnd01`G0x;~2~P_$!Uc8LNB8$pl9t@;wP~T6A*eiH z4TUi~Cr(r^vgG{Z+eJHj`)PA~&u{gkRG6KeN{e&T4#VR6&hCEdwE6x|?9B0tgkJa^ zbAA#3wd#q#t0sP>c>&csK_n|(`<2E&e9LZW(kE54ro`SbMb>pxo&g`#Qw^(&V-b0@z4gkoZD zZZWN{-cL)*t3C>odU|kh;G-MA`R42N&9g7fpZ3|#%BaiB6IQ!b2T#-0<(aYuB?*dH zCXO6!Ib!7$?P+&s!-_E!0?buWGIqP|^h$le*I#~~UOfAAdi~<7^u-^3lfL@=H)eQ5v0?OXtc@6g|91$=V3@ zAU+epyqQX@`LXf@Wd^%-Jb#qi^VI14TyJTER%mKI%( zbWuMN^BncBX2zX)YaAapGCrCnR8OX7XZ%@=xw-kocer9bAe0I0z8M`Ku@Z1~S>?I1 zkQNs>j(;Sbon5&8wpHiZ!AQGgcM^HXyqI=R&E^|?dukKAdo3%4-}+_0IDU{9Ofhj2 zhPHvSaZd5Uuq(fo=HeHZ>KirJpI7@~U2ADs{la|grlG&+9P_>KQ^&{7tJ$eB@95

    G7Q z_j6jV&TCQ58=ddHFT-^EtQNfTRZ3L&v=ThU5o<>6B%)?Xq0-n%6I*FDV{&F=&;>gB z!Qc)mMB?_R7RH56UQ6b^k;9W=Es?gFo8l3nA!`&!ASb{WiN-3Six{y7a&s_S+Gw>K zd0hm2X{c~jZ!-lufHRNEld4F?cv@NhIw6O@Ij=>UczuIh3~U3u&bR}(!QBuz4t2d~ zmUmG0)S>TF7Sqjak3h^3>vX+hQDlk8gUGBI=|LkNzgf8xAUCC3G2P?)Inz--!ADL& z3b-cZ{Ao6Ga;Si}f+m^Vq^S!!P>n@++MD~ebgJyD(0V2Til^690Gx-iRiYRE=_VBA zS6$=M1<^F1ywZYP^ zST+AT^eC$idkM~+UKg#rCtNJ2bW(!*Cm0aRkhNPLUuSLmxv!IU!{O4pwvab*6InNx zkMf0bvSGcF`~GE^9{m12D}rQ9<}SaS2{`G2)j#9R9Xe>G%3S-l6v>JBO5mX>9vP(3 znOB-w{+OjC(C=e|CR6xjyes0~CkmxO?(6+#2k4<(6P3m(N3(ZTNeE zPFY)blqdOB9BX?B4$_pc{zgi05KE>_z;oCkf;olEr;<5k z{Ztij(qwKyoUG4+f_oKX7q#h72aGyoL;n4vyU2M)uiDP0V;8nqY5WM?S%~oKL3=?L z)SCW5W4H~_b2Mg;Y%uN}5%d$Y+D4YNzBYwiBZA@qP86DDXKjxXOJF;a!f|OzP8I|k zCj#59?$U@fj?kn#Z8%g}nqk_i6f4kcxxBIMrw$~l6-uB0jL$2)H7VL|_!_YkkY?qOj8-H2+ zpoMc;EBNJ4hYw7MU|E`2Cc9|1yVMCWShd~U)QVo{kN175ld3bS)7@n6=OMSCxbAbW)*O<1Du=%;~hbckfaMc8?XX{Z%NZpb`yMv!T=1EaNsEHnAu{3J0 zEK)&pU18(p4yZ*omKk=D6PxJVb56P0yGC!9CF8beNGL$4r1_8($@;suMl)${&(k4T zzV(YI{zN1p zzp?!!3?Ex`4k2vs=v7R-%HK{5iok>?#uOEh1=(lMY*~FPzb)wT{f*_mYS2k5oZ^~* z4-j$9D~D<47Y#R{a28MZ4-n~}J;t)mlvY8wt}U19kr&rf6e{@i=?!X|*uY;PyW703 zqXYD4%<^)U8J2J66TR8AK}vMCqfqqV%jM%FE9uym@+@zhtcB>3svf5{M#~$#toAT$ zGe)p!eg|n-#JW@a;Oi;U0oMT!fB*i{q{MyG{ejR+yVt?5RaF3X{oA)Rp>#9a7Xd+D zEsnQ(+U94$>s9{H;o$gsj$(i&AV=WUAx#;}1-b7jZQO>k3T^)+ty8u7YAOjr@19^h zF@+aC5i~zFeb!;_rx)r*$of6WY}=_HF_25a(AdB2vp|5RbtsYBBUwr_SFL@PO4&A_ znnv_$DjqSMihR0K;ZD`i4MJ?ow2Ko4YIc^5ACbSc%s!xcQTME6A!H$AQ9^c9a+PAb zraif%d9r$9?2h9$PmywG@xT(xb3rE47Oe#Js6X`u6!LUbBC$xTpz=71q~f+5Do4A< z=c%R`RJOl^P;UK{=821=y$ylvY^2{c9;e%M3E=N{+=7pI%FjIr10d%qJFjn0ycy1h zBZI;TY`J;9G#vz4>QB-Xo$DDt+3|7Nt9-kn;|T>#ihJzq&9eICt=)!X1dtNe|8b`F z!(U#l<}t1v&RWWuTl*oCoI2>c#2+)Fm%%N8x@Z5 z+*h(hq&1=Ln{l~OU29V4C<5RQd6uOUwua^(EYJP*kS$%g6XJs*l4gpNIfa@qXkPnM&y;|w$s~fzBIJ~qp`k= z5yaZ?oKKa4IYff-d=p=L_AYlv=qE^yAuIk}-v#wfCydBq9dSL&bipZ$wZK|3o-UP3~Y)zsP;&kn(rN z+)qwZiP%3XIc}nm$n}Yp$=72J41v{faxSoxc_&a8z?3Ett8->9Q}YREEwEwUZmtj& zz_`cwiLqNGJGzjfyp<6BOPs}u0c>Qh50cUGZ9 z>7y61J|{AxU)2@~m5PJp%mR~PxaV$$TVOd;ML-$m?;n1@?earD`$wt4 zTEKlKkta{Jg`gO=oh(_H2pM~|NLnS>1m#YxLZ;eJ|1Y$BX|m^sZBtV}Qkm~l0m?45 zVPlT&Y6UwLJ>pWieXLEFdoT~UxzFoK#Q|Q4=Ma~&k_-z7H_9P%_mQtNZ{y2r66#$# zNqB^KXYwm#dkhD-+xW^aSw87u+wOX7D!Ak6sf|)Oo*XyRD8TWZ;ou`b)`MI0 zM3)A#@g_5P0-_vfY|&Ep-mg)%`eVrY?YY8ZR}-rW(I(@kx!yCVBl|Ea)W4f{Uh;tQ zg=d@mWx}-uJ_Cq(>hJ1d6sfY6p1nU0zQn_CmkqH52{9`a5JHAU3*dAIerI-=#K14jFLnZ^0#Oe4npNpy>QpF&lEdv z(7$z$Z_d={y>-*XOawj4mYfX>JEU>f@b>l5YZOT6 zYOS!6qzQ2)70LV`yvkqvS?%5)oK|)%$+wF}x;r41jyG)Wfj! zmL^6f5q^~k{EfPPY(H}!NQ$))HOrRN#dr2+{FkIs!`FiRyf>{Uazlt;&l^P&G`^W} zwKx(h!wUOC0rHb<=iiuX&s`a5*FoR!KfU^Hd@E__VII(r`Hr%+*7jz_}ef?lZ55Lut{c+rGWl-Lj#?~ z+ldts+*XjOcnapzf<>kZa3-gcpDKK*Y`+bV5X3{O_<^giDS0eS-5!l%_9u-`_ts=oZsNOL^5sppgDOK#a(QXVy{Xr zpQW-KWccY5AL|96)ve^sKj`^HVqVP-n-p>{+d*$#q0{ATfXRjGE3AQro3hnZney#f zA4xlnpl<;+R3Fxsl?U853kvF=kpT|cJ^syLpoFuAP<9#l%Z&2e8c(D+I}U|7ZEG!x zuG_CxzlHj5v=v8yIr*r{C#cpx1by-3&I~Yai=<$-u;j_4wi7uy;5a}Q^8)Znu1A$p zAyhO%NV$dMJ-Ym5wW$u4moRQbIR}SHApHN{Rd4afI4d1|#-DUtg@rce)eLme=bm<- z+8pM7vusYwcg|6i<34F`OVAr#*u%#|u7V>OY`}nI{XEcN8Nl;~!5y!PGr1FI0C4zT z=g@`JAQGQSn)VxQvQ33p;@mTh`|1i0&*{8!QyZby6m(@Yx9o0pzMi48DV@!i7G5(vp29%m0G4tvgb@HxmnNO+IwU4^2~6uDz~`&i z#-i0++BGhFpUInFd;hao3C^imT0tB@RpxQFq?JuJ&%wXvm6{r6u-`$zkr75VHQMv6xns(r<$|M$QI}5Fpyl z8;=34aFD=St6x?!MVh@l5p=zNYK)lm$SM)W${1t^oKf~BlYm-1dzksW>XQRS_nlZL zh7F2NLr?Rb?OXF81lZBvh`PPUo zsI(PYNrZR+q@jFRniu$5j%GQpM)nsonD=)NU*7J;-mUT#W?FOg9BGV_!?GF+jR|m> zttot$yQq1Ha}BT$!go}mhH@=#B}pw6?Xu$>$P8ZF5Mx>@&g|NKSf&$uGt0b?-nbgL z_;et#KYe}fYs82oOnY9|$%lbT;;1%Ugvt$GXoC^)sl9$QXv|Hh5MC?U?R<4%+|@dG zoTT>4Aj?^eO6d}>AMw00Vmy4$QBN_3b3Z92e>eQ3#g!C@79a8-a^k%d;_rBNadCma z*o}xFUqc+dW@_aQ!}8l|Ra8`vZmkpEARocsyL{A8YUjuI7`IFp%q8Kc7b~&oFUksX zC{I0J<)hQOqi$=*Wv_dXdqR-Cksle4aIV!{qPzQkzrMY8Nof(XdwB6Wr`_B96P?Nm zr^<6HWt)Y8Ql+lVjx|o>3K8cot$Iz-G*k|TAaihN(;hv?tAx0gnFwu zd^kwxW84*(4P3#UO{|4@1iO6)Ceb_C@7`C3|u2LxX zCe~GNR$8DilfyXEp_UFiTf(?jA)RX2_@rV=4@qeEQ=(&x^dR498l}7=y&mLh6Z_Of z4;X1>Pc?0V$hAxJXLdeN+mh%sT=XF`YU=z*Bfa)TC|fo@l2Qa{`pl!ef7Spn9{T+! z;kk+Q$FE8_^LG;Q?k7yv!T5qbNcWVP?E;CKPtHAG^Ch(v7dvKP$cW#IJE5^LQ~0dq$6J;n@{?j=d&(%wF9>9G|6sXpv_&=E(-tU$(3<- zXkvM0pqUvjzgZKlNCt$y@wvyH&>ZRMP|p(LRf~u;%S+L{3zx}@bLRy(-R$9?;3b-u z%eoR~AsF6QEWaKJSH0IRm$eUARxFC6lPR#_zK5(Uk9dqO<1G`cUg`c~DJhcWp8*CM z*y-qq*UqF*w)}7-+vw&n=J5Q-&Zc@Ewh)?wnP%N7l4`X3iM6`y=#QFQN?-i=2WXeU zdG^yI4|9*<+95mK3vln+fKOa(K6J9EJ|(BM-jWqIJ`4Ic=iZsj8)cZED%!nq6H{Vy zCPKSI>%S1*wz0c*X$^P*0af!plv zN+B_=SZXAwZ&x9nvbai#{+O|X^49Q)(db;!SgS)6@rKN5Wsb9J4Wm{YMc|ZWq z6iyHw1}y6jh=s-mI_Hz!Ww-nln@lcae(Da|02D^rTHT>=r(^oQUO4$_VrhQX(2$e_ zqjYfsUQuf|JQpZ3G?rqBp;tcTzEGpmnG|>{qwe zKeO}yMHPqiH3(!_% zz*2W|$V4-P!N|ts!8)q0{2QybqjNYj6%6}k-bOoWr=c`*2N=->0o_CTlvq=QS^KhY}M+2&kQ6z!uU35&4!3hdqe%vRTNS3MDf)w zZ+>GqVRBN=)d$%MGe@_Fa`1zO9#cz3Y6$&kMj%;W_lwV?A;hOwS%3Z+02m0)H^^_b*yvPd%9Hhm(< zFOh1Bj*?(V)dp(AIrrLAk7x>?c#bR|vzWTC^36Qs*0?AQetR-?*HkHwZm8hxhtvZQ zXPxzDJMzuPb`?97sn8~6A0;%N-!tImX;bb{UfzL&G>~V9;hVPdFy4daF~tkK`S%0h zXMnD3Sbg$3vdThS$WEK$IAcPs@tp6%{yURoKyC1H4sU+SX0yZmV z-*~NyO_jH}w7Wr{;)Ipds3QM5n5NBbphIcZ1|R!=hvs5GtwZOpMr-0nbbtrp_opHS zp78E!`GEiR_mjk6q`$w}dwB%^_Ccafha7H;q#Tv=5BJVEYW`+4Iz6YR0`(^Q1iAsH z0vdMyAS%SF+!Kl9p&xT#(%OtjRjtKXcs0HP4Y*OW_Mt&SN3@Y?`< zcwako!s^@up>#*Yhl(=@chL-8*_$_Hzp5G>KKlmkl*Q4SRuZh-IyjE460UxtO$Wy5m%Ce9rc(!UkSOrO*(z?SCW_yxI_i@=S?RC z1ull;9jZsI$M~4cu;ZV+3*KEc@nugGS6N0ib1$}>hYD%`BYOL0@E3Dnd`5Li`06{y zr1V+n^7yA~mmLLfZ$n+aR;7%9=f(U5naK5YIyn5H|AV{A?|V=yBz=WTc@Kcu)!Zaf z9aLL;Y`;KJ3V2`;&2f=W_7$FG0vs#NBkYt#GR8h(1HrlAH}gQP-Yh((FYNtN=0qyX z6!X~3`hr&FjYh}3{UVI(slNmRG*^~oYewkU3IsS zWV0&0RgZ^{9FAVHcZ&AO$3f_3wAza12UR~%KXj?Tcd;btTvTa&Jk=ipBQ8foC^r_# z=JE3jhjqQCn-$;bWMp>L39Vc(z3x&z!K|Nqls=6{5VJx%N92o;wS4D(yPJd5W<{$@ zfv&4_>-973;%Jh5clOluh3}FZ>|jwI71CY%u!1={X9}4*8X|lXJG$H(wEJ|FGxo)3 z_Gwi3*6&d!+ZM;1ccNes1+rUu7(X`RdX*T;SG>mL$BUlLIP?a2)o zw=x;C|8)mLNq4Ys3n|#bkGS5nq?;>G_+95VRVpLxZ)J?x?fFyW+_tw-H*`ElkyX0- z!hFO0k)B5hsKRnB(y_b*P{@~>qD##;=1^)rc6(D|DH6#iWpSf8S-%h}E9fo`7~%!W zp=Wk-Uhb99mZLN|;15>z`-q4J6L-O!CePyxDXN(TLd6%wyEH@#t)P zsi@SKpyr%!EPU>>I#=j7&L1%^LmZuPVRK^k<0zYth;)@d2+LXetxTmdpTfz#bF^iD zZ?n2vNS+|D`@$WVws|`0@T9i^j(V$MrfH+r^YUJ*;gzvk_#=X~RmW9++bdoDj4-Sk z{&jMq_A_lpX+-`ZNwg78M*<<`5WQ+ptT*FAukS1l73$+G(o*{R+MY0VsCpfMGo+0CXL7g>_Oi>Y-O!%&rX(FQ8>u+q~q~g(dMAt)iGmrTs5XXIj zF`Dk>w<>D!;Us|GNA3@nBt^VuPE`5aAjrjxl9ed;goR@$7Ariv?a7aTZCZj-1ZFl@ za9c2MA06@N9cX@g1FWBn!fs>)IGCx4dzjn3i{I|p;eb#5!Wt;r$N z)UrdL_D!W(rKg4+DwYJC)%3^Y9F;p4B!+D{x?Y~2{l5@u06Ig`-N7-2lrr~+Bn8(^ z7rEDVQ~}Y2gv`ycI!g(~DpJ3qHl`msnG@96xApUlvEq$=)@R?A$`rX4(&kd`^nEMt zAYoyIqM_Y1&BXm>aI9%f|HGxtRSU)f#s+k4s9`RqX5@Z@KN;Ik#v@Dl$Hpm_ajQHNV)p9(qPHWeW*1@8eG)Z-2^=M13uXlTA8VY*$G5vUxkI|pb-8O|&&GSuC>Ioe3 z^ku=@H5JzTWs&sWrjP~)y|?#D7E~D1U;xdH?20M|#2Qa$RtDo!C2vkKwsx0z1X z18s)QU0-Nk6namM23?cQi~m7APsA-1nYC{fltlPB>FSa)#scL2Y}HQ0v52$&ANHZY zjMYy5UmwiXS?-mVa~4#6Rj1$?t?a`#lKNhMqDVh+cLqzb|0Acp)nF$vo?PJAYo|8( zmA1gYOlzBrULz7~V6YM@e zAj_300T!uAU0&o7Y&7>W0gN|rc#^U)uCEB|SqTIm1W=odb*|sssV8q3j~t=82B?~? z52OUT82|yZzE3$)X6V_J!E(5({YZ*3wTjk@>efAG=uG`@iYJ(ZHpU6YTEZRZ=lzjR zz((VvqUr~po=5k+a+Ju01rXRF$yv}(&{DMwl%q*W8rxo9@+O`RVLr#^1tt1E-LcGk z3J`^pUvs$m8BtM^Iho(!ivQIYD$%RAP)A;Fpn>S}Y+}z0 z-e3}WW(nT#T@RlsB5d1)*-;t(ewI<+q>Ni@{`R;L+svZBP405o1jUs)7rl6PpN2`< z51{VhRc#WYy|w<_ZVY`HiJSod?@W;pgEyfWY3uMN!zjLOsI}!99*JxC;=8=pxHdXC z=mvAkoc@$^xziL>W9l{92;uyY2)yZ6eWoEf^GQ0ZuT60D!*Z1z+RG85#~R>?+}N5! z|Ja=e%1RYdaVaQ{g#G9SJg@$#?v*IT>U<%r{>3>t<+Cg|#8Y}nfxfq|nnsnpR>TAoj;-4NN|S6SZa7eHU!2B`+|AW$SQ66%7HoKYF!5w{$}Q% z7XASL(Si5sR$6((S(2vYZwG2wm48F56rS}C2lj|(c9{Kce{Gs$a54iG8ZjAl%5)Yg zqBsRSaRv96F!hs8uP|{**3}^g*AOd;e`r_aww~|aTU)CCT-+yu86qzaqwquh=^}N_ zjE$~WiUQD|T!+`3qv+9`cnHN#ClO8Y*i_(AZkm%rI*?uE>WaPdS6mGz@n>h3<)L1 z#=4C-IleGCNp5vFEVhU)maok zu_-5ycEei@6%pQ^))ViTdXK@E`P#LYqBrv3*943Z_#NFjED@|?`*8?FvF_VI(LKgh z9`XjJ22k>|o}5T~)!0b!lAdZXY#zIHfAGgERfO&KN9Scao5@V$7i`XTYD&a$zq6`l zAObG;3vzji+K@hq=+8$mOLx{SCPk)n%BvKQ;O>NP37D5=CYj)kXFEZFawrfB2jDyJ7~D_+xo)MG z>2!`zGNfJ&?FWogeZR94Ik%<|DF^V!y~_qR3b}8|lvN_E7C5~BQH)eNa(+rd+_1a| zAl2ce^8&iDWu?%xtJz%ILe~z2XRA~tPe{D3nR4m-2iJT7ESN9K!}1qZ{w|Ljt1%MY z0Z9XtY?tCnWv~m^=Q}axO!;-&yDOWI{0yoy-8W zuvhD{b~Zn&Nu8bg3b1NwA5Nx&QRZ|Api~Kip?uhst5~#-Jfl(q4&`Luu*$@#7}O6{ zD4Ft#(1OKn)?2ENvqIFH_gjHwhtGBrHiWB&{6-fVf)ccro1~mS@h=QFu%Z)Vn@l73 zZqx+nYn3fx9>MYU!PQk}K-`W`O0UdMh8NA`a9J?)ml)0rQmK1G?`OU@^R7kNsq3ihx&LR< zI}9LBH@2tzb?*62=t>tL5C{ngiMzQPTw%V!3!64fLgl|wqvbSTLa!shIyKXv2muxI ztE$(v56SJp)X*je>lI|fq}}JPjIIlSar<5Pn}QgM2xpt(Zy}8Rsk~W}Zp-rpI;(T1yS&>>U0LcIWz{R!djvV9$Rh^)qP8CKM z#y*vdfbC27_&8Ds_*{7Z<4yybZXSI!TemY8^t20n$4B7Gn zFuJ>SelNOwHL~)B;``)K+c-*{W$NofL`oSSvLDmiM%+^D2-Rp_Yta6hkcmc2_-k{8 z5AGS#$p{Jnp0 zy|>c;i`ls{EZRwttQXVfoVHI`X2 zG-|V&8vS~^*XHF3nWXb*b@PK@ynkd!_)l%v#7EH^H6Qi_dGwm$q>&*Lg!vLlPgwWl#%_hrT&F4a^U1Gx*pMOi{Y7#YnX;h&GR(UdyqS?G%qzTzjAsp_Q=nBxYWBPkp3@?oad zO(CB6&<^3;#IJuklt^I&MFDM_)_ag=6-;d#YWVV6)brJS@&9cZbtP@(hXEEfFSUY~ zscq9Qf5#~2mlzinl8S~DFIJd3G?O3cJ|{(wss@wzw4a*hb)rDydU+Q4?3UNJ7 zidQ_L`se$(3D3*^NYjPN&Ebk-JOTod%kTDzI2=~1*e_t>x${ydn&0>{& zW9+MU*>IRapR;2RMKjbgmFidTU~IkhPVZaE{({-0DxXPx0r{reH6AZN_ZfL=*)j~p zGc3u|ow{38zZ4l{i`OIeK5(d|fZtS=yrgY&Se1!z)p@5oSa`=D%n?rzi+z9jdH=x( z$-AHS*NQ$lH+@va=pzQm_ zr7b+|;vcxCS5`T7UB)q*a;zja9K>}b7%P$L2psbHyubc@@CGW#E6$3sK5D3X|FCKA zgL2?20XOMq7Zw}~)sA?@siq>~!3b)SNwX5y;WKyMsJl9+IFkx!a#U)!#5j$Dl;2;T z)f^nZt}2-{~FEngAUdUaxV{yTuE34B)>Hzp8Ns)`ZaMQyX#{wx`aV~I(?U+_i__vb+@|L zdQ@+20e!lC$Q+O-YQtqmCguF{lJ6yZZp2QdgT3tT6f+D4fu8NZQ}D^|6vpcXtdF-08tdu|3)wEex%M$o0}&DQ}|7i z;P)&bVvQfgWY8}c2M!(C_DF;Yj3ea-sjM8G7)9Im<1wym@VALGdgtV6@@iMxCNisXe@d86?M3|Tu*;8v;qIzTj6heS6Rmv zt$D3kG`{uZvhdsS70kkabHmzfmnOEJU)U-;A!79}j5YlqgTLXpvVIJQKUfa?$rydQ zx4L>(|Lnxw_7CQ8KtEh8y#L96E8zL~Fm)sie6wW*xcdHIYkRzmPs>iTdoam7n5z_k zafNRGez5e(=Fc1H{7X@(yUb?Wgjs+T;MQ9TH)tZcM;6sj6;ihEi;PJzq4ELnGbr0# zW$k$pmxO}!b9im023)*PptMs;v-oGbKe^_bRs@YS<@Lz*|PNhkUVBHEv(nV zc!nwMO0dX!EkDfN1)jk&K0IBsmlMh&>aYPM;Wyt-Xc$d( zx<5SiRoKU9ZbOL^tQwiqUqadyIGXz+;~{i9p6}{e7c5PEsJ6qNuDVQsR#lq5evK$h z6|`jhLQSHgxzu#VtIw>r`!c21BAAr+KP2Ae{tsj-apNyy+St6^F!#fWl!zkkjMAZM zUE{$|6lHy!Mp&fy&!058j?QqUT*^sE{WZS9)y*pK*Ej2*R0!Ud$Su3i^sF=9i7EXE zhb^0UP^5QrsERFQO9jK8^q#*Meh%P>Mar(k)7<LRguj=Z%{p2OyY~p@5KMqjW8@-><^Eo69=ZJl)Oj#4@=;tBk zN!HCy7VXdwX=C?A%$-_T-?$#AdUUa~(sxltvg4=XZS8raF=9<+K9+)fMCThxA!kFj zIpL>WT)iE1KiJ>$oS@U%CBjzdbCC=2_5YUw-Q^o`9;d`4q=R%!{i999gL1s^61gz_n8+sy67?4iaLom>adm7o>1PXDSnd3)*P$(QtDT z&`aWw3Iw6|3PQ*}KGAQ=r2kC?U}U(cB}IWLD_)%Al=Wfj!&(aq3wr^it+Vi?{iLl& z^*=Itm%Gg!EW39X66;nIDFnUibTyVZ$u^IB5%q+ReV!E!>pIRpLu zpiz$s+rc!F{rNbz(FEh(n}2xt(|Dp5r=y?vSxR(U)+sc2(9{?m#p_?7_$X1IZXjaL zzoCHSxbLOS^!}NZFfG&9M&Ioy>s+MA_5cp;c9O8tt_4>CA?0Ik0F4KUJtF)fJ6sc6 zsL%1=s2Ttbg6}3M^F80GEiAa!G5QalX$(i+=W$Zd16*j!RJGx9Uz<2uF5K%jyK%66Y+aEkXJGqhVKN#N=}?ZHJi!HlZ4}6(oH@bA80SEH8>sst z4Pf++;`-$fRbc6=txtX0l{acs@&sVMZ#UqMTXKr0u{+nXn_$4_k5le(U`1Q)!&sN* zv!=0sJfyw}?Cknmn`!`V9_~B-8<^4_8`D%=BurC2cWdWt|BzQvI-ITB`?J}rc1hi# z6U1;3Y$%|emkSs9UJiD_m0OtzaeFR(a@IQN7UhV7 zU@W#Jtb6j;YAVCXW^A+dl+LRrBMyGl9SF7LV~0|E3TgY;VLHKcbBn3H@nzu(|NE=_ z*O`PVHm$HoQ93HoFCd*lAySN$sJ}G@Ug_`)U9?HJ{L&f9+mMfVGEPR(?@7zKU_z5n zYY4ovBpYT(L@_Z*qC9MKPVNBONtZCnh-OXYlMKQ2H~4t3GiuSI~geO;1RB(bg& z<@Z!g;kyzl<4pAaSRY0Ad|aRAypX%UPIq*6B|EKKKq@k8bQ(tAP+d4s4fLFDlRI|A z+eL&uYp(Lz8cj<1R485dEWlPjPAI_bO((*1C6B%uTR-zf2NMfI9#h^_m%C+2{g((* z2Q5LUTJxD4u<>;$FpHY9(r-n~!okkYvy-;<-x75)Vv3{;9S?6nzAm-IG>HnESrd5J zaLW=*EHgh+2m<$U!u(-#fMWPWV{Wxd%m=H_WBFEPZbU%n{A5uH(*n35Pheb1`!18B zGqv+4@wPhv&SG)yBOvhp=SQdr_)Ul%W)HLqm}!-nC?jhCmx~k)BAAv}<#N;Z=oFu& zvdNdZU^>|^pv?v_7`XstNz8gK3f*cV^^m2jV|j%tR`Hm+7sLP!I-#(og}vyvV`b`| z^9v2F*N@}gMaN<&mrvpRHL9CX^URXOLi~K_SsW#ZHD)BVK88dEbcM^)W{vU7$+*s# zw?6UH`=+tb`4C3CL`Sf8RaF*=~jk^`B^JBN8@VpWJcLD=pZzDC`sc6L$|z5^I>HAbQq*91VG$jNe3StCHv?N&d??nEZcGzXdC%-+BL^8gYOhSVsT`XprYRqFr&Ahktz-&j=5z%q~Udr}X7M+vm zH2{;k95?EidVV_^0kB^{O0sjibw0(N@26mxs?Auh%aQ=Yz6tItBY4?nb4`izyMR>x zgqlg-G!5(n*Kjq;m9ik%Cne^zm8YjM*!-#+_%kZ1w4BN=&mc`F)=zxPv_h!ZN2iy> z{#oC>r?;jzD9Fp~?;v`;A-O~v*mR$ylnvd1M{DJfq>B4}kqF;#W%mxBIt0ah_OpWy z5$umX;{-=(;MifQd_3;R4`3>wxuwHzd_{yPu-_f5K0D z2eiqGbw4+~rlosB3UgUG8B*7;o~_;szi#(?H5+1Uas%b3AyH=snUzFH*BGgo6bW&I1=_i7UG(ry zn(r$Dqg#*m?5&&If5LpdYIj@6F|`u2dgtpJ7^%}u>Vqf$>mo6k0V~o?rVv|A!#C`B z^8%+~o06NSz)deQRGRR&+^{_e>1^wJI)z#O9YyatEu0Ic2|>I|s6Rjt99t~twFl+W zmiB7{WTpy%{5REBB}`z4Wh(omy&vB*ub3Iy^FrNY8cT&r{*st(?sb=ba#rb=B7A9O z9KXG-Q_vT|dn7>aYz_@tpVsFZ*JS+_{7J;FxZd{(mm$|Qt<%x0jrq^lEI})joP6yy z9scsO>tr-JQHRBc4m$U$4k4yX4ssz1!n_wcS~X|%xwV?g@q`3{Lg!Nf$+3;n5y@Zt zIKiI5D@7Z!?dMW&2U=)bGuSm%v(?7mj~y(uqse{Yw4X|&`{7vvPq z0_Nu$%e80H9uf3a955VUAW}Fyvr^o$9I@J`ONd8vlT~K0^J_m~c30{4Ht5yND;YLw zCnK7O5TRwX9<)`Ob=0QQebcw1Y~B$dhEB1a;W%OX2I=qh?xf4j!iF}+4~;UY<(b}1 z$^|U4G3VANAjhVj4ZMW*Zn84dkx zo_&gum)idA3k}$(S)*B^SxmbdZ$#C^!`oK1W<{>VHu{q057+CA5~wK&3D9@3Fguc@ zF@Y!o^jr=7N92S0_aTbEU*@wD-OBHNerLDSBh@oS>=!wCYI;)Ol3*c@c&{GtR!sVM z$tjB4KTkk7jB8jPC-xHH?u*53uZH$1cJ?F?T8Xme?916*Y zv-+i4%V8%GW(1j@FK!y80I^2mMwnCsCf{vJqM-A@vgc z2>f9G1#^Pw0U$)KP>&EgNV@tbS1w77_OfoNya;*)m4ib+M2j(M`lj;E+4Iiuy z7VHD{A`2VMl#}M7vus8Zr1nDOrU??$BSaPt#~rM$Zzui8$%(x8fo_HU-m~oW2> z8m$TwWwDj0)Ym)SJD!k^t44OS?zqf?%1Mq(LfYDWN_Y9*l7A(KlrJe4ed~2|=QbWo z^mFkxKvkO)P`uNLrI0@Ut%|-l8@R|At*mtF^_)vhIP!iD?*p-ORafT%mVaiLIE|Ci z30b5Lq-x8Gyz1q=)dQs@zjXLn30hN7t>(8MS6rbMy;_?q>V|xH7=C&inM&_Sp!`03 zXZP1<@qGW-!yBZ_5H(P;b=@Q+;h38C_uDsI?9K}bq@~5p{w0lE?4CK6L-OA9|QmRc+3~s#a4h*IQ5` zx?}&wck2o=enZgrg{fA}-dVZJNLZfV%s1?SryL!>&0D76?Q&f7)gfChqAGJJACLr+ zPOG-I@!i?AgD3eJo=}DJ+jM|m3os+!hX)(S2<+|Nid>4G<|R6HT;oqc=-ionI$d^Q>JuCL5MaGP)`q@!VqL5B+HJB zYFDiO+XJB$aPaU#Hew=3aPSBN)I!3RX{`MjrCL&;Q zVfBs@w6o?|u|eH{%Bel^KF7Xm8VKouE`1+UPdyD-KID&=WNrhy_sN#60?uoR-W-?g zO3_n&IdIqlxIuq*T84kA|IGh?UYj6Gi>=B_btWtI;taP2xX*8Bj5O)G8BDqqJelnY32ven9ua|V@fPRpYA=W z*#FpHZsH~~GmK$QE7bZJdc#tnIG9P?`|Zh=b)MmU4j-B^@m-21x3BBY&fifI{gcln z%dN(3WjXeK)Fi(-_QsXhb4<|ikz1gLY|$h)cbxQ|Jb*`iebswpj zR{uVpgpOBraCU-2v*?<}SgN{l={;}fCdVb+bHfr!8}mdT&?KBuYkXtCF2C2g%ud4< zW;=i92}eUoOzflN#?fzdEM`@wT@C$XX$#u|x4xa{Ic={6@6EMzRP}BAUwWjFn4f*x zwAnl4bdxM=dc5g=A;uwN(mdPjf8iw& zLng+7Bh)G)_q|UrsiEy-C7n!(v%7$u5pC1j5VKlW(7M-irBRX z+lAh}UYk^!oISELxSghcuv~V^`ePb8&ZowIDH{EZp1dP8!T)MiYloLTEMp_99j5(8 zG{-ejGiXufQ-0TU>Dhhex-hsGSbg^~G{={F{dWoLL6yFS@F;J#u9K|TK?|>3Lf_gC zjnMwcZNJ>pNyY8|+Do&XcT2>x8V-|({vM|C?oVLewdy!Bf;*KA>SatRER*w}h|A^QyXw;OOMH$jEk>28xb?j{A)28u6f({AYa?jx;9eKc zFlw%_`a#2nvRu~Xd|+*)$jA8-6o9_W5Fs5+Q`}7^oa_E0QJO_xUWMM3{=LN;%GIJG zwwB?v5~Gm?G%`Nru3q>oU{v%tyUOQ;-(05kLC=p0f7_*&pdJCEd!$UFmE#p%D{LIH z@qllH^Y1dXd|6Jpe5F=WA_k;Q(>~3_E!)g9Z_dK&Rb$y5mG^!t;R#RD*=sxZYlf7d zYdO4OUK|DYN;O}Qv{VO9E;qjzUzGBFCF)}OA;R#UZS#6($M_BbRYfy9^JB8d2OdIVsM7k8Y~rjuq~K^-pT?b0TY~cyXI^%AI?hFlXKC@wgNF zD46R?F;`5}QQTR557f8Q@O@=V7Y-*S@pJlBOJFP(Gz)aX{h z`_nx>S5Kn?FYdP~wSGzF%0+V^pb;*L*5g`Luj~Djo$k589S&*cfA0nQJ&a z>!=E`bQ$Z#2hb)@{B^k)mcP0FsPfnMMX@fmfyc!}^7q(rNqmnjIdjFiD0as0mn&*$ zzGmE?^Hu1nLMd+R=uPnVC1aSjyV9t3i7D)HD=%)8&c9kPloUylav6MNz7pBoF+)Gb zq?(w(^)a9&6Dl~0N zJd!7LHGh<%hnZc7QpTr~9LH~NFQnMqR7%8CUf~V#7{|AUHgPEhI{Nw}gq|%N>U4tN zDIIf0t=zlY+48ypCHQnew_%nq;XY;fmmcBxY;JwvW$5k|yxH@2C4aFY!y1(=aB#+l zMIT@5F6!wtLE6Ks(i6x}2BhOyV1V<#_Ls0_wMhS1^rI#qS3N|Tb<>R9CX4wRe0rU; zaLvFvZtAMbM4y`i6PdM!ZQBKOFDyRm%fV?W6LBr21x+C@i-61!$OPvJJ)IP&sk zNlggz{n*mo9_OQ%SCyV0PdH`rA9)K_Zv2!IhkQK#5%K}rG$HD{^dcYsc~5YE;j{Dw zpZCtHaE9~CfHh-YPtB8w0iW2y8f?NBUJszFFuT9MzdHLr3q+3DKVr$S*vab8R_ls} z21%*Zqk7z@;K)A4&wE7SBMcg&v9Yloj5735orRT=`@}*NI}a(dFjARwx4nqSlA_r3 zWe7yq2qh$GbB0?!qO=}0J39*-BkTkxs20>>^3bIvD5S-0V63rP^xosBW z=C4nKoR@HwHjn-p3L-5YavXt9x~Q0f(ksoCheAhX8}sY%iH=IbZc5An11*%?Z=gxfb<1nHS>fg>; zjABzrLj;rJj7J=lZj5G};1Xq=gwDtCLB8a|^xgr0o+cbav9YHpNWP z-wXn#BEBMkt(=+MQgnylTEE2jD=&|8685k0%B8nMz~cO%$XEH&k-*gmv`IGM3v9hP zr(tt|(wEH)*ged*r)$;#;a_Fa`)G#V)vD&TEV(wFyTn_XpEN;*;+0)&;Wkdh1 z@r2ROF9#)efpfzr51eYT9LUwV%FLwT87pr%H~!R-;1WafVl(;)ESbdN{dPQ}vpeYP z>Afe5_3eZ{_l5kUXim0NlB&bxgRv!aWQB(LDBH-;GeODI^v=xoh8WHi&*xOm@3P!H z7C)Gmkw}lzm^(;|4ussijbUb?-X*yOx=C}$RaSkoRIzkH#+a}2{`{L2ArYYyws~E` z@?OpkihuO^G`aD%&rOo>9^NuL>2h@&ZOph`T+-f#v-yd!d#?sANWf{zre=p(nkVGD z6|Sq+wU?i?#}rH{d9Y+X>CpCEjL2^u>BiB4cVWB^GWn% z;5TKLM};$zA=I2~jxBDuO-vsEy`FRp#0;j&n)(T!F7X>OIb^;onr!*C-Xt!xyxO&t zR@DA}SjDh{E%c`l=T!XxgM24P$nen7m#XpETb=W?X%D%_i8H?AJghxb%AOsW_dmlv zyh1ieI^KQkr@3z4+sv)6#)K_%i^S4Eg$2X1OAR;a2Yv`SExUuNf4?NS+#9Hz)i)j4gq!v%*kh)5-j_&N8uC4+1_=y2FVFJo=Ldy< z_e?SG#D4S2;4|o>H;&k!B(t#ys8OkEvUO;(s~hnhsrz8ntGZ&DeH671N@_gN1<8l_ z>U?&1E{d+|<_n!9k@x8MOlRIeE>}6TZ=P*XvV@N*-ILG0aNmEkrk(98_0LFZngAGM zB4c@U=&wgp8YgvBBVavQ zjvsYxD(dh#R4>g^Pd6j&d?8L85r2A^=f96LK_dOVdT(%*!l1V&j5_g95Ie0H>0e z5BDi4;7=X-%2>!iGa50P&mrbnSkGpjVAliZ(2O#9(+Q&2T>*DgGzQ`@@#*vr`m)N? z-F4TQebt85btg#>YexEm9SkQ7>BV13MCO%=WP?tt4E06&HY|ec%V(;s!y^Qa-M;?m z_ojh49qXn&XF2u~J<-zaFFWJw0B38p_urDsFEuM|{?xsuad7*H+$&s{V0q!{tmQc} z)0%&1uDq7s*{fJ)iW9@W&?GGxClXxFocmTKYDqgabrSf4dBs-BUq1BUs5WK;{k;m7Zo0j82%%Bhd; z`jWt$s%o^-)5N)+N!otsccaMorSE)@bnF!7L~zg9*?%1$IP!;)<~x0q*ZRg}#h>UH z*{G~lJx=D{f?d{JxSNr#+x#rPG&{Rfc;#nF#L9UU%%K0gR-7*h)PMqSet_?6j zV>YgdtUulY=eEf}binU%nHsjScKX@&ADsD<<|L5e?)qonGCgCL@zA>)EOwDG6iQ5y zDebp7YbQe}dj&|*-(Tv_9I5C7d}Hu?R?mac`C4+B&L!{P5Hho^>-4!w|9V-u2TB!2AHo8|N4gj<1ze`DW(H^1pn7cfW1ug<{0Om{q2;d5YEgitmXJ8 zHJY8|pjd61;)a$(-@7>dH7sCYn9wk=kM7lRRl>N;3ii!; zLzScU+y_+~Ch3p*yH|<{kv@Tc7^ys8-^;IqJ{2xT1bvPNnH zoqt#flI8jn{p&4=nw)j42B&O=6@u-gjNjV!H?;KgGuVpld82CF-O7AZ9(5<@3TlnA zt~D1DCweeOsBN6&W`>!fC3X_YvH+mbE2%`ZBUW0n;o^@R&`WXu+@k)820v&bE8{{a zYFR2`Mq%qMKo#-o4K*(^wP6aiR_qod>?+CXV9N`%Fnp=wl2XE%+!Mc@%fpLuR#Uod zatFMy{21=4>09Ceh%fcH*A#trypO4BI^Vi9tO&iO`LC7HTIHV)3-B?;rtBx-GXAN( z0?s3DZ4qS~>o`^5&pJ)sc^z!qAn5NgwO}`gla}^A57xUrKFlwW#8&>!Z$PuW#D{1O zE>(ihMKEy+L+wJxHH+7C|593JUVBG1&L$Z*W=G%KX?;8{n#N(s`n&1*H+c2$VB;}0 z71lV8sqT>&+1l~nlqd)5<>LsttBFFfCPv-A>9)%bAtlmMlYxYx9W?hA$+jBDi z}h5*A5VA5HL8fL3^>y7T)$c>1cT`?kF6czL-u7{i!P-QHZB1Y^gfOtjxl~LUCiXAh><3aUa9 z8-E}CXVO29@UVHrQXlKZHF@6tU6GY`k(KskbCIXJy}ZiPiC*G~W0AM%tnO^b{E*px zQkjvd$EvP+%boa^Pa@2oQmCD4i0pEnxaILw=tX3JeuYe~k9riI}3{t?Mq$*P%W{i zck8mnD#>%a3j60WsrYwoImbG%57+-z#mt!7UqEXeoK*RK4-4o zsIe;HFrq~q^dFDxhG~m#z^skZ*9RJ0H0}sToL25^8~c%BeHRCe7{$~g2W)C2$iqJQN zr^8crKR#|dDs6T7&l)zg`kre!s1iO0lpkU42Qoz3G#rdNp}=Grt^m_wZ9nzG%W6+w ztfHzaTTc39Xzgr&K((*0FQhJLn{sjqpDh?FRPgf1%U#SV3_=e)$?``$d8{P4CC}>e zIN7D1xx6M3u{u-J*7awGUd>a&4Vi`LHDLh~2 zr>x;9Xee;dn2oM=u~825JWT@0t*h_Uljnn`a|3-mNrwEglMku9si5CMmzw9KFU?C-gmsP zb|kb2ilNZiGGO$4>8e-#wRL?y>2AP#>3r2Gr%E#XA`@Z$s}2}zW%r3As?F zME6krEEUIP>R20fuDGLWt0w;p7Zy*Ch4|SEg$k(~C|_ypmOBM$96KD-#+7n3jN%GFYJTD~XugzQ2UQP|UF@&*VPR5B=+lioYSfEDhZ5L8|ch8yYvs9~!V% z3Q5xk&y{iA;AT#aVc_;QveXjyd6^Kq4>AMhL`wU>914Xf%@yDJ6J`HvX>n-9wN+dT z4Wt@C{L^jLuYTwvndRFe`^bG^o=RT+c7WY5P)S&XjKR-8O><+ML-(hXp^zA!Up>cCU5y zZ*4p~ZVPSQ7$bZ5mhGShBMC@!C7@0)g>Oi^H=RZ1HUCg06lvj4+x07RTq5A{$!bxw2L#(MK{T zoaJ$y-SpnEt)i<+)3Hb>RTPhJLYRG$v^Vqj0eMm8wSB!A8e`;#A7dcES>vWy z2`6KD>!$qaWDOEb$!kmCY2D4?MtNP3uHPO3>4btIMJ|BLQZ=!yE=Ky zs;Js})xAtpykS%?0)-3`rGaii$?ZB`qdUzB$≥YVN0sWArP{R#oXh(y4LLfan3dzt%b5!1S&1+%}D;Qp~ZIrIM4@ znVpcMyL6wMV6$>SPAcUYmDX-rn#kuEwe0s8_3Pto1TTcu-YawUb0F zh>9%XEm3zbC@BjVg#0U(n6PK>Sp7U`O0c4W9hcY=LzMw;HYu-~rXZM9RCVwn`6@C+ zk>p2E7P7PX+P{fKvk5-zE}i&lZ&Tu~oTnH@w2ARA2=skxmeNHnN3v6! zvAqPHB=#N#lWsf5j#4+~gKHWT40t!ID#wE_S!p_V#NdpN>(5-b$?uzrXZU^&W|Y=o>~=hVCvt}9+ZMV?M&hD z(=RlmfM8B=Wu!wdI6T<02nU@O9SuS#Hk+MydcSMP)Bs@oz0U8LU-uuNi}L48uKd`% zxz>Nvc`5-8TVOk4}{+C%1uQK!bwRt4fIl$lOjE~6I!5>++l%6;*r||>8vNSDtTOksAoi#)kZ}6`wl5W#y5{_;sEon8m;qDC!B-K zPLLA*nVs6sfhnHf2b>DZMvyrV4RAG~xM0!HB++cv)#gRUms1hOw*=_+VKlDbQuo=zKWvKa%K_Y zxy{vUh927>KF9m|S}INNZTS5@rLa0)K@Ky;yb0Y$lilud=4P>%ZByN3X#w zvS&83?Vs{2kR^(rfFurfpC`)MW6^?_4VKL73JOHSD2YHzMDp*!IQ7lNaiG%#zKW#W zGaO<~lUfDoI|1z3oJZauS!09YDOVl3suO&dk)y||OJFu*mXyfeo5%VejE5~>pA?x# zp#^6ez<1izAiULhWoyf;c`W*$4PSmlxPtdbs9Wr%^Te!4{oq7kOVroHk1}tinm)_C z--e)MeT#$CDSCKWZnmjqc|k?ab68RGd_x(u)lB)*jd_!qj(bI;*|EV6jd|M>oJFTs z`_>lau4g58x{`X;`B>|LA}1KR-)xtUUOPiN*Qsn?|2sxFo*k~Qjc7IzFbT}M9BX}n zkk%rlp*Olp*Uvf8yFq=nn@@dkl>!%im{yK!T?P%tXPT)I?pZ0=>vtj8oU$9YM{!X~ z4yiR7l=lL=U%aj_F9FNW*h&p2J}dTGDl|XaOv|0?BS!{1C;V}?HI9HaE85-2dCNL# zk1aTvIJk`@jzkIAq)!%xX*z)4XXwErL*O9xO%va;PXaeoEMZg`B^+v8Z}6$Z5uTjO3f=hV~rYsN>PApPIWwZz?JRje-v% za92SN*WbZywKvCNdEO`Gc5e+DCcUT4L2)QaaP)YItNLHt0~4dJ4z{oozZJkqL=!WB zWl$ZL#nnHcl;T{ahMGgtw+Cez!Q_B%_I6oNu*uO=PGOjY5qiBDp)2*a!}{2#&@2I> z%l_IOdWw30~oxY~hUCvNK5%~3T}@Wnf-+es0an|7Vn6yroQ7K1c2GBqJ+y2r5yRHndu zG@oYb6tNSLvKA@D+GBJ0ioN#mV}yyLZ6-TN-RRq>?nr8($X4ZWU4AKY@~z~0J3l5M z@FT$lP-f90 z+d+l)k3W>e1}mv+B|dP)!UW(s<*AW$liWO2;y)BmYZkDt*VJCZNe_`2k;7s{6 zTNVEX-fVoV2UDHoZ4gR${GQjpbc7-I^!@3I0Rn$os!fJgkVDX=9=!r8v=8{iv)0Nu zg3~-^$40|hGruiSHhma2R-VcgWZeHcv*egzwXW|NICNQ8ySTH>%Tb&CtO>XvGLwDL z29iIQ_5#ePwk;#QIMOaV*+t8vnOt{J{$Ef90WDxGjHfg|KRGCQO08{{Q8{6fh_A;< z@_GXwsp6$*E4er^pi1Vo+g9#z9{=TlB*spd)g~mr6?Mx#(`IdpGNXm)nj2Uh$wUv{ ze3s4%?O6e&wxrNXq$p7-1ZF5-G7CianP{~3s9xp~`NYW3y@jl@>&>=tQ!@|;BH3UX zg?|2sDGplnH4l3XDBhvvI}s_}CJmZ|?)FJ7-L(KE~F zld~&D)Y@R`vSy}`DzWev|5erN!KHq8X$V>ils+>MBm7;$w0)(Hr+bW34P?Bl3FZxwMgkJ!RR`z$dA{Q558Q1HoZfE+$9pgW2fC*%{=D7BgRdnKj z=1p7=c%4h%j~5!ck)f*A>n{wQ*AdvO7qcEc=e@8NYsWhOf4GRFZ%!|cnO@d}XqL?+ zS7s#D^|%6;*~Xw?1^%M06QWPReP11jW|iW&c#{`%eW)Y>ov21fkm->j!8^r z(6oa;{d{UhDCd7DLYe@y>j`tUedc;l6N#0{YR_^rcBC(9hd0^}E%$fRS-*8u*P0f- zEAH+PQ4X3(&$|{mKynMk8a&j`wrc%)GOJ9GCOx1grC(b>TYilG`fy<+OM)2Tr~am1 z<|SNFdy&FJBZQ{={3pyoL$_Lt@uEWsKqhdE+6E2=ibh`H@RO0zrrV!unPQX~YNCu(F{gcw| zUW|B8CVk6JQ=@V`dX~RC-!;8rsn|os-1_U?C}@*wn)1_O_Qwhuh1(&F)|&gerL~WJ z5c3?3PjCxz*GKd79k%?f0w}llLt}WQrMaGrg)ySbf~Z^HFs%=G6rO(GKzD|DD*+0* z&mH}&XO2}xY58Su8@vdLCSPRLSDj4fzbMNg=Zo5aL*#EfM; zR%>Zyjw&U3Qm}RY1rbCASJfOgDV?$>XYS$6A1ZBtiq5Y3KwgD{ z9}E=XX7+h2jaEF^O_tOoE>duGix7PTr)E+2m?!d6Ua~jX6K29?+#Zi#b+mL%tu4Mr z{rD}H(oJ%!fawMeqW%@jZ3t$WTUDAZC+{fE^*X1(@i_itdy&V)d!gxVfP zIW=6#dW}Lll#|;Fj8L|0aR<{jxauj0HJ7*Mf=3nj17h*HkT-TFM_SxLZ0ntC;h*&m z4;6&$p304$I zr_tagw}f%igwfP5=G?&H4GTmEB5e$H)#gf?pI6l7exDNq?h848qj0E``oaDUvr)%1 z9_o^O>T%c)TGmnp{9$(xF*9mARnYR~`C6U2LU=H+ul#B)c@# zAy@}E>6(N4t-L(vuSB2rxhrj#kZ)kqrmGwYa}z|XM@a#d3cPM3m3&2g1Fj6aV{bR3$T*fMUcBl?wfX7#4 zDk02W6_aRMVgJpwv%=D2>AbC=LA=RQ!b)(SXfXOJUG7g)_^go8knmQ`Ko+hN{Hd_y zRayF1Lb<`!P2pc8ck>M2bq}1%=wx06ecxZIRFxfY-=R(Xk(0OKp+}I~aBc2#ZIk8@ zH}~CkOeGH%8B{hSO2jjGtfv3^^@}~(p__f}6R(#6tMh*bUT=nCbAUmIr}ES|NRrs#?3lM ze+Sg~WO}-t=$+FL5=91Kbih?~nMw)V__+}*_$66F2}Q{u=@p=0t-AP&fiaPq9Vc}i z#TWfghW7OjdGU!3wMowX5Gx37v_02#m{83o5GyzGyDtBcL|J7jb>A^x zYFoXDUGzL3F$)kfy)0f=&z9OL z^V>aPQRS(UDim%7$$rRdWQjQbsh6ZJ8IOCzL)-S$r#r@TVApOj%e9}DCaWo>iK{?M zEPlYYhUs|myZM}k6{BN$W$*Hju4}*H-ULC7jFhR*^uL6Q0#ijE1NrOja|xmI?dnAJ zfssTqho!7<%6*+GK?EV2^%p5r;lHcRHWnKR!z1rB;oo<--iQ1)&Ko8Dvd4g^seO!1 z^?4SE60q|ypVRNTak>} z%kBhV)kL}gn~c+T4KC}_@vz3qd@OHaV-vb>{4(&rgBj0%0IGrq2M3wi5-aR$z;R6{ zf!|a`>~P!&gOk2E#*Z}-Dk6TMwdYPo?Hq{|SL2jm%QAnVNb zfx-GWhaLM{2h)=nMDe_WM^#Q8YNGt>;~h&ybdY(K#OLf6LG8`Jv6v+wc8v@-@KSt zBF~W)P$kP)85gOj)LuLxLadlV5k%c9~AkM9~UF4dh3)c zAZctg%TYI9);f1?3LS<)EyAGy35pW;p)C!>rT@kVPs#Y?Stf|RB zfZ*Tp#%G(p7-&OO^u7%0p2X#4-~#HZj<5T>Q{a*ArZ#@>(D88{sqJw~2lO0WHzYhw zLT2znxc&I$#*~De1Bpbw6AfwlPPhKO>bul16G4`Oj+jSto=f_N_^iZJ^AKpy*8N8e6Wgv{LSH&*@ZSKK zX)=%{Dsfl+_p*372J}=GvY9WvWT*3UYgckf9+reD+q$*Vqo-yMD=#bdUeN_(0i-E^ z{u-(-q7+3M#?`@{(absex*tMJvt9@h%vS}`(g+$dE%o%{%4B&XzxsYHJ?l(XxzA=>dB)N~ge%^)Jlj7RaaDB4 z{O6e_yr%KtScGw8=$)#b(C~ue|3lV!N5k1h{aOi}Q<=p-b%=$(j2qDPNTMDKMl zdX(s*mm#9}&gi`}I$@OPb;KBL7|!E8=lkAwt+SRt{h>T_Kl|SMx39|ws~-#xm*yv} zlr(pfw;O6cI*^u`S#OMnT{yJk8s}|F;J(ZUu>Ym=x{NPdv(Ak2U;EQL%jiaiG*ag0 z@mwsWOIoNmy~0&3NkIkv{uKDL$d`3bE=KNhN?EskX$Lc6Szm7d-qsrNv`DAP_MF_K$W+DR4)t(MDCq8uAZJerVjCFWy1zPByk|=#ebYsbVl3rWq=r%cj98@~Fo&u6M zt@2(w{awL4a)7%%T8S#QUk zoZqYyBG7ZxsHU#nCeZME6uvO;)En^Bs9=rHv8Tkez7m3CA;k*V2+O3Xm!+`?owGs{ z6c0uR;s%w<$q@j?Fy9;0q`XAFK3!IJfK72-XJTu^jvW)`tcA;f^OM@JrIF=;$LtOJ z%uOATQs8T48r038Xwb(dD#B}7*>7iHV?cOI&F2bZ5I_31MATK@(4hQJod4RV8{@FMu65JL!#tWKLjZVBZ74B?kuzre3$BkRovh4fp1v7tyM@8;|(TyDazYO@h)?;V*UY(rf>bO9SWIUIJ4 zbeB#C2o!9!gtP| z)fXOovNHm}7SY`UEPbQDZ!X(z(msFwY@$YR=#uDk;`sj^&HA_d+FgTyChWD=ogJGd!z%SECFxynK*;DAv*z(QYz|Toh17C1r0gc}^F&ZFlPSHnp+&R%@M5Hg> z(NQt>gCI$};zNZSp%KD|e3g8pB!b-`*BtMTk_7?QbHnfjOO6o@J!rZCJKGq^+yt}A z`xrMnXo(m5{`64iQtkYU$IZAe(yKjYB?w&|?xlwdEn_#N*w76vgtqNrs0jWZ}!M^GGrrG!5+4J8m)R1UszNWNpYMT$0<;7c9{X-@G zc=7AVq&zk*IL?o{hgI^s4_PFI6jR5kLH=>*WBESAB%jN!+(`Ab*`~HC^WnWUV))hh zIN@@${`^6q8jf~Krhpqa1ol3kdhVm}t!bD#OX`y7&Ej!x~}e7xK7OjWoyW`W<`;Uq3v#A0#+eobT2 zl@=eJYk7axJ2AI+#QpGR1^KY0)X9et4T)V=&CIiy$|-;LmmODZ<&CVE?Vz(L~WAt z$~bOKEY3#MMK|I|XUMJ)(1r{YxVtQx!NPWuqYo3K=5JuX8vE?Z-M}ry!`Ggldw#^Q z%;))S_ii~{XL@ggC_z3sVoWP!{?c*h#2>xt;0#nSN>V)fK=bvBQ+7{C5B{ABu}cX5 zP6JGYJWYi;i#(J=+%HebP{%CtQWZb$BQA7`^U{G`6lFC`(@;yX=ghsZ{t z{kv`Cw2Ah2^OUxA^&El4tUg&*-&qo3p*Nn3iRY z^aJUl?pHpTv0XD4}a)@L<}!OG-=>-#HJI4RoOqcNbHBx3NQaba}}$Eu$M!ZBK&%j@^hL;xP4 zi7Dg^fd72|Pt&O}q)3xMR`x8rJJf5`83MGGAk>=A2q`!f%rjgyJ#Q|T=|oSa|GDsS zw*Kv$%B1kUGnf){5>PqQ?~3TZ{S|>2Jzvy!L>S~|&=$E|=U(Nq@Tjs1_m7povu+#( zrJ$pg{H@+cS>GmHpfvU{`&sY!rV;ftca%0fz;V5$4?Sv5G+Pkt*zHOi!L;QskU2Uq zo9TRl=!4IIqt`aAx}GL_tnxXz)*9oVX&oK=iOe|a=`OB$tTz5cja0*w#I0v@W@ctk zhBqgMmAV3ZTOA!8CQttbfVyyPM?C=+i(3lx-52>=FbDS08R)W>(|Odw^0k0I_+~!ONzFbQjdLL%k zpDHfYv$q^ipN-SQn(DyvHD-mybyLqqTHHVSlI#k&?a$pZ!}G$qT7{NiFyQt4$=%%@ zJ*d_CC=EHBDJgl-dWqP9*!6z;cPUc6up3A&DC2d50qCd_AdNGe*#BKUS>Jk6sy+7G z@x-;(bo3W4e&Cv z={K}WJtX>6KEjj%(O02$K|Kc}A?d97-wwaFLP^_qz}|JkUz>0TUD#{O0j)~?ZPnZ4N!v4$u2 zLnS%gXh%LU3ANU&x)=T~4ZobESaQ+;P}Qgyn;bWf?Vy_Fw5{A_NIjpv!_21XrEMVu zybiB9{=qDJGe_COd{5wh0lHy+Me3$JiYBbD+YZvQH`9~HtVd_7ZbYDF7r!#(z+{&~ zY1(TA>>uoxSW(;N(ff)ve3TIoa!|^I+OhAm7nMVeKE9aIksp;`rV>pnb=h*(W8Gkq zJgMeaWt+*UDk_nfyUCmOS8o5Xi&Jea>Kftlpg9{1( z&_FGcLi>%xM%Gy^$%V(Ad5SR6Hm z8nO4`b<+b6$Q#5(iJ#6*&CVu`0&Fwwx$)a+(m#j*8uzQq42DBR4IzLLw#cN~7i5Al z8TZnf-s-q}6B#7uy3ay7sESqSO&f&8LcOpU+a7)Yd8zW=F<=W$#E&naz)T)@E(Xx) zrNqGGNKey2lgan1w2i{=nX$;G!sp{>9+VNbn_#yZovflHw^{^t8--h(qG$72hQUsL zEVfwmHOlNox?Tj?Q9vGQl4ub#E@6xPhIs=y4eMMwsRbP^CmmyTqQdLsN$mQSB~P~Y z&?-it6}>C7Arnc2fopAQm}l~7^y{Adz-$fp@i@*vy$ z)vPIas@zNuZ!O|vP)|vY)9AHD+=84`FJQzKhUH;}%A@foo6G7fy7&R=Vi}nz6U|G( z9Tc1dNZDAsEV@CJGbiJ}fKq1vXkqP9n)%{^&pGDamGu5exgU450%dJsH|2 zTRX{Crd|_AyC&#sX1cQtiP?~FPp1WB)(FgUxReSQ_W_*Tp5(@ znP&aCnUdm!N78)5ZF+}g6AFmV^=*P;`aIr*L-_?b?6K;0Y)7ye{40R&ZejdSMXa@T zJvlSI%0?D9?nQ?B4RkG7l>lQzFxjf-d*P|{0baZ3Y&b7I4WEVi%{P~wdaUAHZFpj5 z97*)EB-Cn@iN3!(R!AVU`4mfXL=J1@N<;DhcVTm#514I5x~ojFoCQ{W-E5W`=D(Or zel>f%Mm9XDIolKxvWEG&zXVr4xJX9kLh zsM72Ac3A*i*88n1V|yVnMF_V07%Zi3;#$?5F)Tp|a&3GL+13LkM>P#Z4n z@7M*Ta}SzCCIXtZY5T)LJ0Z@`2-PjIo)NkeIuN=fN*VP46ALOc{*c^=ssvmmY^iJ9 z&VI(v*X@x#yee4Sg#>=wwYe|Ij}b&d@tH!)YK#1G{Rkm=N|4rJkp6JR~dQUY|`caF+!xunHGAl1i z+KO-R>_lHIl`iO-{`8&Rh42;s;y;tVzn4y+xF3P^_m@*nqr|LvXzE(;4!gP$ao<^z z;)%hj!EUA%D`d;+{w930$Q&JQ`j^NL>%KREbbD3@+}BxT;rQgIADLeiaeO%scix)w zGB(4BkmAtAwl%oHm6qxPn+L58VNadfnn+m07T>t{GT;rCiG5iY@DnP`x}I%b&E$fh z-Z5_>gLqZL*bZIP;|E>&Zu$ILfWx=pn-%0Wr{YpIF9*i5_VRB_?oqU*@}!}_s{=se zy_mX{b3s&;ss$nZ`^{`BC@-(ZROxv3iFMZ}yL|ZBrj9#eDA`?D+-ME-1%#*RiC;bp z>(AND^HWMH-Hqb=k#fo!zZgRZH@o3iVi?KBl!uH3O+TiG17f`&0OiDWTP3V+1)K=ETwF~Re+rA zxFri9GuvX9pM-7AU#{lC-}yB@RUgLe=;Mvzo-E-(2oD)e8R=j}g8o|{Xll$pjt+Ts zRIh{tLB!teHaKMkxG%97TP7cCqXX^p7h2DEYK(>I!EH&oqxlk|CqAc4mLrBYq=!c^ zpVR7FewaYd|H65{f4|25=L2LtlFGjmZg^!PvRm*AV126qNXx*9K8e#xKF8H=)QP<} z6L>|YFJGRkk$a*Q^(#|pLF~v9JCA)|XA$dOduRrZG*7q{q0-+63WOD7l8-fcoR3X> zRHN}u(ApKc1&wl_D}ue!zikH~nmu5I3kQuN6Tqp80^BGz@U z>BXTcso1U?!-rtq57+-Yg7f>$?@sFH+cwXrET^OKcI`%#QwPP22Yr86UW9T|$v&~i@z@7_OIKQ^ z7%X7WmSymYt{%|Kwc+xyyS6_(z~z?`J;2eX*;CV07Toli^_h7OoPPJ%m~3&$Iy)tdCc>tJ{z~m~ZknIaghnQ< zo30sM>uFK=WVS+cuC1(ATo=nNs(=t7eGC-qCI zQKEVjj-9tclMB-^-h;$k7RdlfPDs_kEgW{; z#65!a1F=e``qEtzaGv*xTGF02*M^w(Z-2v*F;phGMRlt)T}68%sgx=7&T5Grs@^+- zY(U621lGl3ngY2@*``ALq2Z9Q$^SB-++wd4=iJvVFtx00GZnSYA}O44UZ|XZn0Z`^g19#` zxqUVpX}-C>l%xIkft9^U{^yC^iC0q!!&}tQ(ogt0lA53-elmpuY(JvjX z1_$Ha?R|x457e(o7G;dhyiXITGPI`Qj(%rn*Bfy=PXV;rgH{ zvPGPESEtcRJg%|l`rx+Q;$uYpmEA<2DkT!_20; z^YW$=C;j}hlxedIaL0^^{kT^kt$1%E7*tG3P|-)LtJWo`gk=5AWXDhSSV9+)&Ud-7 ziNQ(Hd{HBUeZB8fljVii4k4{C_5XI|T3(b+Q=e0 zZldH^=QU{FdD^=Bg3BF|uu$bjXLJ$!a%3)FD_g#j#U|BF#BC|v}CFIFWld}ZXWWPWZGp2>ZQT%qTCRm;oq$Rm; zOd>Bw3;MDj(*l#Y%(+$0TMov*a%}l`UbaoA2Ka|=)M=dh8UESbHSLR1R0cM88SUW1 zDZHi+`)P{W+9XF(cv)J2r3!^ZujR{In+}!xbql)@NAw%r$b zSvdi)PSx7^>C4O2^y~3S<_(eZXiqGwl1fh}A7>HPAz@qNjov|G7t>f=3oMU2k1M|# zk93`=sa(`muHiiQ*IAXX41I{J{Cm)Be7)6h@x0n)&`{#xg^kiOsN<>S*Vza^4Rmx* zWc{5aJy-nP8kq3k9DIUS=MQ(9n>F{lch?vF<3FRXGl^)gpQ3>r)g&NvQW(1KQ9<0c za@~GAo2==MsbTZq4E-Wep%}<_VZ%lCJ?3OFqYJ@AaAn2>X0B(BO%~_ivBg`%4$t1UbUrYpSoLCV!ZKPl%FMe7D;z zTs3i2ttE{VG6C4R^-4Uyx|w*7pw0ottLnzKt1w^znOBNxkJs+I-XHBZVWM?*UFf-% z$-H~UFMjY=79>#6vtTthjt-l>Wv}n}$@j{TpwNoq!-?@gt>WkcA`77rtPFCR{PFHG zG$E;{)(fh9|07ph>@z49ou#GPUej!P<`O22MDA(YB#D8`*VIM+>Z8(a$nGsjqE*&HyMrg`_ zhVs@y#Zb}XhOJNgefVaMgytQyY2{wC2i1QkTxO0Al?6FIKmL2b(MO%udj1U-k_!i* z>T4m7n~I}`4r~8y1ZMl{0sRh)TCLq;BMP7=a~`zagio&a)aS^Fp?P)~%0b|HCSRZP zmctMA>6a%pb`AG;TPMjNac-X1*OnV)UfoJb^yw=XfR9X4$F7o=Ec3x*Q`fJKgG6zA zd0``~5tocjbvg$e*q!YHh-mgdaPu`>yF|YfYY>JiTzBsa;g^f5_;7873$eh{{K zuOHsAPjnaI_9BSC$BJMuzb_5`2U057YWta@1=$BQLw(ha;71{bNUlI9BkGrDQZc@R z4Vr)%usDgyMAl5!Se zO5Olp&?));hoAs^Z}3x;wi8y`8A`9~U`?GBLmFgU>|?im0zaF6z!F8gbO2us^e zuiB$y^AnKNe%aN6eX1ce)Kuh_KRpvhHIrLL=fkV-fi5hxy$V7BR4bmAGop~(U&Lbc zm|eiX_s@*}w|QoU8?Z>ztN-7(QNcfNBkMnao^ui=#7lDqIm_wj@aH=ixXfXp2H99q zRWsR(|`&-H*AP-7&nkfw;f^?oDyz055~A7}dog zVl}H2X7~jcMXHS_;28L2;6qk4YV{af`g)JHOh5s<42!W0wn{XQNo=Y{Wr@5mgTT9U zHze$wAI^4gkG&ck=mBCxOaAP3)7X>FBBb)4`&LD94A?bW*mBHO_h_;aR_u|!M78~* zcf7aIrL@S1^T-QtUptCWymo&x0V7qwZW}CL?^P3BTPzf%wA&DJL{hCZvz?airaz$vyDdKjMtZTK0JqhI2FTu6xv z>Z4r0&aO?;Pv;cA2(;`unavA9U~>4@#su^G*qeC3e}dK~iZqHRE|+hv?+T8Ms~+I% z{@Y|mMc)Q`e8YUu#fJGXi04Oiua0@o*^Th&!A=3wQu3(e*+S)c6A+MH6${fvE#F|4 zEoahgO^y^wG_6!rYCuou-46%lt5d_=xsKJcdtHbej$@g)2nA<+^Xj~|&r!Y65-&Lp z>Ap9H@>^7ss(5~qSKFu5t;e0iwoTUtYQ7jxfY$B;cDJv|1;OVQu%Fh;wG$NJtTsdj zN={%|4dUdt(>oF`nv+GIT+r@>An6Es(wydGr=m&(USLD?aF@jQBy@5dZ}1oFhEA%g z%eA9c$Y&i+h=;1-_?GL0O4vG48-x>+;%0Y7Vd6&7YDLDz#K z!5@Vyi^+4`Z|N!;PS*T{e(biN=(j0aSbg`2cY7zXC5L_Vq9;6p4##Q!9>)kYeUL^R zzIrTtQ0mrHs`tTm_;vav?cZZloFNgrQ+-8frt`&S0#7Nu{*&cc*QInNQK@p0a1rph zr5>`Sw~}eOcoB>7Zev}!B<3hY@_o6_0mG|ODy2)h^Y1Pb_xkcpqa|3uKu%SDGEY(7 z5CFMORs%7uWS0MYoX(6ode5Xr|K_v9-5TTHck1qF58_z2KbYOX_38g5Nf&<6_i?~o zrH6-pRcsD>5Q`e=+^nH14}>h}cboOKy!<%EemSv~z#mVKv=|f{#cF>;VG<%edeQYHymj{Qov4(y1Ubq0`3~1#C0{Du zGaQxPZtcJj_EF}IO4TS&s{C{@sU@Jn5=(K{Vt-oZx7%IB0O+OHXS=2g>`x$LXLM>0E0(s4}I`{xQ=psWHHRH{ae$UO3SrE3IyN#&a{U zaXJl_+_jraCr*(tZDiJ>JA&MW8iBPBrHWhU`97g5d=M7vn6wGkS^XrSv#ynUs}Z@K zh^vU~l~hjvG^;pb(fx{BFfXccwuKYCEkpN_j3seI`rrBip?F(9a82JPIZ+Aa-Y+rfCzS7z)BV1{k?3Z;kP$rPdYSLxb{qo~m zT}>1mtJ0T@>ia!k@3a@j1L437I@AUufP~xXl5lV_K;})mS*M z;4s%RVDjMYYNBx`2J4Yqff-!P@?VM3z=c)eKvOnJ2jheEGdwRRZfb)UaI( zA~p%kT*Bp~_g|Zl{^JjA;cEql!-U6j@OOzGC&8@qCe)0rx`;EH#(7hACU6;+ieNzKo1v*iMC<0oeT167;` zj2f@}wF_87DINaR@)c|^Y223VpZx6zXg!QX4x5iB(9IU)V(HV=d(hj6aHM(y?O8+L zKYPxFTwFWW$wnQp2SZM}HZNyX7XNf=`e)DEj=b@h5WOnk^xH*9p;Gm5|Y|q{a$4g&Sg| zSd?K5c#r*YCfDj8Roe;rRecw ze`@wZJp$>Pa(oVC2t1-gg;pJdptUXQ(_fV0af0|g+9|45?;uMuy;>cnp?_TAGD2Ax z7#^jw!N2u(`n|x!*3J04zINK;m*u07cjE0IPYO7awNz!R0t98@vASx>wl3WHp z)>XSHYwFd;@j@^pTJ>rhLP>;v5NNaDWts20W*;%feDcLfnD}VEB&1U2NPDky*KxXy zD$sM_n1Aytl&uq)?8@rI2u5(sO;fn6KVB|B&j=PIp?(H<7%G9UJ>N@9G z%4PmuZm(U4rEn+XahWTw<^=)@wElieqZ7KT0G!p4+5}+>G2xkOWYIJ}MuA)oN`SL9}Wsco0uFHE|JwFEI&hE9-GeK{e1P`)j)PjPg zY3G9tT8lVS>s6P|Eq`8V+MpFXvhG^*|Fi*8-k!vBvq)ku?|U^LHw9jxi8*Z@lkOW0_&F0@*2-9ZAKR51wd4^9Gb#Fs6J`CJZP4TkyXHzUI1u~sHCy45ADGSuj ziax}8Fslp-5H;?0Id&0nY$;*??w2ty4l~UmpTHvj(>XhsQU0o=joP^n z7lI{vK~hq@@=%_>EY*mVtx-c}kC8|PM+942ikx(va!k!IM(GQ`t?77=XTkk*g9O}$ zyDv#rZ*!}83F5OBXl8!%Rn8q*FKR08Fv9HDCuDxO0{3D_R^jtn9em*BAD8x?y3Pnf zaN>jjjcr1)#i+eg*)It^;f|Uj!@i)NY#N4I$EEYAn)Y679l+R!S1`#uqmDDb=j=zS zFwutg+K`$iV6VEfCP<7{Fzig|RcVq|Gwu0C9;8O#$^c5CLkf_fDqDZ?LouV%q-@L2 zE+XQO`TOyX+tqDxsjTIpv9Beqk~MTezt{iNkmx&SBHBG?Gc*NrZx_alGd><~j>vOm ziVC(k&+4m9zRK^0X5X;?mf8YRKlTk}-^tF9No`^+K!{24A2E;Hf^8DO*-O9FNcQ{p zT6*&w_zb(W#aO<42S0|KHJ@LH%84-oh8DXWKo70d($eyZpFg)Q?1$P7a^X`S{9tnU z#$C$uuk$HkDBc|a93l;DS^IUuKMo{$Hl$~xZzwz&Xnl< z09co(P|LS)Z4OdppcQ)F>S{n)S6`R6S8fN-HDfc$B)oQB;%eXPAJ-bVc^H4!1C4C zdBEQ?kz#ARBTjeiki#%b0u0?84B64M#XigDD5WB7AxcC#-4pFo&n<@$d{j$)5oIEk ziA;nc_+S_nEZEFIw6!M@4Gb?FRBH#K^vm0>Hn{QuQSEO_y(>zU|NcR4uY8vY-CQOK zM?gUMc`L5VEg0dSIuvN4bbU76naKS!iY_r1XQKhF$L^>`d#dMf%mYJ^%QMom>E-nL znxlgyGJ1mHNKI!J#gCSYjV^2RwE$TKh#j9je(6r4A;b5~Qg)ZJz}%mW$XZYIUim_W z1UtB=p~jip8XhY98!$WD0-IOb$N+1B*w{smmg!(#jE};4| zyJe43iGZq3X0U*|W`o{uz|zY^kx#0!R!1E0VW{PH)ybHD2xnHQyTsA<9TR?bqyqUF z(GucOTSdJj5^wreezmt-n`6InI%3k03$w8gBa)kPS~@=s4f`!BMol#mYJPVmEMu<4 zPCs>NK5pKrGc)t%7b>H^O_=Bum4i85-~t2Ma+0w@+uHwGYFr54MjogPl?`2xM{VzDJpB{6Kx!th|DW|%T1k& z6}TS@07A@ed&!Xs-SN%duF8Hw-21)WOUy4p#?ORHx|l=VAN&Y8iZ3Hp|L!DU}J21X4PhO11$!+pS!F*=M8ZpB=g2PcGE z8eR&m>vB60zY6g-r5*S(TjuRfdu)a5JFzf~5bd?;6Y;X=4$MSB6onXm0LBnfE7*}R=Ne9e?j19dx~TXUOu z5RO5UG;zsiAz;am=K3)dSJXs9h7`=}b&}Wi-SSo5nl;^cpFLjrLW1Ae*;>7eo{^=P-xv%;iv*S8xh=#sFE3G7%YDZUfg~16=R-k!F|pDtLydRS@_}o<%gRt>xCOU za_mQ>)noUUxxPGIrpxY&Q7D-jT74O>@H7FT9dH?C9?!$B#&_Sw@dH#e$v$a2M#=rd zqPfPGR+vrs%W`$;KJ!msg39Ka3K|rKY^W$o8KVw)mUVNeiV2Q0^wtLv5Xxd_m9GtA z?*+RlT+RF`cl+F9zUej)AAFVlGT*n#72k1qPt}QiJK*uU_o(!I$<$t!K(XR zP%t&BZFc(|x^n5om;mE?z*f^0LeJ+cu4Z_Jwf_&IzVyMsHgfE1w;uGeSdUw7RMIwx z-LOsppP0Jf4Pqn7FmW6qe3#oj%L|{g?aHYo&zLg!pD$k;=Jkk!;QA#``Ct+{&RT@5 z&w78X$RD9`>V$-Z*XJugCoY2?R%I(vghhpFb1cN@H*X_9DS!D8<(0yWyrUzhP8h&3 z(=vuM83}h(X^5pQ`oslm8D=6$F23jeQ?BNLDmPF38ZxB8{-G*svqcgV&2aAVXSDcB z!i!+bbJ3?w z@NvA)oyV5%?cGIX&+ALn5@JFBBVDIbG zH2WO2d4`Gn5ldb64L8w(!gS=a68gcT-x_P2oxGZty;P5m4g^2B9at37h-xAYK{^oI zWdl2}eV)T%`d?)YAIlm}Kc`68`=|5llMd*i`?gy)OBeb_?3GrgGE*Y z?#mplLr+SosGl-FWcbPYH?{E)C%`)FlGBm4i*Ltp^Q)T9_OAciwGU<Kd(a5xkQ;u8;RJK_iU_r&C@@_u+Z;-QS3MY@LBa)hKJKo5s!hkmY;mCyov96OF%;cRieY zzBTzcoUD2!Zq7>?RxZzAmP+~uVk1HhV>Z@W6Q^qUK**i^7tE|5f!wD}M%$0&DLFc@ zI>jW<|2>-?td;i!rB^PtQ#+AJUR8`bKc=ApnpIBW&!0apf$Y89XzzM)J!YEA*b?b= zK|D*by|TW2QjGVI3uy1#zHR!pBhSv&(CqT#^Qu9*KZVi6LqeY*5-!x+O$Vi#g(#Q4 z81PG`CtL{M^|O$2o*Oc*nSOjmQz6Y2gQ%wx=rwBcESSIioR^+BhcLMZQ zdeUA}OT5aoV50HaLT+iyyf3B4K0pLke8nlE<~ zp2j}9EA#xV3g^Wm_PNt3sUYG)8OAY|opIH9+Amm`Z*x*PcVLe>qLqU$dKz9&n&QlF zrFT_`MUkDny(DGpS3(y~oiJ@U(#2B0&(*BNPIx5$aZrQPH8gzYl$XEtwDMBMuVLR4 z_A*oCwRg<>Y`4nss`iYb7TL1D>0{>C81;vHgZ+gCQ=Yka+3H9KSPa$shY+Hu4R!UV z%RLB{J25iwW&TTd4s?`PZ-wl9C|1A<3L{-9CyBhW>`r1kPW>Y{R6{rWfI<8^V&R45 zw9zXVp+uT*u#}h9O?X;^$dsixsaBJ@dH=U^aV9MqP}~&1EpxpjIJ23@D5kl-&qybs zQjgr{3c~KW^P&7s?Dpo)#N}vTjbbrvtN#5wB~(-i0~E$NvAG$7O0g%S7{ep5NRwzo zymQF(co*{?MRi7|BWvjF3%Wj2QcN^MczkQx%2+k6iGFCxu~;3DWxa-=+8S{`a4u7hxhZnuzbS=HSM`_;dp?*>_K@ZJ)c}Ku2sZ-(R!EQ*J zugR}qysHs>2x=H7k_bC&uk8WIc9`@O2m1o4Q)*Ohr=k!6B^K8x(j=(IR zq7U(x-67(e-}h1|i!putpx_IMpzyPtA*Twpv zaZcmjXvsl+EkjP>aPq;dj=+t?1-l>iZP%WzU)F)XDf12H(D&qQ`v1L~BihKxoO<1Q z02(D1P$QH_&`BD&ErHBw>O@R?A3%?KsZP%Qc;5}aGEaZyXgPAyqi3kONEUTh>NSrt z8P`@=tTEb2chew1qxUEdVGyU$4JGqhoBOd+?=@IoTs)V@Igh z5y`f^=&=HW_~*9-d>`>&b%*nC?Z2I%mwi3N`kX`LW6!u#y`s+B-M<0RK>?ob9E@9` zSV+952Mm(4e|nm`r!)6h8ockmFz754b>kKgQ(rL9j%E4KLt>Re^^5iN{VU?-59J%2 zKdTf%NE_W4adyaZ@Hz*h$r)KgLPd5px9ehK{kel#UMr~9kPN^aci(rD9ISfpMmem| z?J8no^KzJuV`B6uett0AfVNKm=|?n9MK*Onr_12lN$-YS3w{nM*F5Q>e3*Jy2tr^I z)6j>izOSfNA24WTNkLKCmq!u*el|#3`9YP*i--QwJnyLrDbBuMw8vNz$`9s%^&)6Z zwV4jy#L>UR{{87sSx1Gr=J& zzs@r53fvtTiiPiS#?Qmq7o*?XGWd58e7I^2=`Y&jivPYZSq5+1Vv*bvmwA0OaQx;i zC1!|s{5h-MH_GLv&GFcIm>AvSBNO#hyk9b1e4fOrA0IQHePj65{dpoJloh;GRHV_W zYB(X<*JmMlovcOQl>6N3h6zDw^4)K(6}UTmS`(IDMK&vGYdmifR8*H1X(~|v+{btn z0DJz>?FzqQaeUFbOlNmcnjOi0$IL#SmgQ5Vd7y;=LU@^KS1OZ?L2mhzT+nk&NA-uk zq=rMmg_^+AyatI?cO2CZG)d4yF|*^0Ez!4B7sT{eA8_YomSdG@pVQuWZq*Yd|2WQ3 zQ;NN5L4HR7lIr7$N>e#uAmW)*QldaHd;tKwUr0z8L{t6W@+J6a*5u9T9HIe$D!Lf3 z1(!j5&^wK*YXImAfc;=EU1HY?93bzda}mu zl>tX)=yS$8Qu(*t1?!Hk4EIAk8NXG*!$rA{_tnVbh{A#jJ|5knedzjNk4cgXJ@umZ zhodY)``x$=2tAt?n6P+P4&eet$?uhJlsO%&d%DQCgFm@9s%_*9$=A@?GQWQCkYYn5 z=x5V3BD(cnnZN+GCPT-c+T16s9He)jAb$L5A5i@>|7TrZ#gZ)I_1g(m0z}xmMyQ00 z0wZ<*+7Lz{hVw`3n zKPp?r=uGPSpectKg?IK0`o>p{ctg!TyDNqv^i}pwfXU?aH28HU1?+z0PwKMc&J>n` zPD9@b5$4?bxL@{-YHmx`S??&bACY~RG3yYAeyV1rRE0vH8!o)P#XO$r3XMX01KKZ^b77csKi~}(PaF#)W8(OAvQZw&E(vY8=bXyaGq4wRJ zXIKx(o4KTUnu@AEK3e4MX<2U?IEz4D1Uue9&DZ7Hk^A(nY51gI29fpnLn7BKc8E@E zAY3pA^z#ydw0VfvhsjN!-hhfYDl%?ckhxA>JN03<;=Mz^`1lHuoJ%;zn15dr>#~*s zZ-nV?-d3bCjgQWo5pwAe@It0!^3f*bbz`-C#N?_EN|QNud%EW@{Fu5a=G zmcr*QJ-V)%+i|&$Y$^}iww3!+8O?p13hnG8@`IN+FllGwwk{u381Cf$;^K(8+s_q5 zIr}v;^I_S6;biplw<7dRex^B$nxO%>9Ft_^#thN}g%7`Rl2irq#zwzY7&keEa&9o; zKqVHY2<|D;dh;V5wWRzWm>}2;I+t4UQ3`)wJ`c5wwIOL#nWel`pI5L-PN!` zsCoKNvyN9~KC^CzoEegsDfx%L&By33R`<$l_51m9s8%D~#<)txks6hq{o&)skGECS*L7`d zO5i|iv@r|U*=aOQP#G9<{9@Bu7%cjq|KHi4HhZdGH{9c1ae)3Amzc;53^}Iz8zACd zgKak$``^G-*)=v~Qb|;iNxF{3<3f&m=af0wFZe=Z{(P%Z((sK9ClSo*e9doLsu$ag z>|||-DCqvDqCfnx&#$lkkUBL(oV&mnL|#c1}CcOqVeFY7>p9t?^YjKBPFea-hO~ za>zJ;`|sf=gq81(*7>1J=9{M1{`2(B zuHRrSxe!>02B!~l*0gJY!C*HN;exftM08w$sk=)6ZqXM-#<7lvkKY0K$M~ZIB#NA5 ziUtJFn_{}~H_!&{UUi@HfB?fw8pjyT-GRXsJ_&E1FLHNMDn(~2;o3h!TMi>Xm6j+q zzrI`TFB=<5)cL;1VS4Z_zTtF($}l@If9d5;^%abEk9wXE&_xio=KlEejrOcS6zHS? z`OwPwH{BYOi56EIT&xF+|NZ98u4yw8UN$Lb3EH#x?A3+K`TS7k?I=nVA+TEK6%^D4 zjJI5X(%DJ(I>v!);}i`A6vU3|Q%#_A)R3?UqZ#)Pq;a;Dlzz3ME5^cOG?t7sB6D&- zXp^Qg`*Lw3**_gaQ$D|cd7kcAqI#1PBExYBJ^~)+xSz%Ra@%3&Bxa3LrxRh~Gla{U z&G1efQv`67^6{ol-H$ld|I#df=7&N)#^Db-0~j{ zdggIicL&i`Ne@?iulhYK&BT0QVDz%EN}59UKDx>clNlWsN~tFn*e9T1lWGAk_MP~Q z7D|_;ys#K2A=hWfsh=IICV+i@tD@^Y|3jL*)hoJ^`V^Jb?W&jAqOqC=b;tGcWG0#Y`jsfj6{t?|0&W+ZS znY#P>Iy(9I3`LK@+QffysROYxKZylsad;rAD~ zB8Sg8{mAX9z;=Ob`g$5A>rYy?4RWv#uGA@p>OE+U7d{l1w{674>kI`UbjROw4~OqI z-g%}NVK5Hpo8^b=U;GFYCQZGi&5w`QSMH4Rj~g(R_a>vGl{nnA^>UB)&>VKUI$S*x z{+e?# zyG3w^=;NQ$7LJivHpGfci}QV_;oPpbeatzp)4I#BWH2DB+}MV#4-@AuU_8Bod!|6| z>8oT+d)r|<7^_R=vfc2iROw{zb$(ZbNwl!i*jQ;DFf$;oF^@^&$v$<3+KZkicG^68 z@6VVJIHHT_eS;sZ#EHDYo%G4lG-3Z`v~+A3m|b|y!Xx3Z;#GZxqAJW2(m}yDg(`pW zc&rz-Gzqw$${<0fdXbc~} zqV=}FS5zqZdmnN`_rk_oi3!JhuOBbEO{$=nT2lVtmlW*B?0DnZ4-ZtmGQONT!URbfNl>)9Lp&l2VTL~T+u7oO{AQSb66ao?99h_<(@YE{Nizi8oZ;CQssAwYmVj z*rA}?`rXM>Aqfmd;tQ{aDeeX*PcnMBnFo0KE#p%n@je}=qMnxjXr!jYj!W(=zfP5o zYds3M-nnp>X~sgxo-$iItzh*&Oe*iEeV=!ILZ-uBf?FE~~nt!g(|4HQPwR z&mOIW-vJS2*-=Vl7RWE)bP9b4{U#v9;_C?f;;5X$Yl?m{m|dXZ`RjcO2|_C4LS370 z@rD&0A0y;`t6E1kBi^nIbMFs=Be-!Hx`{=3=&19Q>dED&f2{U!--n>dkzx)8=&nFaJyii!D zq=YRhZ(hDCwWXc;Kse5G|7&cDEcGV3z4iJ!{J~t`arC{%m*KLqw%G3W`*Rt)xixs{ zHQy@79G|idq77@33XmVS=S$<;0nNh&sJC~(LQcRDI}9M9cMiIo>i_8$w(+f3s zP2La0)7Qvof2*%Y{jrEo<+JGDsx$o5B1`9YqCPY>mTuM)HZ)r}n(qJ5LzgPVmtoGb z*hewmjkh@Tpf4-kQ<83khfCY;r!p^;QapXtWH3@PGuxDl8;S3GoWbT7xY^h4>Cztc zykIBcK5AW-UNKxudV~RU@e_3E#V*gl5I7hevdo;*H3Kt}*a@R>8Xe}UoVtdnk(7px zFvt}9B*w?$B#WGbRYeANcXqY3m?2@qv}=c{@f4qo8U*82Qu*Y&$}|{;8*$k~D3>XM zM4r|`ibxWJ8y zpghS!IP%p4Y?7o+I3s-l+|L#YsRJPs7!}xe0xk1Z8|eSA>_l|R7&$oob0YiRU7xTA8wbE!bl6C-YJDcz&Y^ znn>2my^OrBR6lFgMC>>T;{x64q{<~=Q$ z=NkW^qd)tVh7L1JOh=Mu;!=pOH@3 z(b#+GQQK#KlZJj0zD>(Xmy{o5RZ7;i8F{B zau3aPF*l6Vn)W7e4uEU?tpPOV~-Pk`9DkuBa2=xKY+yA9dn<}Cl6?hjEWbFZpS-#B2V&6Ld1`WqU) zL!&p9svy9m?{Q$Sp?1QlGRwf1$UaeiBlvu_L|q2<074IvEu+?W5GYHp#^*1RKpBC* zGtx*x)j*3Ojz&7=op6I=1Bg{RWAcsbV7{hdPTX(^+h3}ubg-moU*uEpq1J8l8Y-W@ z85;-xGF|)u8ayc!U-o+Av5ZMk+a=@nAL}jivf&=*9r+w8JjI*Dw@7*>_Wk9|ud!3* z`V2}nH5lXP?kw=g_7mZOxqjJ7tW^xiWo#@Dg}yhCU>a|77Qlb-YuVT7@5Ke~M4hpy zUz||52s*pbK+JRw32j5|*QGzp^Mg%!)u)PpTq3eppSD2mNEJ&QG6XfV7CoXtJZscR?{RZ=g3>(wuw&YOD&(&hBz zfTH7zZ!2D~<@u3mAKQw|ZKutulPoYH#){ z=#DVD55X$9CmbxmAX54xbx2Jai^}D}Y}i*RBfht!nA+wdqds{h%aFIcT;uk{WG|PB zpLX|PB8Wp2)Ky|FUvN!0xYB9F)>!|@8S~X2WQGwzJV9#_{)IH)G`5GheZ)!y0YNTo zLPgb0e;vx%zLaf#ir5-t;jg_?;TRKW9ZStIRXh z;E)u{7)LCEy<;#xY(?Es$>>aZ{J;%)2Jkj_uveNMhbfLn04t z%RtBa?0dU=JI2NXIuUZ0kJhQj)Yal`4Hw)$Z{j&e2(7WHJ3PU7@9E9@XN1j!2hica4r#IJus+#Z#;b(IJn4p4qSn2uemtM}R_bZFRx2cX zb++HpAy}*TNMrQEN3Y&8G8;fKFMS3ak-(xv&b9v7WWZksiD%p-cKKh={0-n5D1Z4X??)AH7U@Q)_g++4eW zPgsn2KV(nR7SvB{Hp^4pnzr(Og~Q1$x4u@*xH^@W2ygqlwrstoM!P64#F`>iNg5Ke zVS~fG8o>q*Ns>T3b4@x`h|$FS{4E?7__#1W=y()_apEE9vn1q(g);?PdeUr%(-eJ# zMgIA)4qq05DD!U&ahT^gp4EP4mB>}&BqcPCGvpY6w0C8XmxY8Qwn zNNl?u9EG+Y8>J3+UJ9){FzlMbTT#=0>MX4OE_W}Qs8vjxc;@(rEqSe357mV|fStv@ zb_<=3O_{cwk^rKT&bcBSWan~}w&S*jg4G|_2xcJ`7Utf8s7 zUj2R1C0+(b30b*=-9M?7=sQ)Sgb*DhLEgS`E4NUl#EU6n#Sn&`3kI0bC{%VDvKU(S+1%@^M7fwb-ilnWQEZ!d z&znFOVm*lQ5pD#>VljzsZ}^S)D2GDNO29u^@$Fz%!92A&V#5!$o$u-6({DNi=tsN& z3!L?x0tEz_r0>GoM(6RB1etWVI)NSU+RFI=oqp$> zV!zA5Ojx#KC#GMN)bix3l#9dp0jWpNljnXm*Me1gb<%MXw_dU2)^ze4kzd69S_!pf z@7#u3m#Sgv|*c*(?o+9^Lp%uHZ@Az8fVJ=Q-6GV zH2uOHU%#I`fQG2#_9i1?{_H(W2Fpk$BJK+KrGhR)>CU%m(<*%w77BuPGkcyrI*9N9 z?mwhdo6$Y)jSgz_P3T{%eT%tu>=#{BkXZhZFH00))kw*8N^tJoi{0+ZaibQOVwk{_Lb=!pvNCS|(f^#iO;2XXj4UYU1p#Qx1>kIUeVvEXdDG)1ZuP|P zu3h~|7J#*wT9iM=4m;UjN_gx3)Y;fd7&lRL7CDm8h|4eLs{J8m4uNfB-5wB8Vc&*a z668bRNA(1qF%N0QsgTzLmNb@WmQX`#mNz`V=J{_wP}cACB#ed;uWaDg|B8&6gszG4 zg~eDjbGqywra1rj$!`D65<6WIM}QvkhNNmxFwFa5<^JTaL)7a?RqB5;;IjWqfHfno^qQ zZxH{K%6BD{VyEf9G|K#AfJTwSP0o}!ozhH7NchT0NGiy0_7h7*0wB>*?Z=~&zMc#2 z>7z9%$;pLRVMm_JMB9*lj5MKQ_%eFanX%r%6^p7z^`?*V&*Rt>L!u{EG@BovP+>RN zsKwJQnh?)5oxPapzlZO3QTrMDYGiXz&9lHNJw;~_xyqjtj~+luQ+;VvTGY?tem6Fj z@S5Ca_~u(Wd_8$%$US*;m`Y+affIRls!2Y0v{nMIo}_?VxTX*Pnk0vpW^(AQFh=zr$PU# zkSF?r&$+d=wM8JQ!l|DJbAaq?2#|5j`hSwo1vzK^&tcv!uAZ&BS?`$T$-Sp9|QY`nu#Dc6=xJH1qLWc*QHD z=6v$}^e=7Qn7QZh=GZ58#uU5B&XSk-^a0o5eYBKG!#~NyaX4ea?n{gi^6}!^*HHo7 znC;sFIvm~&b*3E9+Q(yB%Tak=N$pJo%RyoMq}mU>uHy9*JgyM_c*fZX4huqg*h)== z@+``cl&suUQK!XX1fyVJMuySNnmE2Up2iPub4_RtkP|zEqPJ85t>ZgrW1<10^OVW+7~>tWvo+E2q+- zCb!9jU^fB-Mfcdw1lHzsyQ2HNgYC79Bw5Yr0bwQDZ4~Y%U)O&2G}45%)^9z84$?m( zjpzg}b6;xxcPW{>A3ENJ^&~A>nch5Dbb_^pT@?Jj(@0($!x1)(prp2Oy@Fe%s~w7i zQF?>jrp~7+O%ChZ#vX~a)Q%~?bKjhbqc_9(Ym|Xua~_X7jKI?93IC`5nCYH(e)*wa z@thxRkAxFgG`JOFKN#AjQXgL#@hKHGuGv5c3qoP!ZEIQ(XCKx zuOt3hjw|enZffUcc1D*{L7vy!pT}s+ezP9S?`Gk4`r;2g<`n6ki>m5q&uo2*<1*CN zub$u(BrfM9t#osBAF3{!n1*6_h@X%<%^T4RKN_t6m>v$LtK8jX8lH{@ZA_)(G+L`C zw(8;C^qoU=MLm`bXRdy^TQQ(0<5W!!=m+$EWn2yZKC#ukMNi;4=*G1XlE#a#W;Md% zQhu3pb9DwWS>zoGVOmT!FDR=;WtQv=>p0sSK1wnhYJOj06*j?Jz+As-a5?31J>7tT z=RVJWjgR28moeL$o}NaZ%{vYQdGCx*SyiX*{`@$ksC@hIj&BtxW2Zg-cNIIB0S(hh zEqs|VUJMMJw#^4ifMvx6m>usJxzhVz^mt7Hip=Q0DasewMG}yp>-1p1kuTD)MfGOZD}0U;kMUoHchRi0wNG z6r%{z1xA4Ut+=H&x5K}*+QJ)YK(I6*J zAHvW(7@SN-EZ(IBi_n&?JMXXVJf|h4SZM_#r-NUC`4fn6VLTrh1)5)xNR9+*uW^hf zh%EaCjN^}SE3{P7JDBH+qwo+)9{X~wTFq#So*r$t%kg(c^c{mpzfLhl=NtJvEdacT zYR2aIk`^i^{hmQ&u&3`!>ow-UpTUPMy!AyudX%y!-6|89Nvkkf=zC@xc1x-@M{zT& zEG)0wH{_~tOmWQ!eUbRK(nw^pUWN8LKLkhrfESVPn@f!%;>U{<-L`C54GdrZ=`T8T zuAHtkpFxQ^`{JB5pPzj8a$GOMxR-4I;em6;JnDJl>@5FD+Bko})(UBEI_JLsjbbMi zG~cq}u*h!={zHMYNxux0VMCWX6HQ?&ta)|7VM^oIF6VJHqQP?mSrB5aEYLUxC45`x zD5kZ;-yBvsY-d{YIZF*cqc5qC8mu;>9B*#_7?w*MdtvhwNSYC zQOJ?;MBBD_P(1B9f?}%s&tnlM-Krvsr02Px+k z|3feF=GQ0Oi4J0ud*Lm+&Zb_EforeBCbWypD)sV4e(K2fZJ;o)^)+u#IQ$<_JcUHIML z`~MYC@&5`a%}o>kfa@c9GDje%RDJdg&RGKx)imJZ;^M5Z+ApsibL9r>Caf5U|Be!( zci~_^VL4R>ybNDjsny$3-pfG(h7XU+0|lgs8ORl6!Wfnlup#pdABb%sE5v>XW{_Oy z4`czqBIKf3*Ku^sD!YuH#ZMm0z?Z;i{M3S}t6r`IMKSzI<*8tWje%KtlqlANP1|Sc zc5zx8pXT7@ibL2+MnCT#7-&!MiOUUVq?v->B(G{EjqvhJng!qp?1V8$J!ha#H2L!Y z{eplf|J8KPJP(h-L?L5iPQr8A6#A1VZ^CGf7@N_?T^>%G6GS)!mek|2!erf@a@N*u z4n@oo1}}|$+E{xlnDq6GU^i(S@XbYrF=7gw!e^*-PS>X4B|$zNtH<-@FcWTLe+Y+_ zlZ4P~cCd7@LD>Ak2AUDP*>*M2-x%uc6o4suf@IwpzLBqDaJfekh0IqyMz$b5FL{93 zQ&!7v=j-OYja{!n5|UHTX6UlR?vo?wsXSLGl0*=<-h0M&vG0#-8By>l; zwiWd!nu6Qi`=JN=ajCPi#psK2*1-u}iQQ8M;f_>*NuZbj@yO-f$-j^&_(x#VE5^&_~rNqK*=d*l)9ej=-O-1sE1M=KxO-#Z{B{d zMo&)%cFH3`6I3%%&FlL4G;@kmT=icLpKmh@5=6_gg>Ct5U>tV+!fo-#BlgW7&e4T^ z^S}DN;BvU&sa)Mg=i1B6%)D(*2q;|1z+z^@QK2=0$k^EF+t>dYbz02-6M|)aaD6N*eOyP<3 z)SW>(mOt@Z=VP7-)gly z-Gh)hRnbUP0X>O;-FPBTK!ltL22;*!9_v!}*d^4}?x9PJ>+pg{N}Dc3RW{t&GJh{ASoVJ@_l9y=4FoNk8`Xi>PBV%kkz14C>BoO155EDd??%c99h* zjaYvw$Aic9{PUI6323!yKPl7&jUPW8lH-x~ok&8pe&Ji+H{afCDwh*%3(Jq^;^^K4 zMy#)38P*O7=rvL5Ng79?X4my8Vl z0u*Tj<|6rxqcJz&8ir-0rBO15ebaL+4`IJT%H*0Zi!+=hI2hvRHmY#P1}sc;MRO?khKG#sMV$5h9sCF$=5FY<9ljc z>1RZy;sA#%o$}5frB)@{U;7HY8u4n49=3Z23ie90X{JZWsWC_qTj20Z+@X^`Vi2N? zCv(&mC%NhH->NbV;*bZ@fJ%oY-E(3fLNjGwYKlD(F(>uAPUVi+IV1t{3abxa5U+`r zD)2pnggFak_p=>zOQ*}Wf&jcE-j?EL=UBkG+ zt6PVoFkg6y-{3R2+iahp@*^5Q$p8igk{kz%!u8K5&suc}#V?4V5-bc|B?8GEx!%%~ zNrp{H)LqYcGp)MIq;sFZrNqXuPsVP)mBQ=jJIe=Fx}T0F*u&T6HqzNv7rQIlK>qn|OFt-$b8J$%S|46()$yO1qcLjoS7d@!JO? zNX}f`gLJ}ou{e`g(m5F~3Crb7I-ep-!+sO_VpG2q)AaT9&5!+o!nWBt*+&1!@f;L& zY=`xzCprV+8`mgRzCPg76Yq{g9#O{KJ+PJUWuB963Ebqvi6oSyl?Cy4^*&IEz-4X zQQ{~fGJm4`BYike{)v`{tQ-KX2W#+rbQd>iAR&No@L{FsI>V;pv?&;W3I?%>gWobP zr=@GR?ncXbgS-o*gIz+0b~7d7d?WIa1ugv0@rT~~v31I&cgYRSJkR(0vi1EJNX#K= zBp3>E(h7tWq1v6EZh$52fF1U}3%!QEVU3J$qGfjc7MgKVsH;pw$R=Gbsm0aK9{R+! zdm4Ka?rQa7B(!HVD^7Sm`!5?(qv3#5ZYR$+rO8V1!raxviV%@Rex zKmJV(&^%9>NE2=^(Y-xIVw{?f0i=g0&#B%>WN(T82DZz*_Km2ay_-mkasP@)%}n-7 zVlK`*ax7aDBZfk{X5-^-WyaA|G;G00!X+RhnOAzg_hu;osXMXuEndJBn*0p2Gxw!& z@fvhs`_ivK-5&NX(FG|Vwy!hQ;v-;DQnctFJw@=Gsd7|IK94hZe2^N32nBtpX*2oh zeL8U!myI%ICE+~&hcd0Vv1_6}pD!WouYR*i2|9el<-&4Vi+%0wV=r{E9DMq^(zMH; zoYv+)rQy8LzauCPkbrk+T)5B)$;pg>pD{%>Y7|Ta83C>TAD9>)pKj>bp*>0`tnp~< z;$1*M1&DSt2RhCzThaEAhGK|vg^#3+U3ax!E%3!R!qj4xmO zT4WRTyq3U?{#fHW)fgE&^9rnACb5b?+e2ePP+aLrX1CT9DLq_Wrd1c3V7>*C#+eO$ z0g>jT>a5I)f3)cDdhbEI{6qq3-h?z1D-N%WBy-18JbX=F< zwbfR+l7KEx67G<^8~wO;wlYMoXm|kpID+l6axnE>gJI~dnm=CV%Qzp|JMhDnfmW}O zwoN2;@6#Rw^)fN+lOsHY|7D~iCecwr0DO5-bbyi<;U}Qt8${aL94?ynkL7YZWW7qQ z!%zRvyWV`*nYtoFG~<1}i%MS4w8@(kFY;61+8J{dGm0Myt|I-j@paVJ>4&kc*Jqc5pm7FnOz;x2fa;)>o~zt3vp zsaJ7v6^ur-QN6Nsjm@5gp*n2`5XY$^ToH?4<|tWA~UBhY|5su^j)5~h$E7{ zG#l*f>}*o;zpIJk-+Pf1`INPS#_JZd>28K?*$v32OC)4^YBuN~CG<%v3#JyiFr z6F)+{L7x+RAPt~fr4Kt=Ut20FYNH6{#Ym~bvhk*y9_gx*MG~Ep`#Y^OOd7pxaJ<(Y zF<2xKIRegP6KdMV4&z8#qMgYvA5@)t5FtNNPUPB97gr&1l75yQ{MBq&z@yt=ek&h(O*+$>T+*VE<1XyQ$6y2b{9$a5v2e!&8TV7ur)w_0ePL#`F$0kTefy^>C--Z{8L^PrM2zqEq6!riq$dU{? zI7Ux8gb<40rET45!a!cBzXC^EL@-X=*z*-lQfQ?F*RD|_mNWdlF`JvbDRs&N_KUH6 z6-zjZguT0hH^PTy(KFrq$BKrw*oa~il*PPb+Y)(5YF@y8Q*v0$!>;z}c^+OXI}_e` zQ;M(e*oYe9k@Sewv9UwMBY;eQ3Ag-We`U9vq}$VS%O_5~aeTB(xGT~Lx<)SDURDCb z#@DTHy#6jvuRakT2m+6I>gnmR0Ryd~l85z`x9O%@A)!mIW8ROb&8s#hl-+$Ao9&lO z&R;(=?N2?SWtf(yVGK;^eV@hovUl3m4*}~~Bm70-k6Aa6pF=n~r{MFpt6iS$@9tB5 z!SC5O^*xf!*>u^zi}RRJWE}!vD5jN_?iTw0-J)mu$0hcZqLdK{YjL8gcgri`^fO(d z_!K(@gyD4FWo`#Z{qV3GV3no1vkj$TuvGA4s9{&QO_GG9EoOpHN@u_*d^3-CWj8~# z3iP~qqYkFf6jsIULHyx(tW8cl_bE%B_)Uke7|It~x#^VYb}6W_P+l3bSi3Rzm|VJn`UmkNZH`@to95L4dXP*9$v(32736uB(q3dA8aGAis!DQ}5D8 zS)h>#CzFv0mXvkz0o>w4!v&;}jHJ9)yW7*LSo=X{`(qNGZXd!g}y;6hnWF_{K7j6g_ zMpMox`%t}lD@;?!jXG!CRS37#WvR?^S<);3yW~lq76S=l&|6Q>3$$=^<&hVChU6GtL3a)p1CpzbH8Vy#eI&o+MVtv zu>RMw_7Aq-NQb$&c&^U@w@fLNB||u`xO5?)_dmF z#iCPQ=9~ByjN8#OU7g(Fv2Ub@xmKf3T%pi7$|%(?4f5zn0arxPr{Q6a6B8Fl-4yK) zOxC-9*s6)f9`y_h#~%-k32sr${k%Dzm!&{g9T^>uxZKV6$qs)mi8Roq-)L;V+^KXQ z9S*yLTgy)W8+9-eIgnugw|MP*0kWYa3=0CyXMD#`Z~=xM$-TW0rK^ZwL%>Q6K`1i^q+Q{I0(oc@~)Ve2vS>kvAlw)gQ;8q0ViVAsu zs($&of>9|7=^R3jfOLKh)G+qBA(Perm>=P$OB6Qpm|4Lo)Ii5rHmSDu;eJUcjRly+_uNexzMpJZ0vjbNP~a>^&vr`b$lmF^?Z}|QU6Wx5^(~K z?9SM6!3}E1a4YWE`1fI8CGB~%4Hen&w|Ak?MPlcMQ2xY)Uk_k+EnTp&!iA32S?QDd zojRqrp5kLM61?WoTc5>k^kMXKeSOX5yUeA)4@RsUTy{U=Z61Tnj+Gh$x;e{m^hpZKXu*vk7`p#l`K ztHkX^Aw*t&7{F**2WVVlRFmRTr~%Ks(^!kEgR_#DGaoS1l!xDwB!+~A4Uy`y zSUr8y)X*Sp`Zv-841X*Y24Sp+HEb!f58fdw7s3=BeZoz`ZF$MF6kJcGSkwY6u_o>Z z2GvWw(x8alaYmf&Dl`!J{kV2U<(nvkeHKk;1EUnHIrExa#U;cCaUgio{qYKG_wrI` z-&%CGeq|~$#^Hw($`w7@bdiBPxVo-LEa7uH2vCrSDn2A(z)72!GkAlo7~Bks)pjdq zwM#jaHvk>lVr#Inb4V*0Q?D&_NN=h0)F)nZ!YhjuEt}7DSxA5TO;8}8ni7o552lUr z3K_ewzDvm1*mfEDl2^{AgbNv*&FkRg4xr@)j6W$G3cJlh!d6J8)T*gGA8K;x5Ob$S zV@vJm)dy6kKlZckLN!MdN6u)itgO_mNl6C$z)>;&`JIv?Qlwvh2 z&Fj#jw4-`mr4~!KJqAxA36(=`E9!_J;m*d$36vPWOm zYVI+3u4IE^_uPGx1()M9$wX&uv5A;yr`K9rLqn0Y<73X}Ppt+#BWyx?bq?B|j8J=y zy*VEQ+()HXKRom0_9y`!ebv z+qmJezb$3IUqBsp3hO^k$9G3Le3pbf-JW)CkYfe$B+x@}w-egYN@UbHI80A9aOx!A z*b1Y;$N9bF#4E3403m7K)%^BEE^BD;jHl z4Y{Wg0E?$75W6d_w|XlXKS?;JNY7`KjKH0EG-Lf;+keUzGv7d%PHzEdI;&%0t&vgD=Vh z$8pI#g>k8ugE&L_OJVHjd< z-&|5sDKCgLACkQ_(%$Q|xDPP7%SP$;N!YW4H=CLGJk~+PHOWO0IDp;~YfloW_@xB| z`CKo;x7pu%&290J;~U8*v6rwp^zV*yV4Q7Sf;b0>oC8y)luB4DT=~BN4i-MWA=zdE zpM|p`657_&3{il^C>4nNfq!b-XF(Xb##&li@1VAU*=-8UxNYYrQ5DTBu_Y28|E0Fa zSE+yVXs2!#^%W7f1YT-z1hg$8OlAV5rDNA%7&~u*njmpTWtylJ@LmuETgGt$6#}jq zqQ9f|r0|~+^JPDF9wtEUDVh?%CNGlvh$?j?u z9v-2D6P5`!OJF$xJ;1LEVw3WfZS7>z;ARoiV(#aNeUDEO#sHp9c=d!avFvq0=qo1z zj8qY&75MD4z)sBDLX+#z@LJN3YCHG#&%T$xyh=g5@RRxbGTPQ|aJ4VGxa0ff_HuWy zE>Zg9jX*=E?P7jQw55J_YOx&+>(bm*=TX>H$89UmGI8r+r^!x9w>d%57fv!=6IS{? z+LYjcu#A(EiJiTk^*_|SGai_#n$a&mOHR1Yqpp@6T?x-qeUwsY_|s}7bD8nhFpQ#Y z1a*%kfYDCQW|mLiIYEM5MAz~+>X=#xkV!%YigJ=wVm!Gvo57?`Ujm|^mw4i5U){2S zk)Il=ZG-DH>A5SgN%p{%dMS2=g~%T${dnrT)ON3{UjZ4f<5o_t2R^ImcK%Oo;AKG( zSa3(Ad=a!yBgFlOg7F;uF4ts*0@HY{i8ts$Mt=7lt?k8*wto>sF8x$CUN%v_wPL!3 zHYMv6_(#f+YXAbBdJ=vAE1}oyhT#CdSfWq_tR23Lb*8{&sj>U#^C)YWtfckP#5*bx zY-7rCPr*x#njT?bY1P^Tkvp<_DaPiCiqq`yfL5uJb=ApMhlqwhTF`^PHlbULkjE4E z%9MlVO>df~ZH~Y*4pA_`*Ve#_l$d4#XK=e# z;`8&pI+2}blMVr*1nlm10_ zIo=#jl&33CbOwl*i6#d_D1e}y9yTIOl4rl!C=bNZy8E{T2qu6A`LW1NxlzxSUYNR& z+z%dERUU}`E`gnO=dv&FfN^cW%rm)u^m`Cp#tmyZJIl;7;&@tLvUL{rrx8jI_1;=o z%suk#mIf0VMg!j4c(tTh z;@^B^3y%#9%gRw>M8x^XfRk4{v@B! z_W!%~Vq>9vG490l^t^soXVb##B5qp@W@cvmHls9D;=au^z^VzCHvDWxcM$h}2c;|_o3Ct|wZC`_b32o40oA%$IzpXo!O~yPReEx}g{?(Ik zSMcKXo%rgokmSz`jMpNuSEZHFhn>76=WP1RngGT9-I~gn!WcRtBhG5VxrO1=O*2dk zoh%8uTYPg6Ng`+@U?(g!WIhyk>TF!7$5|YImcl_FZ)5u^Slf;pfpb=o6*RfaC&mU{YblNaE^2}$OHPf^vm2g?yB`O;rra$q0IFk&_=(yn5T4fhN9}8 zT5V&mG1VzkN80CX(9Vi5@V<64ow5FQ+$JI6+2cTeIe%zF3){KP5KV+`xaDJ?4>`H# z1dOg*bP9#}y?nQ}_ftb(!+@u&nj?+m5*CrZMS0##i9tDR*+mO)LpiNagL$(+OikZ2f#%RTWicR;+S1kw{eo4utEEk zIXI0?sB5~?f-$e+=@itvqgra>_NI8BtW@FSu$Hl1sxX-$M1E*>!lmQ;Nb2A!p4DOj zsEF_UIpLFh*%Y>8-g;@?8`5?}sQJ2$WyAF5|nV)k5INgF$csJU)G^F<-_3nN;Rbaj(r zB5wQ)E*^G-O+^JvXLn*`;m$WbURKYWrGMMC-sVFRlL{s4JF%0mZ?gmxKNz=VuztF` zIZp?;X4A7pAIFaW-9xe1Ko?gR`2r*Ub02WaBt}KyZT~~FIR})g{vq}NH@H0sIL?6J zousU+ot)D#v?q=*ZNiqnY=Z6}o@6eA$Dj3Y6+F$Y9IJ(2D-4(u;PFu$#;4EJrA>6S ze>vNcHJ(n0^B5FHBv{eNe7s*dY@M#V{o*}rXs6MVt!hJ|mhKTu%n~=+;)S#LW_<;B z0fAz$-Vl&8ml#|IP%9@s7g}$1fPUkOU z)L`jLRn&UMx$O}ZKkl+Yma3%0ppn&Vp-+}7k}_+$@D%fXdF|YCg0}k+u?Ve85!PtO z+xfg@G_R}QXD_6qRa!&WA&aoqPEkvSKsS-35-jo$}tGuB5Qb*s=k2X7e=xkEBN7gP5!7h8Ly>-YE6VS}^1T z9Kpp^%RJTU^9u9zjpY!@l~U-gJQF1XQswUC*T+%T)pB{F6g4^Rv;8`^EDq*S^<$U@ z9|Vg{)SBr2HgG&Kv49URaBN|Xge@hwpjJCSgnVs#ost?}<~9(i@I_mVLlMYFk#{ww z2kR!fr$ln0W@Y-DqGQt}y~?h$blKjJt}*>I4wltjHM(A%>QX^rNA;$;Un4!wt%wOxFjiJL%)*TnOpJuIgMR4Q zxt8x1&SjIitV1{9@76jCMNxxK@3_BHjhHo?%TT-q-f1C`b>zLqado1f&TKEo6A5cVfM2V` zV(`ne`@>>}fl(u{AA6zpdg?pH3o`la-PS3sPW!QghhJ6mMW2M~ofz(%E1G$Rn<;hH zP9SO%gkP0+pY%BFTxztmFSZ)gprY>)IYu`-UxfXt_SZ#@uERD5Zuf*f8L(t5!aqWU zUZlrh?C<~RPWFRq;vOD+&5;{m zSzU`81USl!f6Cvy0lMijiFcpD6xPF|UB4xazU#3aE5JK0)kZf}jHw8P#5LV z@ct&rC%3xcg~2zPIW9iFFaDX+w7FamLW^%2QzTDozAUDZ)dpOy^(O9 ze;Rqd(aQ2#1}S?7w3TieL*E&l5`BYuGWw49TY_ zw3&&d>)3?r?SJx|)KljStv@0QRc~WVOTz|Jk6ey|n=l;PgF5&${ckA;V-T!UM;AWV zEI;{WrlaO%ZlJHWuh`dHrI8s;(*5qUs=axSBVhjS6{B$tg-%AfN^XjGG;hzSg!9AR zu!nHOgbeY7d(`;rASc_0e1<)$)}O&z*Amye1&-sr!vkU5U8)UiJ1Q-$O|Suw%5)bZ z4scL2w-4RLpRCF)osdUFX{BtjLVi<^+?{_Lw=(!-jX!W0@i?$VsUzfPawLfwn*F#4 z0sk<6_WkY0w}Z!7k3sW+-a!vsekLw>UmUXBBtEw$V2B8j()9mQV^Y?H-Jl?1(P3Em z&->3}(P?opF{t`_$)Dxxu33a22Bor1@iCw@Rg7C%rud#a!!GUCeXX9(VRa=!u7Vg7C!NfVM>#PBf ztVK7wa}o3yIM21N`yh*&N7sbjGeP=CI^{6z5{rdG7{FDsp6h_*>sIr6!senz#0-gF zZb)68p#7>&#JZQf=W=I>Vk7eVJ!2Fj>SF-4gl10mbzT+=`rMcCl3o5;ZYlxqD0z8P zD85bz3tDg8Z=k)vVM*wsq#zc1!fxmXs_}HK@}EV8(&vq6O1ewd(#){$Ri3{XDXt;8 z7vXc}trOnRFH>coN!FKkeIOzQ1_HZWityxXdy@)Jepg8Cv);Vgm}=4cv|HWt1tVQIv?lr?VU)R)!xGx~)bWaz=KOCZh+Lo}2whd08yT2pk+jVjt*$5}yBS%`Dyp;8@~~|3uYF8Xp1~)qSHd zD%yIR$6p;Sf5Mx=_FV4nn=&4~{P{z*Y*<(cqF5HtF{0c}Is9qBVR zsqYqjNTxutS-!B}V&Z%o^hK~frkop=D~A8AOn-mu=VlbzpbkHy(#oWb)U@>t#(|ZW zA{I;4Oy0FDK=_R6k&S)a1)z$cI&x6gUNY3PT;_eL4z5n|{f?;7gc%>z4Qv zc;wa{Owu{Dg)3nFb_BU98Bpq@g?s4i`6}y~XKiIsC`ib+nQv|M=a7W@0V|ohF?Mep zev+n(hI@mfzrO&HJE_rtU#{yEtsaE69)Y(df#JR#Ax|v)!+H8WmMwhhtMAL!pM`;e zM&}=1S~jH*W@?pDvcHEzrsLc7JX^rc&X2LdqFn$>RW;}+t(Sw)X`Z4BKsS8#&Cxy#wTR(cWc6khex+3vYhnrROTLE`>81raV)5yxs>8{;)|c7b z38C%X{a_`OX@6cyY`Sl+hLblo!S`f`aj<>+XgshXSv!j)>KYAm1dpl>wQct=oiIs% zynd!04}1MJ!RH66^7lRE(keeH_9siK(WfAW~Y_U|%buIfTsaxIhkXJC?_j9RqA^ z(tg>2Pw7^G1@KgZW7jC0YMK`^QC9idymaocUgYWFgNkFXONNw@y7YsNLq)Cmw#>}2 z=JLwQF*!bhWhfA^tx9|R{`Ys@N)QN?z>Zsl=E9% z7pkVf0%*p63577VcVr#xG zdCv81=Gm+L&5YJhRWKb&Oovm{>0V{|LN9MnqyP!X#{nGZc|ng^+`3)TygPHBP$#rE z0eDd)g|}^C$S_2$GQfI@t2I-CU};~(>AF)`vNyE;2$|2Onf0ADuY2nDVZ?Z68gPaS z1OKwd(ma3}=?e_%TjG=bno*#?XvsQm>Q(EN%ioPoOuddDsow(ZCT*bjOxn^F$S{6G zaS^saKHZ%4*y>xB)!{}V5jmW7J!PB~J!MT;YZea2;LnxU_b$(eU*2S0T)3N*0q8D3 zJoMIw5jDt|`VVXw&;4A11w1}b1I9?J@*4c(_kpd%&Amu~uD){ydc0Eh{@vp5&_9<= zxw{>I2B2gNPb)fzK^n%noas%XR|R9nY=2WHcv{H?VvIAZvvqcdjT#@iwlUcZH04eUQF}lqsiZ7{$#t_Ei^@44SDdLgMf@R(+~aGb}Y4> z>-QN&xWq@64aojI#Miwck?Z<`I|r^r@=XLR+kPv!dUSNucejUekN~n$`1$^A=|wsa z75mCJZ!tybhFzBQi#zkMcjaX> zqORZe7kGCkqE#1uuO9az;GqvF%9?f_H?sF`;PdAx?2`Ek9!SJbHGsI)`w8}HfS7hB z&lvjmOi}D(2Yiz*uM$Z4z;!GwnlsGYaX7y%=+I;pxx||*SBxw_6AldjwkCOc*80AU z!cNt5HUj&dNss07iyckM=~>|`P3dknDA(7cKaE6D@AJj|%i+5n)BYc?GSoS9uvc7- z>(NLyuI`O3e`HGmV}e!%yqit&O)yx_`ur#Jtr3KSncHx=EU3gwu1dZ!2~hliu; zt)z(JczT!2K8Iw1U5=ZwZ*94dz!d8FppGz)5(Ivo6M{)^Wnf5}e7rEX(J{W=G<8OaX?xIqj8+7=quqF}?i@(VT_H{gv$VLGy%a8yxd@$n{ zzPvcmNMgG6iI?t~@E11l@ve`UP7pk&$>|*NYk5%rjk0n5;tLvB{$v81V8GoV&F#Qq z|4~YYp7H>GwTLK9mw<$cW)IUDURSc`Qco6DEi6p9o2Vnn!4-PHn1)L+;AqvdE(qMjO%m^78{Q*j&RG?6PH zxiURgPwK)*n|y%PK`#Rj;CbxaceN%uv%X{~v3B=Y4IM6CmFUdI7>aT>`+#qbqbQ7M z5z5O@)GMt@AufJ zdc%)q!pE(H$<&rNWdi_A)@sW!ggm@@4B#HD)RQ=F0Xdg_Ur)sS{)>QL#mp0qZud^P zCa9Iu0|Ht$g$<2i2H-JGu_Ls|RpG(7b?wK2lDH}QcCS~5_CV}?!R(_~){Hs) zd;`z5Vp6cP)??daZqk3~y_Cds<4Ey|`=aChx4W&F<9oo^Fyft*CpI9y`|yr5rJ zOfnvvm#cwhD-!xn!RgRk_IYb{Pc-m^*5Z6*%gDrdbJBhgiA+Lq{CV=CK_Rf52*Qn! zhX2{Ey?v?C*P>6vwih3`w9Ze&s+zbhWX5m$qvU6^nXTw;Bb1Ul4lMgtcrMiE1e?T* zNoY`ph`>xujol{LMxXbO@I1-Yl;;uZvU?7$?Eeik)!p;;_4PLwlDsT^<(cw8Pfl(B ze~)ui-7;Ygy}VIbS-ApOG?V%BpQ;joXo5mQV?FG^ILa7myQX$mXfw%A-{WSIewY?V z!9fx5{^Kh+iflSO6S#HZ^7IF8clF_xmk3OphkA6ceTsPrC&f-R-vU=7y9;(ip zG0$ZoRP{tB-H)XmTJ>??*&q!<^D_88?D@paIyHGoUUPjM$*Pk8*ie7+FhE`eHBw>X zSx^q-Qmr49fgU1x&@`Qqa=l+XnQ2FCvo&k^3_oJ~koBrX62_@P;6mhS(PtOTd3>z) zr(ub13InrMnPOd}=w&7RE(2Y<%PXuBO+sM-hGplycFf~xu9i5r(k;0CyOf`s3E#DZ zMbqNH5YZ#j(&?BBL9R$NALbH1OD}fuig)vk&S_)tqiRyVqQ;rt8^%WTnEvFPA0l7* z`89&VckAfjp*0~3QiwCJUv^ZQL%CliFNy}yjlonNVv-4Gky0>g(DPpJ`=`a}v(|7p zW(`uAfmL!@J-x=P#%_dYvxB$Od%hx({=Cb5CbSm^%MY>IR6flo);)9Asc^{_s#0g? zf2Z(dyq&7~OqU3*?otv9n^CoAJ&tlJ|8OY1m+bNB=Z+fmWUBj6VtbVX(yHxDh9H7^-Gsrzf6*P)oFPUfAzNV#0)j2X0^}z+09Je0bm+8&2`!+7XAECFOr72imJt~P}hFt@H zO=cxGfsueSWD~PA$*EF9nsj-XUKCZAnr?MU6qOiVGtA*&yTQ!%xnEo}ggo$hJ@Zv9 zmQLNl+DgL>MpjU15&zsf3Q*6;J$t$UgbCn{cy!fhl4=M~TdL6TaV)Onp=)Db%1*7_xQyQq8-PAk`u8!#+++HGQp2Q&vG{qw* zmCJ@~qso`<$Fz#YsNr+0W9w8iaV_x_RHVW@+@V`!BCtmW?UPmFxc$@D4*qE17+=No zgPODED#ZX2Su~vd80MvGZo#v?bQKdeD%tkhe0HX_MV04{ndHoq38YvAUc*a?H;F<{ zHJ^${tF~J<-5trlbIq?1e6;@aYG$SzLC1bPBp{OBKCmkUeT#Y^8eXK3xqk07BlsE7 zzQg?cBFT;Q%{Vwh&JM+PI#ZU?BJgsy!^FJZ?~aAzDAsLM{i!f8Z%e84dK zFoV7$*>pI$eu-zl+G*j?{H*=7)5I&k=AVi-6X{N=9yqXe@|lYANS`8=F5>Lz>SLD_ zt~^BeZP;PLoo~qi#zNj)LIVbi*eQ6r6eG0y7p5vskWLnc>Kz6Nu57}1IS5o8qu;zS zm}&A7yBmBok#3>zWT(35b981Hq{rGatD^I!V3hd12(H*Ke57tJfNpZ58`MP}N7|lT zonGL|%*tJK@=3^sS^<^?PTE5--wzt5R_tcr;z7!&erSlNaGo$Qkcljp0-W5C=yFKZ zZVxO%%SAV@Q6*YTyG zdT949DOPi)o z@0^|NowKIK=?gm(NqQgJn|ntZ(z|2smSETt-|9|^>viqs{!Z%q|2>Bzk9j^*D!07y!pe#(`)dikH>b%s<=zw=TRCE?a0}NnBvEM z^VOL}nZxWQxuTkhmup!^C_S59cu%X$ZV1xTpQ~dMV}~fWlq23qW3#kDfZQuu z+jf*gDpx?*2*f9WrepQ7F?aLkzqSSy!sDQPFE2QT-*N}w0;QPQgqrlQK}`Xh10S%> zVh?^U*xVpz`i^HH5J;?Ta(Vq?2cb6IpV37PhdIc)s**|x>14Qe{$+WG?%TfHyuKUo&0Kw(xWzV z2W5skPxtP?dLF5z4~6`u$Uah!-l4R$i%7CAN6suYM*k`n=IR1+|VC0rjp+C9$G&zCY^vZ~$iz?X}SU|Dr(Z1Z(Rq)jkj)8~^|r z{CB=REzX3{fS3iPCnv{_euKvR%kp>|^uxhNNRwO4n3#SDjrQ6*$O{o37;wAQZt6Bq z2!m`2^Kad(C^!F}-W>Lb`@zb{x2BCZP#lkuXyQpfwUg~f+gM~BpCPR5dUOm;jOoti zhmi-6PrpH6$!cJiq1=alF{I*waKziDPS7_~Dl3r3UAJd5bidcYG-}_kX4l8FR<^M> zNKd7+TXbK{VUWa!>Ou4}WwMf4d~!M8P3z66D}|SxWMcimPmtGd?en3L8bGw=CYZ|M z01umQ`R^;-oS$&VV||tx2yth^RCZmwuXQjtPD3}jiACoEf82l%)El#HuP~eaBNHn~ z5_aE#rE4PEA7r46*~FqEQpT5Olk}3ep5$b_1wZ!qrokcqi?WG6myx`%_b^7FSX9O2 z=uF@?WZ{dHm*YA8#PkG?U;=SDZWEg9aj@RZ0D(BU+e8(uTk;<_M>PM$W$XdzlTB3$ zV3|&(v^ccwSs_S2KwY2^!3_1E!!v3(xD)f_=`7$80ahclGY>^-yFP%L77`W?$j6?} zSPEKZ^V4>mSQZIum+*y`{Alx2c423|^{J@X|F;0hRiyocw;p7i=HT{yCF@_2_8HZn z>s#D+F<7>7{P#)PDen0!XnaRh=cfWQ@~I4;^{%M1s5;(=h$!vxyjJbLWvaBwP8z{1 ztoZL_k1Ip^nTPW{7JDCMwSLT5F3m_CC%P*QEAGcD0^odrbacWQ%H*l!Ji>)NoU#h= zVfcGOjXwm4EaHtI2sd{CIQsYRr$E*W6(3LjQ#09RymSDtatP>Th@fU>W+uhX3%_{} zzYF}&;KB)6Ir3=DY+_`)F_`=%P|YF5&{R-F>P>Zn>RN@JfV+D3ET(#@unLI4H|jV! zyJei&tLd6D-@;Uk%B_CkQ^re7JPy;sHbGn>L>|wkbz$Kz{RaAcqB`rdRQ0aAR1dKT z30JxLx69jeciCB3&`I>)GspE#8z?tb>?QA;tE9={nHY2e+x_hql8)@ML<}gc0KJ22 zql)|L{K6`U2JUO_d2h?jq{NgA=;KsV;vLbG+YH))Q`$fK3kX^qLz}eeUYS@jpyBXH zN_>!Vzq$fUBZ5A)>x7n6R1xoqcOqCn_LA1ZXd%buh;%g` z^NPkV9^826YqLWEnSg5Io1!LVj(#CE!-_xUZi1LoVWP$DdA~|!7PLUFylRn`(BSBb zce&FQ19~}e?Itn={SA*vIM9L<`JF_TXW28=*II=RlobKS^BccPz-y9!@|$J_EY5fC zNS;isl_&=58qZ` z9A>RMnzm?H{%-9|6ogG-R-hncFXlb)c*`q#h5~O@4j?Pl+E37@f&3H-jpq4@)LdAL zdTPbG`u&KwzkFUa?LE#FQ70{`c>kMCzOe9onETUm9NNTWa!iC;@Z6H8c^OuaJ~gra zf@;V`!{5r-ygWbdKsBo;ir6fQSDR8W^57~%;X__?fY9+s+DPoWi8RY~jW8aPKW~Cu zpDO^F`Ubj|W!Sr(h)AtSMm5Im%^sgI=9V~fD@)TtVJzh8pzCIXA`Wk!qQmc+^cb=r z;1;A3qdsS7h6Z0v*pInEM8snltl2Cy{X4S9VN6EGa%}!2PDe=UDiug0f)ghqG%=}f z7D|7!*^fG?nsiW=fkcC$XPu67Yi}AGa!8;VnWdY6*7ip98}dSdo~Lko#8XX!f5sSI z>%VIDXP7Sc4p1K{X%049*?jp7mTcs-nRs9AK13f?j#S*^=HB4k;}VwB3-|2^Es2;T ze{xn`q!aE&SEyrmXt_hXmTI#m>c6ow*7E7@ZnW&%N1~nSh#jpoHC;-yC$D=4 zhxv~gK57NR6n(v3uH7g|h#e!f__fYtae1y`^fQ03M#Xs?cJuBrQw68wJ=|RAqSC1H zptdmYyLR=U$Z1@lQvpy1n~=J>sccPac-&2^|6lfl+%EP1{^lXlYeU)GgsZ6{V0@F0 z5AZ+^*&^Klawop}?dO!|*NC+XltK@_l#*g?5z#t&U-IkA(W(xlMP=oc>S~4t)G;`0 z;;w{Hbg~nGd-P#4ioK_ukZ64K29Tm%2R1;VR%)*yuju=N)s?0np%!U_Z%i=JT+1wI zu=n{n2?vo)*>C3rStxmLWV8+$WC|xNO;yi7N2@yV%s1JQ1X?r$T-H<8H|sti;y7C~ zMh#o2)eZguqh2UKpKt>}XQVQaMPN=@$Lbb!I_Lp}9x(`Bz-DXp^8nzRh|j^w4EY8o z%htfHde<0Svk|n9?16QKRFjCy&=;N{puECGljN)r!FTaR25=D&ueB=i$zx!Vc5O$u z4sUrMsvG%GhT>D;2>97N|MptouV^BGs05ZwIlBP^(X=tHZN{&l+38^O$>DTaR@NoQ zse6K{m#VV93#jx@h_m%OI8_?R+CSjIHdh)@;YH?leuAu-=tV3V{mSK9N=guoRx|F9 z_qaen>h$GW!dbjG+I>d*Vk2&B^Yv>rZ`0<-lMbu>AMUg#Gjx2K+VY|>ZSWLTj+ed9 zP<2Fp93})E;(@@N*x6 z>UlUE?aT&Q!r^e}q9RqmoXIOAV+zP~HB}1v5{IN>Yf*A-!&+l)J+>@`k-u<4wU+EP z4b|~-i!Vk^kdj0cATyYW#2>47I?Kcn06BGmNj>(SRwAjHPo(!o26a_m*$QJ7lPUu^ zAz20H=~Jx}5|3j$5+rtHNYnheB1l7EdnxU!0M>luMP=`0!}bzzOGCd=$8!L!u#iBG=QhNUyqyhs^L!^)=_PglzF zT&4IJ#iU9E5gV}CzDP-llI6BxHB&m&Fo1v&DMvbKgI(0{ZiWjTj#Dp*Y35vwr`gHZ<-pdza zu;H7Hauca(;GM9@*5IBtOo|LH-V?s?MlEZd`C_-u^k=SP6Yd~idBxf^?;ZN zJj^Uf8K^dah^eC56Q0UT`fW!dwUpGDoK)YO`D6S>ezW|s77@fq+;&D$&UYv?CAkg1 zKPWgC4Lwc?ye8kj^feWa)!@j$6{*(zocYu8eld!5WzKJSQq7_h9{yMDv2_Q+??Bg# z?T;^Y^6`g&20j`JW8d!!*cek=9WD?9c#T49$gC}_hL@n6sL{Shyx(cQ2=`fD(TnJU zYfE{X5hQQED_REZFkV&Z^45Z}JVN?Mg{35RKk^}-pbw-L(-eY~AwyITxQvqJN94e! z4D^{5A>1uPnPxc)gBslo)8G4I+{C}U%Q#Y3FaKrh?C5HY&PXDPr=+65v77Os;N;g! z?nB;Xg;Ul+jhT$<8f0XLXuz6unaccZPzWkv;$=ufWDEB~f80ah(dj}`+OLa1tx%rn z?>=fObaNisy#lwhtp(k>YB(b%jIaVFHqd6P@o)u(WJi*h+-m3;%Ij0~n}`V>pUaDW zSPYPBRuhSfaW9Uu%O&&lYg~@^$gbSRm7shtm{}!Hh@JSNLEL%Agv)_T%>Ua#~L^3o+ z9-9{wUE7+PL@kHng%IdjdMVi<$=}Mg1xWCC{LPJ`$Nu4N3no!-X;?mq z8$?~X!^SZ5#xkl+(kqu!`IEP4)DV#8hQ7#l@;rQF>D9bFW59<$>vFpQm%0CuIJSA# zYHf6UG`4{*#L#Zq@m7yo2BMf(HPoDcWrs^Xk1Nk8rDGG<%%Zo0+OQ zhhNa4;oY3T@fZ888?ope&TfYN&uY=p8;brSPd}Xd4yE>KmscO)T&s|886>U{48%qW zJwW38x!jIGbl@KK!XlnJFa} zlDns6Jo{BPZE3g42K4gKe>~PU%Kj>2y{kZ5fjA3@5IH;t>K*sK+!@yTVfadhJm53E zaxC2>!CYHn)#T|r<5IQ(0eyOPXW?Nt8=2-Dkg4@uL1|PD>FDbNdnH?#etirq zRWGdx$t}c(kB7p(pB8LPOxl9zXXj#F>3x8>>49Q5T~)zUvtIFV2G*n7#4#`u!}W@T z)nKSibaVmtLyUR%;GwS5z2+Xjnm_ zZ%K8~2=|6r%2Wr@aFu|Bj3g20hnmXjsiW&=*)^#aY9&HTKv`--dv$KkcZ_a!yEl|2 zsx|E131ok!M@P=hjzA7Sgg8}n!37c8XPb(;FbTJB#F|Emg#eft+DXk&*I`%k53NVUmXDY zeuN0KD@F+`2(?~g%+zw_GTIZWGI@_y*Jv50PB&^PDhC#{8=y#$C0b^vF+G$UB&*2+ z>3TFT^ScTOi4`C#jFg3Za6?q3r0C`AMz&kDdXR`kx%D>7(@jrQKHDq)Ol{CF-ff(l z+1Pn8+0wwQR+6$ZCg2fd8$$$t#f=DlJ6P3V(@)kfG;@E#Vz!y7!hf4r@)od94)RIf zl2>e2b=zNm=JuqGr`b->5M;FSxmax6uE;poFnm+173FxKfmNWg(C9`qw(^BCv#-u9 zeJ)9I5erz6-3H$s#XCjLviGCs-q0EQuRL`@26*$|@_r-M6` zeUu>3`W`2Avw3T*z>ieNgwm)szFugWk$&d{Ikr!ocx&#l&NSbQIs({o(OO)pKZX0s zsXR)4PVoV1BVZA@1vpp=tIhMl*IZNa{mptb>@5MSFXE618TpKqnHVSXRD)^H|3nW8 zg6P2l{{I~lMRny6tAAuP06mg50aH~|lm6?McV2NKc0=#(p>aa4!jCsy2Vb5ngz^Lb zG-+c;Mhxiv2%#Z#Nl73trXapv8|$?CDEonNB@KndxP+)>$t>EW2jFU2<`6@8J1W(C z?%!_uM2-7JZ3v3Y67~z=3V%NMGDP(oS5ALsY_3nhl2Z*3gT;eh#0k^_33(McJVxg$ zc^!B1OmP~?FQkdArCPT z!SThcv=~`;JWe%*x7qDo0vQSP{_>pk82k*Gv6T;;!VQ{40S)wcopXh@GvP6$$<)+D zC%*N@w4jfJcr~2`zOwdEReuU7P*n6J!MxjrTSZ-N^-M-?dEbQ`cS7Nzh^rT>6y?H8 z>8GiQ4dj&1Yf|CUO_7-4fma(l*P*_Eb=U3HhW?5u9w_JkNi^Cq;=@qo~x$^IbdAt3XsCN$J7Z@$BS(;nl9++`yNm7*sE( zx|1(srkN><@Q<7#gy{ZU9xEfb0PPAI{Tn1WiPoZ(1LQ7V!2RDd4;+NhEiIO($3MlW zlzzYd(J-!O?ZSEk+*sZK4;vC3alRA9OOqFQ-8e7g4?qz>kVehz%n$A46z1 zymnXv)I)rKGNq87TSY2~1_WxVW`WYpHfOTGpB9$3>lJSZEaX)}y{=&Z2*G9Q!a`}= zifzH=$YR@$V$r4}Lq_>)kL8^cvA{@{P{36Hg@b&DynYYe9_}YpIt*n=Sl-E>Bovqt zLVo}+&vzQ}MC+^{CZ`ouS72<#0;0a|XSseqLaSu zstOI|bqJ+Ut1HiF392A)wb|5ZnsKEhk3=eJz;{?6)3%xXt(pkrCK=+-G1ts6UgMj@ z{R|~M)AZ{L5}9rm$t1}vzeFXq=FzgbKaY+>P)WX-&1X@@=nA&tg>}w7V)zwBodf9? zQ@j-s^S5Q-@)1)51V9-OZA4|?c5+pwV3oNKfG{~NfD%v92*N1pBJUF2y7tr{#LD9G zK*I?2s&>OlyS(Z_=6Ljg9%CNYB1ZqOM^ronIKruO+xtb#rHyw?3?FUJ>HvK>c;GLY z!Erap*_h3*8xg$yPJX4fy88ZpPhX!7(1b_nr1qU1$m|drJ->$kxhQcM%%CB0$3DIH z8SI@bs>xX+>-ry9ank8dynA1&R|1OU zYCl&amhGK;(l2lnL&EbYUJ+UD`a}dc25$8}B8fElIB6gl9rjC&4&_B&6QCvkgdGn8 zMSG(uC*GB}SPpss(*-DMf(3g6wg$>;jwmb;?NIh&A4R(R-EBm9!)Z4L4rA`WG{yW$ z4kPDPYxW6^+NqrIJ8@wJ#fLzcK(9#Tcm#YYuk_Ca!9Mo1J{A?L841I;dv_pb;vRc^ zhZp^n%}lpNMX>Q}qkvB5BdZ;pt+{YlzFhBJxQs)J|0f%;jpBauioN6J8`sOvcaPx- z>mjEbWzwCgPON(J8$6*=#8e#Bpx4rvp^f7XKEM1>o6X9m&z)4yOSQ(<_8y?Se9l_? zqVxaS@$5AE2-E;o^`usvZv}s_O-*5s+^(hg>`T$Ri`)Rw)AIts-hU5RKpRLk${U6Q z*+xvr;?o}Rh>Gg9UmRH_6j`;0U^8C!KTJ1;BxLC)+P-4Frcwfh+`akox2>!Y6lP&) ztY+om%~3a0PkMK)?7eC_P)qYkP=rj~3%k!ff7rs`Q}IDnNFpuOwlp-Sn>aeRrQQNT z=h7tudU|=-q;a=Mc^302Y~JOLVHgECDV+11Gw|q(dZPqUhTXYLN||^Ol6Jr(xb%Mw^hj zG{8PVCveyX6jA{H>ldp4_pW7>{=k^X2|iYX=PX*#8kaF{U#2(qr*Z#a{BKH@{eQ1P zWAHRY#ss6sDR|p)D49?&M6gatYj?vP97@oorLHVclb_f%j&x6Q6SeOWT9?f}%l12S zSV^BHSVDX-p@zMmJIQ#lP6j3qwr3)ZL90}Xqti~tnXI*0P}aA}VolPdlWwY;2I!N= z%9u|6pk^$F-j4C-Zi!v5o@)7}(xxpFWe0hgto%mQ&_PNxYwHc*rNFfA$RpD1fx_RM z#0UkTBLw~W^*x8%!*?27#?}8|+D~2O0Mezj2h=_>kE>(;R|B0G?!c&#`dG11Iml)M z=q0Dow0Qd~;_ot|!0_)U-FKBg6BkjPpmBumD;enPYZKw+<*oPMFrs%SIEG2(VZtz#(-)g6(;EM$RmxK7?=`W&s+EfJtsa(@M9OeuL66_W5^43o}GA?isUzjC&Jr4)YB2k;VTSY6tQW zr)=u#>YD~zgsx6Kr4##v9ed!TBf*shn3ZhgE`Kivm>-oInLXh4%MY}1RQ%OqoS6|^ zVWs}m{a%o@IJ_k!8tZhfk@*;!h_Tel{Mfq~>+FHnr= z*9V*?w8o#wEoDJ>CLZWd1};;x!A5s)cgAMGrfQOQvDf8CmC3ldmVPg~u(EFJ;%ur$ zeFS7|8cxP~#937R`Gz+DP?EsU_xp*2p5bVHTC5y!->t=--LB4&u?cJ2 zGrX9yL~l=OoGwTjEzOn%3;sRxNICxdRapTJYFdt3jljz&DnQ=AbM8#i%WIz6p3y3IkW(eS8eEkEvmY)+| zwdDD$Q^IB-O~E=X_We~cpFt7|s#MW3cG0%WpF}apxFe&#A4BK(f7itRDLP*zg51Tc zlhF@Yb_rJPRBaUSjoXkw)6x(LMpHA(`SlpYSJb@*GTK(saohAy zY+Z8Qi{6+6*a5in#~Y)DDG0+7;TNUXAtghIXty4<2(3s3s^#7n^phA-deOYoH>4sC zjqx!P^m-L;?&iRE48-T=y}RpOia-Te(=F75c>=nsO#QE_ins zfYIIg*6b&|x#>Sj#?bLh^+`KMUMFu(!VJ32zo!v>y;kR98Iez7W{RCHO%y3zTsw?r zYUSHf@<3CmJelVUW?PoK$?;XT`q$uG)X=rQA}|1puf)xN`C@)o=216^1yJN9s?>Sz zLudjIq_B8%<>nKBk-BwT!+6d{OV=Xue(SMG_Sqb<(b}n#+lNO~p%^AGd*ZC}m*@XI zK=S`SK`1ICP#^ZnsNCcj|tLb4w@zde&M)KUQ$ zWdEh$H7~q%(og4u$xF=rs*Qhbw~GWR-#1fXpyfz2UZ-G)eJI*$o*DK15en(}T=TAz zj~3SRt*da~v-2xv`mist_1g5lqn;h5N&@RkaJlnjU-mz=H#G(&2dj8Kdfe8q20Csq ze6tXFZ8gRzs*jOO(8jv9ZiF(gkZO*)TIB(>{@uaq+;WI%Lc-%|C|`X-nocbF^yx~o zn_-_!-4#KfLm>=is*$JJjhg}WxZ!2XWb+x6W!rsg&unr^N8KW_!FP551p*KR6wUHi zLe*cTy1W$2Q^aPlAV(xCSkWzwCfIt5ke5C3fMIoiKA_wtwcOj|&a9>qk0bnP^VX~H z0Z*fnA9tMZ#fjLo!vSiL3<5u$gycS@8BjN7gCwf4pVL1Fw4+;n9KqG#mGxso^^cBZsEX2n zpmZmpNwNOzTRh-@Hx8_Sy89@>T(w!konB7Eo_7BUfrVLR<}q)Vbk{iNjj!AO>ZgDm zdE8tM1RqB)EbUrjrCKcl?7~2Ko6l&9jma%J(KeI&_k<7^l7m7eFLi7T;C$C7r3w7| z5ERykw9?i1p{|$!YAMGO@Q7ykPV@QG8QQ>#K_K-5=9Cx`*`hhXSM;%8HuDaIXCltO zYFg3ZU4YP7vZqvlix!qgLv0-kTb|Tv%NUjcdF4j0K=XY(HY4nz-vOb@$Rc{Bh_b3{ zY>t0pB4Pgo_PqqAUS7@vp)`WCQ-{E*BnA$tU4U$W2?>pg1|6FN^{9rjk5YizxgjHD zjrws2L82Px;kV=RQv zBBsQW4H5TsQUHPYG0kS67A+Km?6!aUFNxU2#iixyFJ-M>vkn}ZwIE}uN0^XXJhW@& zCe~W0(o0>RuooNsJDY5?|GT1{C`8P)2nYxmWUC*r(f;Dbo726Jf^20aQU3l4u8%>= z73C!h!DK;K-T|%E>#;R#(9Yz{{ZNU0CzX5PnBN}(=j>=<(SYHiq>D+Ndd96=RU_-o zS#J!o*T<0N++$?f)53y!CB~T9ooODGNE$^%*$(JlL^M}aJYj71*m=hz1kia7@)6Km^RR&aMW*}_7QJidQZSQ=e>4``!c0#L*OPscMtH| zvW`?#2?i+kE6z5rqgUx$03fMVqkco6UT^5$UUV+B6QtWT>)Gl8qbu?R0!UMu3S(N_ zv5D*D37@p0zwF^B;$P6Pi=MhT=Bvlv0(K5f*;NZGQ&VtT>N4PSgL4nJ@b*@wxiYht zob^{6WC>K%kWs4fQW!FD;0!*C)7$qeeJ7S~K0MpjeePTSs)OS4vgNf$JIQ_t+aqeh zs2_IUWbL_5kk7^gm*!;Ze8?AgqZ0RHsA1ipl4yU}Ie5hR36P)0X>hSnRv?qnkB1N% zXt1Hz#8s87#l73->2jw?BG@IE(S@@94FcY}YFRzgVQnLCBN=hkjL%-t#l0czd3u`<;iVf=zH~16%#8|2NIqrqWa6z(&%Cm z6Q@Yzqj)6Wr(fsJk@2VuWU9}~$}0D*y|2nsTdBTEmrFq(!(6jZz3XJ< zp?VicPK%C5_=w~27h9kYhEZ<)^-JRq;MGQ}x&21(Au~z*5u=o^ryDg52OmP6O-KQ8 z?iGWa4I?V~`-33-97ZL;Zn3#110~2`>ESUsb|{jl zR>)2kw7R<5{oQLflB#!-U&HM~-Wx|o>C}26cq`O&HWuE!CI99}l`x_0Hg(@DkT)e! zlIbd$JNH@qE#l{~5zyCdzdFh4okt;ofY1D0l7&P7g8E8KF1w6-7G@~;e7A4wq%HV( zYQHfZyV!VRk{2&|artLpZcQnDe9^xwh6E|}ie z?d2D6EM*K7%_i(gb2s|69a2~r_^(Db>|LL2xi2 zPJpM&MleaLo8tuKpP+TagW^1_bRovk4k^)jUd;pk=x7q&Ng~T>)SD+d*USV(^Z_QKR8RD0{&Ity7sSswZw)|>_4QF z2R-3~(C;jw>ghpkf4-XSjg`w4tx+rg;Eq7PUZyf^kZGsBx>{=YDiUn@&b7qQ zvU>e%jn$omu}3?S3>4pGyX?lt#tvlt7QsKLLlX>HPA=lzxh+vjMS0|crTQ^Xp(*uu zflA8sEWg#E(f1$P3cZri2aG4{I*kNB|NcMq+M7GAKQS(_kA_Oeb{ag(aW*SWuktfe zcr6GU_7PHL>}Sq6ue|iv|D^&@Cg5}g%}P*1~{31CV2lQqA1`Pu|v2MXLTCo3S43|F&Irbd>zX$D^D z@c*7PLKmYtx19!!@7C3?Y7-2;@%^`eznSTHnf|o0Jq^_F2(ZQc8@ibzU# zgVdG|=?>}cZUO0TP`W#$8|m&22|+rg8#XB|{jSYXpWpw(dtH7wNB3TPt}(|PbL4$r zgZ#J@Uv)>p3hb>Syqhq$@b+%s-cj#y)JwVUkpM>>99UvHYvXH3=mc9n;SFM%v;YZ& z{k7Ssn@PF-7e#$_X2@uf*&Pt5g7=+F71wbX#{CU9HdHQWELsDW2CJ0B7xB9&A22{+cE7zo!S1H}~3xsGn|4v0c9 zjcHXG%_qnKj-J{#DUk!rn^@x(wDfD4$3ta(uM|Aa;g}hK^jZq5c@CDvYaB$&A&xLf|1J^E&s;%{C-c@ zAHc%P9850UPMR5<_GS+OXZ`yaFk9av_EjdeKqzXL6^mJ5=32p4oY!ZBebAR5J?2tP z=pJB?A10<>s5X(3F@m*xe7IMse~rf~e#Syffa+NrBhI;ToZXzKU9fZ;`onAOO;JVB zgCUjc+UhzdJm^;L&ry{OsSU*D`nfABUYG$EY`9(aS? zjm!}xiWP0M2`xfs7|EY|BCn=GSCiqX_JNQ2{l~$#ty6SwXt^ZaBe_(YGaYLE->0O# z`|rGkci=slevY#^DHEX?jHlNJI!01Y(>#+M&uXeS+iW1Bt9ME{Z`pP<_xeSo8~XRI z_JL+&iZ(dN%Ikl3RS$Gh6Bz`9Gmv%3VA?$zMqnD=QR^hqtzxJHSc(@oE)EM9BTGd@9^`Z7@5p&*3kSDy>ISuM@zLbyjCc^nBa`k-??Gg5-!c&4 zkGY)F1e6l^(eU>|BA%rO_V*h013SnPdq-`6d~%sP)V!^-Ppi|MVgn)MoJU$%0D_5+Lo_DyZ54xJw;5DJe7MK?cz+IFRngPA`&NLY_72gg{|(nW zjZ4p6X3o_zZU{gmaFtLG55ydgw&}Fvc_(1dsUQ9Ct4x5(^&v^RmzGt3#Nj3zc0QyR z=JybXB<^xzH`)Ldg3O1UM4y>-*U5?hKf7}SG1TU_P-mc@`r+jDab8{ z9#=l!%yT7Qt&5#@Et?LtCh^7GG`k-M|J9-=UBE+4rqEcP>63_RfFLJ~hXh9@=vecJ zAziN_c`EcLcS%hiM*tQM0i_x;CK>(hDErQZ;dO(es4rQOOE~sHC1gK1wSj{9WJ) zb(kv5hwYEwgZ#w))keb!A#pe4weLQE!2;ZCu?HHMR;M6xXY&oc5!rHJN# z&nDrMTNXS(yOajYsWsKb7#=ZcIeWx>UK3^CGl4IBsKnJt zCV-7g^kUZKBXBH-Bm(jK{@}2)Y640M5#h;KxUkUpbb2m9;A?i~UIV&7(py1Gg937p z61~sc{u%fP$aETHfj?_iR3|r5JhXuCYXw0zVAUvTUw+0vvJ7(m3tA@@nEx2XKFFQ$ zWS{V8FKq{~k@we;V|kIt~%*|&6Kn9U&%Cl4qgDSqi>B>MM>^wd;GhUtBfFV zA;kW5q|YT5G5kOE?8PILc4@UVnF0bYTT5;qHW`3Ctl;13>TAPn+fbCki- zp-B+O31V4N4(FHtrwl=m*CaPiG>R-5mhyCwy zAr_O1|L?8=kHA{UL4xSWe}AfYA$@Yr0uvjwdw&-MEan09M_zwF*thbOI{;Q-eG@%> z&H*`Z|1JOj|I`2b0AkN?e8>nxg#V9qS{sX=Ia`&dSATlKZ&S!W{clOY9zM0e#6)XU zgTuHW|Dq+U;}oG>{x-HaM=|EcoxzE_ce=yXAn?KJ%Id%R?Hm$hYq)X#SRKTTQOG5a zu<~1Rd0_+5tz|{xbVinHVD^!S&V=T)m0$t;;$0o{ev!-82I|7*dHZdKsrB*m>J@ag!z*!Va!i^U)Uet`sdiNZWOqYq`umH8ccL97ic-edLb?V8kRRL4n{w_j%{ zS$U+Ln>SagS01esztLN@P8~*}%tmHBa_Vy3?LV_p5{7tZSZ%yB+j0L{)49R_Tm>Kl zf{I5(Z=evfyo`qvdcFTHN@8s>Uw80kd|E8i)g#@Zk976Y=gb-G)YU=GL%Eu7-62BJ zKlF*4AsTAAT`A>oW>V_)2o?MN!)%^em;K+9Gl%!@`2Ze9e%|YYjl=tl^?+pNlV+-X zLzC>JYHO^HtFrgOWv{zGuA-|+PI~Kz3JJANz5iq(C7C(G{5xPjZ{^)rsVt3ZO0}eT zpiq-<{ii;v6%_3r)L@0v=M3MYf{g1B3t)O!6SyWL?t5l60NOw93L5$mN6gTyX78PH zlz*3@i%rDP_Q0YYWLf?i)p28_No6Y?xrft3&$-%>_udw8dwwYb9?SGQ#a3#i1;Q1+ zHoNa)Plqbp2Pf>wlS9l^K#N;ehPXISPQs~2u(wuKWB?xg2f7Ep@Hd*_g^fo$1a-m# z9Iz3vv)N52gqkUT2xtC}u+h>}T6IDFcV-<+=jVIZn|u3vCfBC?-{;~gZqviVj-%;s zd7SEMdGy)QmHudi>XTFWf?2A%wJaizD0ABiu;>RkBwLq_$Lmg#oZl9ru$N25?N`DZ zb^Fr2N|ZOZJ;eN&tygo^#3eiE|M}3CoPSQD**T-96L8t8bk(z6vtSQG!oAYEz=|7Y z`XUeRzdOiSj|6-^7d2WV?GW;dIQxFrWA1wH)%1#$Owo28iykLP3>!FoTCI%2Z`CmW z#-@EUoqz%#=>Kul8J&4FU;mWhLL^>4EK3EygAoTw7QN}#r&Us_ z<9}10Gw6MmWG z32AV;MMCrjVxKMH{zz%guCO90oWUpN4vf(1&tH8vN$k@wu@?!i;4kBHw0#KuJ+o=< z?}bqR60kFnuOHw{%??58yAWtIz?SK*6Mw&U3#7f@g&FR6gARn#ATKTt55Z7uQ%Ruo z`1e=uG=MAO{Tq@Rj-iElMmFtf#&E*K8+VQKOZ8;i;SKzFJHE*yFO}+kxr<9@?e&F* z_~1D+8@W7J!9Zo~1b2@=s*(vY9+3BlAljU_VdtT%OHk33w0$?dbkr)~+~$_&9~k6T zBv=eDwK)s8x7|%rZSjP0g#{sKOF2aiREimGia_rB|9u=Qpm}Uw5Fv&WzRtt5fBk*i zFMQ!FTPlB}11VaTih!E;J>d?a1{6)0Y~!UJX!NJuPF$FzY_vZTcsZjmoJOO%d*P1@ z_dp8>*9e9T7*%cnP^qenK1mA~lg{E*PxewthI!q9KNkN;m;s#nSil)L-o*osFTIkr zkKjj1mmhAE-B2;W5&W@$pjfM__a_WVjryZ1cogES#(0Wlq(G2MM;OU1V3H>1__6xH zeXA05OP$|`N;*HD~kMgR|rQsI0w~t?xS{XN7gnj-ixrYxwbu9re{G>GD zfh42RW&^c>B46LdSnm+ftyMi|FnJ9)PXqL`nfEQCh@KF$iXAYAs-_!Zp0REPZ7}fB z$}RujuHyc=_{VqEPnO6N%q%9|cQaxa%hDUJ#8Qr@#hNqR{2LlxseVWY;@{Y_GeicH ze$oQbniYw`(?!oBZI#W#Ki=EZ%*Qxvr6?hA&CkfI$kWzjx~oyl&*vfS7WFXB!t_I; z?OOg1{J;un;h7HG)f$FGiS~*u$anh9PY=!62OsB=;-Z4m7@%vgJjB?grNb~nEEc+f zzLKGVx&+n#Bv21Q52%8QA+mw^3gf@O-&#c)M`Z$>1f)%3Fy_q;>_F7cm{vE6`KG=C zc>I2TaiOv#i#_D#tNs{Hju|BKeGZF2lHVPWLX-S>m(*3aY77O%KGZFOmZ z97VL&HvL+C(WA(g(^7*e58>JUy}k1q(z?2?M-+J#%rsNGL%ESP&kl$~W7JRa?S829 z!Ac)zf%6Xrx5I5Z+0G^JPl#5TrIr5PX1_iPPklfkorQFw^$!?%H+<;{6wr*|-kISq z9fOBV=mVzX_p98)didb_b>?*R3P-m{Wy}O|jSm^tXKDZ{-}{mT`df#X30lLd(aBkH zp?+1}LE<7%MZ6xpk9uP3Rap|*Q}Su&y5G$saJ;dws3->L^9BK&90LR5AR3yu!9huY zz&-)s=9NrkvwEV*+1xbNXm%{Rm4JIFh=yd|PESwC>F8vl>TFhYff^At7z~b0O{FQ* ztedEwt0*r|luhR{_nzS7=i<_=AS5QPFnKQ`vJ08R_zz!tffG@U*Z7A7P^^Hsd3}-3 zUYK{+MGfUJ>A8W(bY!`;Z?v6Hxv(APP=4}D#~h0-XZNV!qu~)z-rL|)06h(l$iB!D zi6^}b&EhX}Xvp~bxY7I{XG@ID6Q=+cL>-lg%~5UgI?RMvey?mG2nIWk-)-#^*x#yE z_IqJVwB%l0T+VzhInL9{O!_I;zCqFWz;nU)^Ln1;!JX6`$A>hys<4n+18Cd}Wqmn+ zcYUT3ECb*g@H^Ps8w2d8?sotdPi#Ga3R$XA6n`r`3D4)VObXKW4Awh_INHKBB-1;>ITa{0m)$cMmogU!!|=YgE)a| z#8k7b)!q*(RF|~=V>mZJb;1vkA-bFnbZZ>-eNOsbIRf)!*dmeuH&o+pM7;=95?|Zq zE;T5d{t(YY#%$I1#>f~*b-05pf~CXbbZm$~R>;JSnu7pqc6Qc&Xz>CTsgU)rvso$a zh1YWCm8(9P-x<_+)(=B!IX!J~ZFiv2h-%z?CmA0kP^_7lnBGoBTZ+_s0XUp*o1*Q3 zmOS|)Hjhh7OnpR#tthLUZ6RUdSx#vuiykKwrzvFcdt;(gq$)8-T|>hh2x(~wfI0)o zH*OySGg$Rd$^DfYdywp_a22Np_H+>G^K#i9 zUWf?yvo<9Jc~#(4DQHOKth?(mH$%G{p?SVnl%gD=yl*Jqi~>yYX)D(K49fs9Q+%J}afW z$1kj|oJa0tLnY$^rbM;t%C4rptUT{Ieyl_hcGN`2z3aY6@iAh|TxNe$K6|}S0{G;J z-X~lVyHlE1uZ^_y_oj-t936pD)hR#*vWFrcm_@dUq8bp8+RnvD7A4N&kJTMXS|C!K z5FfwWYCFL54cop#t6|lUX@FNm&(1F9n`ofqOzm+VSoU@>%?;t4V6Tf&bvxcDc(2v% z>^#n_4VeEYoRJhESRYHWP7P(aFQlq)Ih?PXtWM62wAynWAPq80-h3XG16ZT~qOS!` zfJNo3NlC%Ttk=lOah+D4#v>8n2R*(VVA`Aj1|}F*JkKHkhWUX!i8y6PtB;%bJ4#4r zwM?6F23g{?d2>KdpK>MXxclV+C^W^^Ii>+yhRMx?N(3|<>} z<|^l@wEJho5)0;)04IX{2c91hE_U*;~S6^$ODH52(Xg1^OaV_#276m-7ldGp`Plu=b^3IE- zz`JeTK;z+hR5#Qk+h#%g)g!;h&U1Cq1n(0TP;~T5*w4?h1CbQzK2fW@RG6x(aB^}w zEN{MCUeKJqbeXQBvCzPG&I@w{w~-6DAM-XndbD#R6RizPp&$(0m;KxX2Gjsl86M{2 zP0tm#4I<;aN+E5>ix4yPFxC4ODGdwDN9$mT1Cso5elhh0Y)Pe>%IkC+k*R&pJ6O1M zvv3?SAkkg>?5_fV z&xkBV;Y$vzn4mR)YDBiGz?ds8nnc(!X&@FeNcHK2o1crbPDQ`~UfGNzE%C-nIkQ=_ z5R5ErQYtc#{P;ZO75(9*Rh-ckc2DDDCEaAD*L+FmC#9-4r6r}@K;cItiT7x?Ah#y6 zo7C?O-W$FfNnN+nMH`^9BI=pvaWp23oUo}j5@w@~71nEb?NsHP)@%Ri?7HCC_6j+w zCCc|~8uyrlw7Kkdz_3c4mOp4d^sS}qp+l($*a)@Zi{kvzt{@so)oGE7Xzd<{0nU6R zPVh|7g{ZNoWo|&lJ(gFCI={KoZmwGP?N9V2F|45qm`Q2y+gpHn{1-rRB$-SNg|n+{ z0Sj+&*Erc=qi5G@$9*?~p#(4I7&g9yRqI(pi*1Ir!#Ad^Cg9~wh%$-9vGMo7 zZvJB-Xh)C&QE(t82`Ywei3(3b1$PSh(RZGMkks@JKX||0AsiYSdfjzsWCZKE-Q~eg z@r9W1*DLLTGDS@TNKz=XgaIvql8*Pc->V2*eyw)x&XlE|=Na*Hjo?B{1LCN<<5CwK zG34xoNCkL(Z-hOnvdflrR>bBD2FRu+1?7KjYHFImKLX%dP{j!Nn_oI~k8g=Sx7i$s z!D0Cj9v?Gt->a-hZ~F5?Zc&-9=1nB*#7Gv)C)inVVh7>gLd&Na-p?8R-C*V)v@QzC z`=4;5p6NvTv#i6{R5GeC=plT)7a%G4>`_(CQ&?dQlOocEThVbF_W7cyM07gvSb_82 zE}qDX=B?%>ilFsccL3SE-H1A6%g5=r02gG4JT_ve7sgxAk8w_R$6a}l%~q>oUX3~} z)(}Gw<|b_-R9aGEM?_L$+ZG>uB=8qlVOy*DtP}_fe5nx!z58R}->Bj|PL_V);)lFp zb>E-ZOUHaK(B$xg-Vik@`jXQo>cs*BQ&Mi*iF8_(`du$T3K!k8G)HqrQ3+_$T+Ki; zGJ`K#Kz|!(5g&> zchs_vhLuq5XDkF7#^2ASKB6i2Y5Iq^K$|6)&0GkWSUqcR#l&&NOC$C9F!}x}`5DH+ zC(V1%RDn4x=b8dZduFgTEvJbMPeI9q%s};wMrLckH1}zAY$9onj*}bQV2R&V4ul9{ z+36r#tbcK?%4mxlx_PE-pA(7>I0L{a^3#_8#22)_7M)zo1f45zChm(%aA$ zJU{qWqm~`6gs&Q_wC}ve+J*Rex*S1>!DH(ygJH5o3ap_~zqWaGzVD|)5STdkym9FM zWn0}!j08jcB^zKWyZt4ok|057oKGPUx%4-KvUp>#)$eu6)oA`MT+dgXChsui9Wp*^ zUhuz(cj81Nje7)BrGN^1ZG`ANkVj6Cd%&(7@*0Tm4*9ZLpN+t|FMTLmbb`vA@qT{y z+o!W|f9)LanEthZ6~$CaQKx5{^$@+StT%ixtUQsHPT(GNMXvpsHin!h8o(8y&Uvim z`M72wPFLF1{KFn(lW!)5I*Aa-U%8_TOj>`V>z`5$)P_)rDjMEP=|ki*!C0^L6>=B= zEh7GsLkCj7nDXH64w^c~4pE;~C(~?*7SSNi=Vs2&%;-IJFn|LMflNozLLd;W zX;#EOcU2tgt=~8jvzP6M=o;6EXG2`C*25SiB`BcqE;Yg@k6~04J~eB|J$HI1Fyju! z-Vy1=Wr{3OPIz(sUBH-DUJ3f^ty$Zc+_&QC3ZqfZ{?F*MI#@-qmLLbw1>x`#dYmmc zdG5sE;B7~ob^7xx#VC_rF?n!F_Wb2E0uSH(^fVc*6zef=#_w26H^{$o>9%68v$ z?7ve0EJI}Nzt<7mBE3fLz+>5dFB#J8`fz^(&6X#NMptVoLS^3{V9uu_wjorz$MDSr^Yk_gSZOvh|%;Enq^d+-jk|CBO3~%j^a~Pg)21 z-TR@jwLbwAp_2Z*iTFF4o9YG-iQsj@+hYwqmrZH^{t>a>1!74F(ipeiH4kNUK%LH7 z_Wp1<7MkgPcXM{V?7~kqH^LVT0`Kt@&i)T07?n)aJn*H|kpQ*jq7hyurOQ{Lpk|W9{z4?5I@R`kP^|!Xw zjax$QRVrXb@aTlHlsfL>%bP=AWV!j;jhibAzD;9mTdh6H=J$dI!+bT!v_!E zphJAwOfzRt|GhF;V61J&f3R70)D9^0AYnvhJGr3lij2`p3Qrx}j%S-U#b@h!T}->~ zW(WNOK%V7ZvS(BPfaKzGoRrl!JxJmh>ipN6=n&wv_3Dj%J&(h8ka78S|5}|`KxIti zN=Zzgl&AL;hO*g#+Y!gb|JKYUG;WgVERFkQ^1dRcIBQO4o&!*;Z(gQVtS_OHBk0jf&TN;e>wSTcQWke$8WjR#OvH`ZpjuEQ-lFIY8hL~=7)evx2ul1HdJ@yL>> zSz7w=K#_YZWc6-phSPTb68*E}gluZVJ8Mp%HH%v^I8XT-w_YaJ5Vp~4eF+P@M7!LW z2?CM}Dv+0G$t!m@)g&m+)KA^49E3>I2zV$}^$gKWxiU6c=HV@sM3SRFQ$|<6IkOq% z|9+3H+lR-YBlav?X4w6vQALJAPoK!b^Lz2ZxXVtu%lZm{j~`$ButEIT`JE~=d~RC- zHk%q;E;n9QQ1Gg^x0h^F;oF78B$JAN=Zv#cg66xUPc`JYnaF*~<5~@L z7{9HcA|n?l{-`5E$JWY*sTbLSr^Ww!xrRa8#G7f5#Q|_Xq)2{d`Vt7>`5A>GQ857azdy1Pq;C?w+y(XynToE>zJlO*Yyf2uc+D?P`2SU zMUIuK)U?geIrs!e;64wkL(6X(`84TIsiwsKRMpAW+%-C92q=@A;Q|vXavm}wnaip+MIqH z2eIc!Y~8u3Yhx`8U2|7NBGR*$M-xj$10((2sTsZ4MhyLXrUhC0_iTlDZ$ubh8cu5I zg}Or2FpkT?!J!xR0%&WK((eIq_#+1;xhfHv#udcF!#aO=>74ADTb&H|>}>cOi48eO zpCbAP>qvG<;N&sv!DbZ`sNb+n{pb&8i5N3cO?$Oz{VobLpI;`h^mSHH1tZx+7h~5V zgQCdFUAXM#rL1-i>Z3MQMsd+IX4RgMLwG7KBH0r92^MQ?cT4vb#gBXF_2(P}+MaQhBbeA3HuCmHZ`Y;Q{P~i79xWYA zNk)cm1(mMfqccCWQgfQWT##ZFumyg$}acqyHU`KDxE9Z$Mc}0vR30y3D4Uo_n>c# zq^&5Fy_wV6`=Jcpi!1ix7J57yk~pNhy-qjK`ml$wyo?%i zxV|VBVcMU>Z#W%yoHO%E=q_77hf)gTr;#N9@;u=XUQSI+r&-(iYpti3&SiATW!-Ow zxD(_>7A~(63rAI++EM_6s66+p41Cj9#;l6=`u4ji*y=+XnMGD7OR{OHSLCfqQF87gg#&(o*cbIzt{bO zi&+^sS4a0aCkGK3CZ%1w90nXItTtIM8J^LaYTqB+{x87G74l6&YfF*&Wsm5Pt5JUMNzz1O^}ah11Igu`SpkvXkz$ra z93{uiZm!*u)9hLwzRfpa!ijc0Jf4Bsn8X8$fNKCJevI`M(vqgGyt+|G?I0RQdL-jI zmR>*F%$LhPh4(_;t9cK`-B@!{kuQ|@ml=`Tk&Kbt}vy@vb!) z*3;eeL%MxiL>iqfH361sC)l+SHwpQkrB@)K4plZaL;IQ7OPYHl+H}*tE^L(c#Era# z3Ju!$)@7*BNKV9RbweU4ypnz~uEZJpHr1t7`S{!#dQ+CPnWf%o%CW7)Hq@+=sIBUV z&*j3D{fWk@iu#v1XNd=uP%b^}eJ~*Qf`?x&7crXXhQQa%E!!Ux0iD>|g zEV}{&d?yVZ_pgz8&ruTTb@tMKXvS_m=mTX^kQ6aeHcWr-PMbRT$U1%;NDN##B+He&Ry zw|Qr%%Z9i`CB8Y6VL~dm5AI8hcIBMV+=~x(@23<3iVA5Y*|&-u$BVe8tbWTb>YD0LJ?*mB6nqx35qfAms0321 zW+&B--}KwT;sRan&D`Hk9qm4?Q0^vA!F5X}s%3#Aq8GU)X+kI`kXB zO|fOKu9i^d-Y9dW1*dc2U+jebey9(m^XZ?$l zdaL82e=*kbl~$Z5r~dkh&f%~j#^JHB!(sA0m1FNZ6@|aG1J<>Jytp1Ib>$jQNlYg& z!p0jEMR!XD^z2Stg&7ju_Ey!7CB^@2cCsL_`-Zx1eY3;=7*aFBCFLG89Yhuls~dZx zfkaMJ=7Y3OQc}bg*^DIoX+X7F+$tTa*Ip*ny}WU=P?JMrU)qPgd1F^TH?_=MdW_FP z(OV<>#dKcsvMw>WC~!ph;)}LHc-uNoPG?o%yU*}pWBW7cU5ycghSZ5E)uw6hDej*! zk_#;w5&2>kl>``qKtuc*-t)AskIXzZ!oc(4*Y^CVZudVd*mDvY!>Z^IRr% z-^&r>B%-K>wnS8gDeYw&p-;aa<7w<#B|9NBD}0=_riB2;S(${Q{*x6o# zAi}_Y;#T~MhYNWgrz3rkn>8?(%_E0%+PM#*I_{!K()NY;gTN>-dgw$$j&qlVJao}| zd@Z2wQ2*H-#(M2(h~4oa2g<#b=SMypB}NrkJ8345pVtR~;zHiZ126y{3{oo4-=8Tv zCGZFY&@{rHU1dJr0quU=PJ85|hk`N`(H(?^)X#7t1?ub$Qc+jpIA9n194XJJ z#e!*u_4O*|)(JHI91TA}u|UzT!^(fGK)R~@R(2)9w`POqOzV% zqhMT9!*5%U3y&F@&FWol!HFs)VkxcWscV$!-^T z2{E)jPu!-7xZD-d1k8D)ICL!P=EeyC(fk77DnsV_&{Q5j+*(e_Wk0>y#0o6n3O;I{L9GY$UUYRujPXkxY-Jq^HGf2Mm@co;;4hy@|YCwYjdByU$fk& zB{7KhRzT^eYLNIG(XCQqEzh^3PqKI3SpSfQ7`rJ(lBlYs|}mY~n`g@0&vb z-9#AnX{6`EA~l(5%L<(oZCEq8da@4%4L+g$1(K8kn8#SdCi=k@<7jiSvNqA7kIw@^ zH*lVLfu{o)-peF~gBo*LH6UwjI~}BP1*n$+#CB}`)y~h{gbo-x)IWInoj~P2HWa$* zgdr4RSUJs_nJ$1BIiLMWz(S(E4cGx7+h=}9GdpedHV?rx^_X0HSXh`O8U!1h?|7K7{iX9INN|aIs~AmnjiM4YG?-S+L|@c39{hb9T6FBkbl-iy)g^CN zu+C@w%y)oi#94`6>?4b6ni@Z;_-S%OtzFlVcCyTcM>iO!*^3Ed$=UHm{cEyL`yyN-G6?YD zFy|h&cwCCM8uS4!MvlYUN!ua11`;~DVI6n?Lszor9tblN*db+~2XrLX{bGg9{kX!Fc0e zH{Cy?xcYuoIU)IUEm|HdLv?@M`hsw7B_hAqy%g!T-%fYedGqc)xF1NmrZuSQM6iq@ zH?ISeWfT%^j=GA7A6B|Qd&#`8f_3`YEd)%d6GZWx2EPoh{7Sl%#{FF?@MaTla%dEg z?xpa*c+c?XF-U5tua$;4PI0C?VqqyiQO^%Z`L&*naIeefQ175~8X6kf_Ticab96gS zkEC)f5}OU#`yiB$lsk?h&!2i)viDVr7Z z;S6(w8>b?9jIH_0*Yx%(7{S6LV75?u>@<}7lfr!kG7h+{fIjnC)>j|T5GPq8Mi_l? zE<4c_E**@_DSbY`Qx9?ag+!2h1%#{IOe^GtF6w-lhgk zO$Dy0-$Jo;K(6{ND2WzbT3oynC})x%#`13bcC9cV>Ab1^V;UEgG1eY7Rago+9&zi}l@oZoB8(|-%9FsJ!({qfU)EsP%;neAaTm$cWF z$)e}RMeGzFHa68LHWt=8;Phjx9R>PmM>%P^WL3%@&(eg<0Q%`|`sef?icWb5IdWf7 zJxSJ^-;+1%5?VzoNXEt|U^J>7BX#)(zPS7|k#XYtD)UK7ZJ+y#M!?sr0`PNOK;*B_ zfB?PZd@qI3;6-;2R50T-=0puGwWzs#uZH5fI1ILqE*XlOV35kTdscsA`c`qQ?;w%Q z;SKn6lSw`~`}bge$2=yEPreup44`tN-9xFzYTrX!>iN?97f3o*j;+@NOD}?6#N&^w zj`4~$q!5Q5@r3##s_SR6hgxDh-?+fhF<>CUp#CWru`pZVq~5*{y<|*_xz#>LT+v1p zHCwL%FR7-NmYO!0;Q;_p|9Za`bvr#I(wR2~_GuNA-*W34SJfrSZ{il65U@pbTllo@ z$PwZ`0xK1fTGOA&$B-r*TIMEEa7DZmwgDgN*L<;(ZC>*7ewt`j`xY5&@GXV1-+IR@4i9jEBJhrz?F#=dio&X7amFEA6%6j~8}Q9e!k95ERAdyRSIea>%6# zkI)VIbH9e3wDQZK5o#c-fO%z7dla&}YlcX~gTuaP>z7x(3{XsS0C-R$=cb)KIfR(5 zzth3%dwC9#UC4kzsOC3-e#JG0Ipg$_M@RQy@;!{opyEd08^<{-J^eIe43j%~ZY-b{)2u0R zq8w8uo%MW3x{Z49Q@p}Nm8c!afi8_6$QX-f$W3k(qO#)%2}xg@X0=-_2KE`q)kRb4 zqXbO4eL=nS9bTB>l*c%uPO&TPTJ$ZF$}Xmn8Ep$C+n7Um*{cAbM3HRkPMC{LT^O;F zY(G5)%gIJrUQ8&JudF8N=@&6h+`KX8Q*IuPiVqrei)k3<*rc{)#!NJ6Ym)fjg8}_> zB`T7?nZ%9WujvqW$WrQp=j@&P%ERm%A0j@_#^650PpeMcl|KCbK`Bm<L(w_qE0T^(^EKliQ5c?&DPr%6zRIQhK01{64l3eUkFb{GfZp6`hB? zmKM$0YYb+f=fgiG1y4hkYEgnJ-5)3n!9$oA3U0dORVd^auyL6R&Es2Yi7RQ5sOF4~b5f7sIE=DbpO@;)l1a(&`|jt~N_B-=X91{GAX>#=G(#+BGGYYZbxjNS zPR!b9M@nZ=-1!ptY^cSj&s3LfS2(#yht6CA?8F&5KiKX@#-A0Dk0;Jb=ep0?b(+&$ zxZJZW#SkbLb4%fv!rHCVY%`^*YyddEzqaORsy2q)jufT5uo!g1 z5$GGA0q|cW_V&(A@GVaJfe^mSwD+_ymWZ-40d`snmT)KNq3U?w8M@nze&Vl+^gi$X zDevg_4q-jI^ew93kC1(&S}-VVPf>06dE^VjIqX@?)4Z2)yyMQDV0ZGgkGzSC!yjn7 z&;)RCVyZ==+7?U2K8Jgae;M4%VO9%skQsMUQ$gxg{CSh35yFSXD~pQ^&08*|5J}J1 zhAcwlsecWGGRbG@x3vlfxl=+*|}38M>8jE!W1o%A)pP@u$!lJSuG^#N52-vg1Mp9ldRY+MPn21BIpD&qUfYo!78DWub z%cfn<6>!!cz!|x73H3r1+%J)Iw7V`xoAmMC&RXDE&0P7ellRcMNBSwL`JoiVEBYh8 z44~n9rGfOrUMn;bx2q2U z|DhYfL#K(^1alv73K$R8fP_WgM9X8u-nya-xNB%IfrcXC6etgfyzeW&4F*vBAT??T z2-jV!nsGV$nxrJE*H%=ohWrr!3+9<%f!w*ri2GUUAEN!KD1MaIppRbEbC&mA94(DR zw?UW%k{YFxC-N>7Nue*4ZY0RGgsNDp-F!j&h^nCyf+e;=aD-X5ecpDC-q#|mm*!Gh z6hAa^sKtczfdkD=2t|}V(;)M9ZVXzG$YRL(0`P( zn-J5j=F^IEXFxXBDHfz+ek&KG#Hg9>}HHv9B%Hn~-MN5P9Dq!l) zN+6ZbR+&zd4WS3RXJO;#zHASG&Jn<7HNTt9t={5X7VLx=@P*AP<<<~l><|Cvy_j@# z!Mzq7MUd?bsnHV}J)`=*;UzjfW3Z8`XSg>YRdth$$AXH+4ZhGT(X0v z&rE?nwsjmsmb>6!SQqm*pdr6ODPQz*z1f_&7WvVpyYb2qSo-NL+g<0}FH`Lu@e1yN zXt3~aFR0*<=@TKs+BYZY`VqFs%A0alcwIib5Hd`kg19JtG1sJ_;!vSU^vEtORJv99 z-LpOR{s&L8eC=&tbWFKBeJ<3>mb*YYSS7yG{Q}2M`swFkPrZnM{3+q@ZBEN zkWExIB36lLXB;d)9yV!1HY3qhBx;oq0AHqNzPD7Z>x`Z_mQ2en&p`%%WGI z?ksk_kUICi0aLXC=%DKDp4TJfDibAY3~4~E42Rh`xH0f0*CgJ4_gC>+BUF^*9r2Qq z&pjg2Y$wM~rL>9`d_g%h7Khlj^XKEEZd9S6ERkfoL0z`Hnz_*;{pdrAAo^>iSPJWU zl*Fn)|I}JFctP4!#P@s5B$PyvL_xvAj{D$y+;g6>gg%kEK{V9zZ{z(&7eVFqQ<%0~ zMAqNBTgj;lx~tFMiNjIeE^=}w3Mi--gMvP;tawo}zBQu5xShnbOxjfM#~zU1_taq%-0Ei9*$?QnVuB|D!)`Iu^J4nmQCN^Gj4Le>D3^^ z;Z`UcZ?(dfPUCnUl{SygaDOOH!2f~6(8wqzKA!v@0{{Z=*f<;IPePk%Zhkdr28l_D z|GOWeQHHnspEifUwRU$JcjNI2C(``{3#i;~&@ZtA1)8K~dq}y)1l;oC^+Ta_GBfno zH2cu_t?MwvAVO!H4DTCryWzTzbtO$5k{LGc9aW39r114Xlbk>L!cW#aDyMgaS{EU9 z-qWhW3es?4C@~^~{2*^P&eC0L8U|LRlJ>X=Sk*+BP0Hk0F|N!zgDeqOCDbp!G+FyYLW4tsYu7n3U)NAZFiIUQv3PjSq?R!tV$J}xV{_B&L;=lXA&(Y=4RULUU%-x^>okXxFfsO z#S39IDSy_!D%jDJ)$~ z(1a8qmq-GGeg&Hzynvmu{F#ScaK?1KTpK1$t$ehmhv+k>bxQfNYA}(}VgOR6pRQri7wCDBiwy#HWNY^SWC`vwMyLn^zSle;-&b(sXQM_O zcuYTA_&NeKFjREznXZWGB!H_f#C(flX+=#Wbj`u#4{nII9D9YiwhLAb2IsruM~c{q zI@>mWnvZ364A6dF-zBTNenC5${Pq>xI%YKgit#n&eTZ!@ngYn6w1_z*6T|d{f?8Pf zbY^#Up{PQHEK8dg*J!7=&4WC-q*lSK0<&sA)k`NXZATnA>Rsc~L?)U7uZcDaiOlj~ zF;w$?ZM*2A!>~0*62TYMdl%9hOdnXXa-s;-2yY9umZ4k6L;%N(=w$iw~JK zO5Wqjc5+t9IGAaKW3zSjI{&tkMVP!>I+k{{jeKkGI+wB0s-5!#ys@Js8_7UO@IdU+ zwtELzwOi+@dg5~`u)}O~OR`0qT%8FPL3^Uf^kPzb-}E-vY~Gy2{c7*C6hoV`5Ha9R zk*EG_b*ni~G{W5nW;sIRF+ziY6LLC)ey7I|1Z{e8suPX&XmQn=$CMM0h%FH+e5^o* zarLGK5>Jqg-J?wccMcUcfH3EraJAg_g zgvE@V`ip#?A^QCx!cqVcwTVA7yp@b|0xH+RmTLSuWnQ3wl@>YgFhM8~Y}n#Zt|r84 z=)4MgK@<>&MR>utm$#BKN%kBmpvJv$6Z-w9oUpe}$*7~duxIcDB>x{%Z`~GE_x^z* z4blwVAV_zolys-kB_h%wF?2I@gLDia4JsXyL$`#|h%j^vAbmE^_jjFh-oX4bYp-?R zpS=EE#2U%x6H=_SO`n3AAhEd_c&>LGI;*fzjVSI1 zT_2#&-3$c?D4ipKbWq%x$YT!3vRhrS2$FK{x_;-2KW$bin)&o+J%8G)|0DeY#h&8V z%Nl5SI<%V8;hvdQW4ISTQz{g0zmibQh0(+m`3%pc^CClZ-LU5EHa8kzS>Xe6wfup& zGSTxfffeWl>$p%T<*52X;0B<%+`;vC=gyWXGy+^& zMRX}<qUKrEvKX#rZT@yEL9rbes6^HV^fcivAMc5^Z zna&vDGv&)nMZ(I~I653`?kh1|Dj_Nh>1Yj2&OW-bo_95Z=df`YzbF<;phX`H8H6*UnEZE#b8u;=K zLK*3ULpS)uf1fu6AIP~5DKBPoXB zSZr@+elC#va5qg5GK@~|=;_=cx|6J3X*u|pmiasqP+)w)3-LCYbSAs|Cp53zH=(!4FM4 zkjUsV%~j23#8E6C^U?-sv`7z>(8LbVyezipY}COHV$Wd9OV$RkCGw+JgzQ=8v3P8k zc{Z)@?FjWJ3|TWoZU*%;?87;Z>Rw=^&{DAmhuW-k8K=C3Qm5JF9lmK(yDES^7~p~y zY}hy>B(Xowm~bI^e&T~??1XimBPKQLVs89>(r+?y=pg_K7R8{bi0#4I>}6)jKPVp1 z#hT%Ei`%oX{W6DNyVGLeOb7inYUq9jNwg2?W^Kug5wcE=x{L_+XVAi;Osz5<*?=N; z3a;26Y(2!6=>>Y4OmkWK&{dhM%+6`V?KxH^h^R_+naEHI{ZgXTXL!dq0PMQ#22;V> z&wfdlXxPAoVBRhS^f(ql_d-vh@=v9nL*qYxKfOT#fH?V9Ed6`>5c{aC^ke1r#e(qv zF2Ibi+>#>o@Ynff?k#i07)S5sZ}T6(%q@G=c;BucFSTh{YZ?QT_mBa0&CTfZ z9%;8NSRxE4`C4YC)i#~I$_M@GH=An;N$IV=&`xf6eS8{Yi4$(Q#F2BOXKa)G0i)AG z{E!t-2lG@J3)-%^>^fbeQTg5scdjYo=8v!ta-NK*)U@p2LO(OIr};&;ZFsHat`)z~ z&!QoN3=AdwRfiQd9`Bth%XY#L#A(HdwOhH0R@+Vea@x@=TH-vbZ8VlvL1Ti~1{C#f zpJ`o0n5e(gp(^FtJad(UE@aPI)w?}59Gg6sdP&=PrLbEfz+3s9P*Eh{I3s*7wa>D-{siw%_5lAB8;MZ5kMFev`TeRx z*2%*Xxx}_-?%Cw9aozgle^pL( zx+SDlDCzjfX>bdC!pvM}KpQ&RKxq~^Q?8)H461#u8~Rb(KKD1L(Xva~sk$mPz9T+y zNNM%#C<6?kh3&1rTI%zc$$pl5IzA>p8^}73BE@=*R1!A&Ts(VmCyos|BU3w+<}+i^ ztn{Unh;YO~h5+JF>}fVlL86{i(xS{4X>%Y%3n?ZC7f%l;vLcZl@Y*$jVp;Qjqf z`h)Dj+gZ#@u0FXqMVJ=^R5AHHZDYH|sjD7b5>#X+^t&@#|H#W;DUs!QbGG83j{30) z>ePQ&A;w#A!wS=ok-)b4N#g1*+*{;BQ8H;z->4V#fn7VZEU}?dA63{5hK6N8V9yYt z0?Cuyao|`-NYP4w(HqNiIWCKfcrnNzDVt-CGCvT(=W;HoAw&>oN$i9U=RAUdg!#{{ zB^=4WlkfK*MX!1+gMNe_?oz&Ccc@B~x+G5!`%5n9_%0y=y6)0-T_$-2*ezApUR(IK z0HcH;DaX)Zl+wro$M@ojEC&O9*iT|c`6#^f zKgyA!^%#agGw&a_F#XINh0!xPHe!(MOY+}jy+zMQjb5uftC3toxRr3Q3#zMXLYF4HKTqZef67Bcc0lo9C>nc-PF- zH11-5VGAfLAcHNpdENYax)?j3E=CHr0eB1IcTPiEklX)@N`I8g5te;)e2g0wc*F*f^R`y6ail&zt`wz-! ztq|?DJ9g$?|5INjIL!JDlOh4sqWiCh9{&ic5k&Mso7d{?hXtmhnTr5{0nxVZP}y>$ z9^oxr$6v^clCzi)>5(%)n!E8$8L5vNgqD4Y<4^(2b~j>*Mb!%pEU!Z9tQsrGIAvG( zF_g*Q-}FptDD{k0y)>P8#~P{W>I@ewRhv@#QA{wBVg~udX{7O{c!6$ABv^7>&?suV z6!f^OUIMP+v#sU3{X@=VGkz(R#EX&fujznwA^b&~;qLX;HIs9q1SE5_G4&)Copn6) zmmms6&Y8Tff!?|{Uk{o%>G0cV!~`v)=3OWoR@6TP6?ms zj$B&~vuEC3rJaZ0cLMj}rjhM)rd-s}O^Ow@k4aiPDfkd+kTmP3DMG_EmSR$x_v-Cw zXHz%5pA$d3GyTxsO_ivv=5O8%5Jrf2&G9on!KPxJU%%BaIVfroXsRXkT`{; z>@;t{cPvmLFF7XmyN=1&p9}0}RvN|YQybgj9j!M9=Ow78mi8tjqI7;H_i_l-52ZdJuBte4-K%X+D_wj&n80xE&cF%l>( zA*eE{`;>{SL>C|k7{X&tPRtl7NB5p&GR)O?t+K4feBmLXxGUP`$Z@M_s&BA)TSBZc zbbwws8)f9%ew`P?OE~4fl?hK+qm|DpGs*jD-+P7%#S@X`6<4HmqwI>AcbDb!vQCs6 zXcKa2tns6B)+-1k`TUJS#Fe!4qd)#68Qg%SsQT(Y`%Om9(AYGC$S&FEPU46!A~}c} z?D_!05hIIH8nw|v*rR2rK_p^(=?0ok%&aGzLHjnUH#*^>**p*%kN`?gmp3O0^lLqg zPup)|TF}p^)lHFM?-M7XQ9iW`Bih_+)8}}%bv4fx9piV>&ebwa=|!b4E5gjR=*aRu zNXqPbbV#F%M2GCe;3)>sG@||#sQHPZsL}@Ct+vtXv2;xU#?@9@CPgJ$x;jG0=u*y@ z7tAi(F`fYCL8^{ZI$PI)si_c0h;qMv8_mFGGZ@!1t0faptR*=e@cLM{TV$d7O&HKQ z`K)>66IGc;&b+97C7^zL-w?ViT`vxnYHA=0r(?b$8?X6F*Slb1-=;=c)>5fp{xv1& zOO;aegVLjxRAQe}kRMtYdHd7a2#iA3*Gr-dcz(GeST836C_1@wab9|^xkMTK&m#qB zY9U;DT|%1^b*M6kpwj^|W1yR@9hDs5hSTcI{Z9w{7TPbz3*Nll+4ucP0ND;W7#KJ~ zTJ`o5`$N8))I@}bg0U;fsIH@t@1n{K7q{u=g{X2#^r^f-C0WH`A5y|+GpMP0jX7$d zgAo;K@;-|&Y45qyLH6sO@Lp9NO6sy=VSQwkkVsAOO9C5X#Xa5GzVVl=^M)k}&yWss zUKhn}S-o+1l?G3ocOch4OVmE-REjc#gwJCMnAtte+LWk;MknOIW4 zqbirxc~v?DtcmXXU6JzkZ@sb~cvGBIt-Q;k*+nHt;Vw7e+YrBd@k-Sr581+CB_)8J zX;7l=gMuAX!gM6Ht-Uu}`fkFvCOR4g)= zvFKIItz{bP(ABo3;6c-dR8pguK{!1wp_6_^i0>&)y@=y2Np0n7B?Sdk038c&KklLe ztYuAUkXuWaR*_X76u=$)z2)z&HL%KOyfT(`ro)`=_LN6fh%|y*{7K~Yq2*{q@T{U& z%y%n1ww??GOKrV{=M>q)WTL?d4;aPQWc;xMiGmpr!Ibb_bXC#+{%x@#%*2>pt1C0e zR=HH-zm51^`=6NX9?u(g=gCekO81l6KbEv3GPj@7R`h{na&}*88k%@LEh!Qu8ZXf1 z=H?W1wDwFB;_9Do_X)RnZ(X01;SI)rU-b+I|HWITB%W9nV`q&>vKXy{wXF1edSoX4^Nnqg&EnyBMq4G3m zB_@+#{sTFmgrDnqqTQ8}u_a@e+BGayY>ygeW=9v*(37v2yqWQas7! zWxC-KSc;Z1%|4xG84G@5d+yCY9D<@(qw*!BoTIGpJde;qe^+s>QT+RHuS^iq?v#(A z=*CfvMV;XR39BZY8i$#CE(f+hySYPyw+=o8gT&#iwruPXX5yG^?+JlH?X+fgfwRDc zbt7%Z!Xk<@GyN3?q@(A_{wI#{zI^iKN)~0tE_*_V9N&OSLdbSyObOyE=%7PU<&qFo zl-+v_!AE%CcbybkbO-vZhhUTjnfj2+P<=jZ^xgul(UZiWJNaDCh=_>Brwjb<{}WaG z4{rm|H!5r3QZEeJU)`n1*_Hm4*E_O5D#-n+up5yD($>T-W`ag?&o zngN<&P|8X&?{HX5O39N6!zV$U3$|>0 zuv(bvOQyV_gY5D}vLt8@u8z@jgCs_7p*CuREZXOzS}3wc^gA}AoQ3yDU#0cz!CG@$ z(R};*yIUG2=mse^s>UYXJI}{GLe?eQwrACi(}`@f(%`tt_S7<&tpP{W87+T5zQ){1 zm?Zfq;w&#N8WxfF(=cR#Eb$o$8d6=~hX4)qBJkDGzuUFPgeaF*B6;zHRS(zgk#rxR z+a3BXeY;9{7jOvuvw1of&oMt);)0@T4%2i=`U z$Hggp_`nXNummvz#kl$QjqHF2qYBZEoGK!9q=I(&&ssEe&}x!9Bl!bsZ$RK2v$4-s zcl{om?d<;ie64rSH~BTdy?eQaHj zLt%0{Q4U!b7VhHng;B%sS?j+k^RksDHuv zh${D0FK!=w)=6bSDxZf5$k%^U4~g8cNO%%SoEE(vC$%@-f%H=4E|ibq9*d~V|?@{&Tg+ot@uzgo5G=il-Vg3SHJqY0w|C;YG?HL~DB(Ar~QN8~+QKjSG&o*y=Bu{F};$U=KvMMxkidT}nlAU^f*+06% z8JhE=;|5h}LSWW>2|syz;NU#7i%8R7zMzh}0u&$#3S(P#e-MjAk50gZ{oHC>FY<`A zvaFjp%SZHBVpwRk0wH3>)nk;Xz-|8oh$t_R=A8r)(_VnKcLQ&&&jqihxij8X_pfz# zo8)>*GxmPooFH7-Xkx0%D0qyX+p|akv0p=j0@~GrXhdNP>g~k79oOzETNe8Fg~s9r z1qFK2t>jT%d^%k$L7vZOE&ee!k$$}W348zFG-3D1P^uz|*ZP+;S9HhDQ_P{X-E*yi zt?CCPs4JcaW)U&x5W5ToYrTGrz8drx0NA1^4sb<29T-0;^hFWcsa;|LH=ZhHP;FTM z&(%(FtVwM}1t#;TjQmQo_cIllp|)pVYWQQII4sd0P+0umjax7?n$jBvS;S0gwX6k{ zs+cguKQa@9Y?^wZ<-U78ROs^;fy20$whtB(FK)vj>rrlqdK=X<=(Mwc`d6Ng7>!=# z+*HEgn5Va0Bo7~;SF{b@;FKSqGLD6NQhitJC>k=%#fn;Et9H7>E8OQM@C@GmnD#<1 z5=%KqxD6`|RXlhDd6{mYpHhnF<~*!J8Y#uyq_%mqb#xVJU}fcId59%~iL`F*u2ELcw+J>R3|5 zulsfG+?I-2EueN%<2&58Gmi!*7X>h4@3kI!woquv@7g%Ot*0nSpbZIo_ty=CMD0~Itre&P1x?;NSr(uM8LTLzZ6O64qH}vu_zNH>u zN1inGLn9+{fKLgUeD{<;@o;~;?`1>Kds{TO{d)1VYHTt7Ope|$57R^QD!FkLA+xq2 zO_4P-_mQ*Z)B*{GXt%fcYXWz5qp4o+Vr{{LGz^v5N32)y<0{WY+mPWVM3=&`kTvw5 z#G-#1$?ou2@|nE$D_aLfw0_H}hUQZ+Ye4rnAYETs++BN#qw}YPeo=$Yo3@V@Vcelm zGD5V~G*g$kjxFV)=^yOYR*}L<7)LF>EGmM7tvvM`-_vE-Lw=`#HnFc!GhiSgj&MoJl zBa=&&o2>i9o6u2y%Ly?$jGiL;+`38Guk*V6T(TrRMCNEx_BT>L_!ow_<#|uTQ(b|U zFV&mMW2rrxrAE7!r zsNYw zruw8T;NigsoCJ(O)(A873o(oOlL!1Xv-=M1ssIei54f{Je0YOVzR-ZAMt5&2(Jm{J z7MM^gNb(D0B9p%*O_*DXUvBfWTRQlc=s3b%@1`4JP_~?W-`KKJG2d=#a#0klm&FoO z+2|s^)HF8pdymei+SD)&xqLslOokHNAKe*Vwn!Vzy&o}pIG|}7Q6pWj2-`Fp(Iuo+wDh`#>GpWo!v75{mE5g2Vo79$wm)dK@Y~h z4B3^nO%d-^vx{@TNtFzd_sYX7%GdiTd)wB}TT@f}#2a4bj~Cv~@%UV}OOMx8eJime3L1FpSjeuQwO1%BpZQ zAl2wu*^B3zo{n2*?4uZ)w|gjGycTLPXlztGO6@7#N|(P=YsTV*M6d!WUQX;6fySY~ zTpAw~h)Yf9l>WXA=Y9WUC-}TIpVbr&W@l?JRaTl-M`o3jX0fXYoAF>P!XO!Vm6Km) z@s^$yb@~u0gTac9S6YKg?ztgE=1Ew_O{T;!>O+Ga;3?!sU9j0u?`^8@D7Dkd_~D3i z_>W@~j}UBu(=Z5r=o8cMP#8 z4s6O{MdGx7GsrL~FknL-WA4j~+_D3jODr;KyA9%p_rTcW(wgr9aqxUT18o7)AIM7y zl`$`R&K1j96RQN3Y61HJLwv~9w#H`)D{Xl~DLy{JOtViEM?f?6^-@7-DDsm(f@tLI zmt$Q_JpgdvNmtWfJr`hoATSmGCy8bM9uuN~AK$i(&oxMhZT$VtjyhQIL2;kV_U|R# z>BT(75fjSffLD|S0hH|fd`Ri|SqnWrOX-rHIKZO{$WlHo9gje787d_(?vMk5hb}i;F1sDJG@NL?xO+rje>|giet;`E%W(FX?RaFP5LFb%=LZLB8 zN<9hG9%Fos34OO97Dea0u&EQ49|;3UU~jZAyK;~xt7>Zq9=PwbuSQZU*Idi=F25?d zwO^D@>HE54FDX;=N_vutnrEMz$wc&N@-)=3aQ|onFj%8*t1CPaZ--L=^l2ozJ?t6!%N@~%SOOsI> z(f{+MxA{)ULZMj%;|@6OK;_QB(X+I+RM2Rp&X9NGC0Kr`rtfQOru53LIz`$`A}<gO=P4-6HO>^C*MuGSY5ytAWGjE32e=Ba!=kGOPC7z8+JAQP9`c%ZYZ_+fuwQ z)Rk=mGD(61y0Qx4yIYR+Jd^-$ZdJ=#s`^#Eo3DVkZ#^tmV{m(Lp561cuh4@xwJ4mU zUv_BKhnx3rB*EEjxvq+RO0sdu7#snHDDMmj7ZRjX060i2*6k9|{$ zuw1R)868NjE<cB z73&F*`%QrQ=zPqk;qW$Ls_@$?&gA{x7ehyyK*GSE&S4_Mf~=#k3B$`kf8dTNZC<{) z*k7>+$l{)0l0SiHth=Uy>zsnPh)khO0Y9xlx0S(`#D_&!+P62(czdU67a}E#pC<7W zZ7^oj?nKqsK+BQ`s^R-o&;ouVE2c+Xa@0$tyJMBdDEov~Iv#Z&^5gt}$l`PD(N&9idlq=qx6x*j4Y(eE8eu8=7^suq=WA@# zf^v?yP-5`RHuEv3&N50s7YHrC#$)3}0AW*m1Rf>i)+#own{ps-G-F5;6;o zJ4l*MbmrNPS_G7LEYOoP0LrSi!Ab7P@t0Y4dU|+&{?TWz1g0uGwc+M1F4wR7HFvub zZDvPHPF8f`&Hg%q+&)w;w8v(H?g-94w-9VkCmX~np0V9Gz0iPwp9go+0b7pxGSHAq zE)&>+NI#EqUI1bjY4K(5cmcNz=QbQrP9-J+Cxp4}+itY+uR|%!BB%Bus%RO^@e3Zf zCLj3WdqsSgm_+N20+75C6|j|Wj3COGsXWFQ_Cgh>MJ)yOt!HM(nJLTAX_#b8J?n*TCf;!67gN0@CL8L8L^4F7*C(Y1uz{X`` z|J2ClZ|t!pkQK9;5Sy3?tI#QVF%&{KFY|95#UDt+CHnIN|DV6}OHZ^0^+c7zJDV2~ zXa&kdnBrePR4It+ecS}(l6?goq&hTP+dG50pA8_2Yl0%T6UNW6yiZ)izwBYNRi&rt zV)J@->r539l+Yc^#+w&>uu^Pz(Wa^`$J-OFpB`;8<*;hL9NHLQVZl!rjPT$zIFMWp z*Qx&|Q0N1_8l6IxGGe%AQJWOAUx&Y{h>}RycQL^%gQ#M0!+zZRVEG)_z}(-ooo6YG zXrn|D_>9x2g{kqYcQ>U$S&({+-d0{QP4GoZpPWY?=p~jjkhAwlkAa#I_X49n0~+L* z0b1h(SlD5jF!^yG);2FG_nj;@Pw^!xbqemh6weAB(!|}T zP=13i{GMvh&8Izt(ey@7*MOb5sNCP34=>1r=z(v`+^rkU=IzT%l#ZjP=dRv38t|@6l??H+8FvuXH_DL-HT(wWi00S2&Ba zqNPDT?!vKZ6Q$qhsdxqiE?Y-`V?%dd=>(rv{5Xj^VkUgc>V7K9W_dm04R`(}ip$Q3 zju#>Jz#|@*Y1vHWSDP2JOBeFYRt}Z+A6?JC<@$X;gG{IcKRS)trpqIfrw z=0XXgsQ)EQ6h~masg zt&6sO7F|m1TZ0d(;ES#>0KSu`b&Xn$kZv9)E}Zvw_WO2?*2)(%|KcjL$BKe~G%HNj zEq=jimQ}#0XFXR3(-9n>7ifIO@Lgo;Lb)Q9%dw z6~0UNeN$Sw31@~35G!?yR@8D?kgj(!bJk3izA0w6Qhuu_`r}yEGnLh|Vu9CtA^~k^ z16M&xdiCE=+RhD3dFrFwTP-%aizo&>GTgg!XKRa$2St^uJhBpTTqVa#Q7q&>@ixJ= z`@et(n;+YU=}Ka1S34^5GmXiAN8@^XitcZFffV7(315m%9%(F1V}eXACM+*Gf>v9q zE^-gCF7Q9*j*GuJ6}7d41rLaq4y4D=eF-YmN_X)e@3K|W`EL5UjIv)?iOP|zc%l($ zuZJHl;n)49fLZ?7hP5YBPJWIUPyQax&4)kD9*?}N!~Ysvx009S{Q^EFFFJ8cl4IA0 zDyTY<6>d6czQ}n?&@CZGKE5}tWnwu+HRHu!C&eL#moYixa9+&!n+%oO%cWcKj3hMf z%aKNPV)1F_Glv6zG{jNGU|1*@#OmTxG} zUv27hYOfbGnh}S8Ds`+10h<=pqT_-8H7uu+;m<1Ops{)2Ia(vj-{imdTWgR^b5^z} zM6tSlIZ1W<;cJj-eYjq4iWNGTcdTe1^Ik=02pkpk-hPIg#uulX08!3oe(M*+sDE~G zL(O_`rt2A2v}VH&PHk->iX>lnSJ>zfw7X|p7$&XBMuCU8PTVmJdPlgC4e#>$sXbaw z@BiEMTQp{m)YUT6JzZaKueO0f#LSHDQ~ztYSfrFBkjVBF3j4xt3GjBE)&m$B=D_#N z%wo({WMVx=3&O;x>BS|novveNpv7fG&o4CI(7RuZ%iaslTQcB@ z;I_-jQQr;Ei*Wbcbn4K5jBa_?ushJj9tbkZps&ik7yIvEG#Gy(q@{_GKkh<(>HmoQ zi&kg|m^bwQfao97U0gNI9Rns)qo1^25-UOy8v(4N(s1=k&d9#}_nz8lMb5X@^o;25 zmt@yE&|O^}ZVG;q#Y7$DwHSXkibeCj!+^5AIUkor0&DLdL-AhLXs2v0XbIk^DoT2=d;1cVBBws5!*&*hK7n%9oHC~3s<0@K0_v1+ zm0}*SlZ8x9^9h9F>lu&5LV&nqnG7Rdk_%^v+8{Q!qV{}r%C<>y^c~kmSU*ZYY`P|8 zJwL0!zdcNBS;9XSp6`X#jcUz%j26b_zed7Em*+rSXA)T#>}$J(6*EpImfp=Uzui)q>FUTYK~Paq@k!rbp8*t+tONO6$&HADz#Elg{vqnOfCUDRW9VKE zl|8SN-1|!B@rRxK1dK%ffpMbdW@<$-lWfHtL*Tgjo-V_7H>Vn@{)MOfD(O{nm;D#+ zzWek1OB}cNwCg-MCfH4_GWY(wEovV(yot-FyRCJ8|In!Yj|I*M%gpLWjRPM)i}T;c zQ}DjFGu=1qwRW{L!|(U+L?>wlk^{-an-}flH;L5@wr+QGX6S=_N|SWQ5L4o!F*uQ! zC#Qu?s;HUrk$;&UqNQ#R(Zj5l|BF4p?!gX2kd#?aSCR8CP>9f};i6zsfykF~3%I|( zt68sy8OxvGf4jy}nt~0uk8v~A3$O+=S9lT_rmNLSq&F=i)X(4lIi53A&8{5#LQ7|6 z%GiqYZDvK~E8DcJ# z-7*|~_Jgq7xdI-Lo(C3!GRz{j0YIWAokRKg#Vyntnu4h1*_$Ufplv*% zddiM$gowbANST}N$r+7>*B8m-{wqGLB2Tc6?Q>KbE0805Y|$c*(=DT@XT5JvLj&2{ z@*-E&uZYX%NaB0QERBt0x^+}bM37?21>8h_8(h@Ke|5(w(B+Jc=K~b3H?-aREsgWC zrvi$$989LV)s8rzHP*MfEt{gOn||q8{Pm$fIh+<n_PsG0b1(vq&0M{rNeVS@Uw>dS zhep3Kc&DHacw|u}d-uO_8mZc5Pf?w;F)!oQ<*mXftibmRe%W0tzUFtAvP#Q}WM(g{ z@H@d5M48KgsB22?af~4PY{q&li%&lP5y-vQ9!0_f0Pr7AEPsEMXG#ciCXTpLzbG9j z78&YA)YkdXdZMU*{%(uDS8c3%vRUP;+qQS}Mh8#rl6;&E+leB|L@(iC=csJxMIzIv zS(Huv^-ilM`|^ggxT|t>rP0X$G=JOPPvq^5nHM_Cb&b~@MSb4-{u0hag|Px9N(nIrS*ka z%zT`Ef+AH56xl(pdvp$n#-x1rsw-r>jT(QFZ9uCHSL_NmCIm!I@v(REndiJvqiMSJ z^2GjpUqodJ;`WYJB;JeX1u9J<;3k_euClp;X+>;e} zh~OqE)69cB1=|A#tp==W;2J;zgz_jL7uMpRJb9%i`+M>{a_YfZ@d6c@C}Nm74{ndhQcf z-%Vd7gNgG)4 zqJBn9NyiyTqGz1>zYxho6pN4fER31~kxg`Q^1t_}Nby-%5_(FVZ2nX0)B5YfvXI@yu|+TzS?D`{+@!7U+kbWo_B%$ii1al ze|}s)THf!pZ2mTBU=3(}(e*cN$I4+))%1Ra#>e5>1f2F$*Ya>gnyj18AV@L5x$Ew{$t!tqt_2uXkr@rqDOy&OY0TONpW7aMZs zI@^jT+`o6or_AsIw1Pfg{HTmimWjb>236yB>|uY3GeQ`(eOZ)o`oX4aO)=$bWW?3^ z;~({kGA_%z4hIj2F-dMmXl31u@~aLjL7U0vWYgqEMUWie}(VM#Hm>v zDm0suPxge$D>;gqxWZ?B$w50txklgf69g1tG-yrppk%r6%l26*_$gmJa}B3ndQ!M} z>N1>4&7oGs8;S|zw-i65L^)3VDgtqZl578v2AdC8FW2T9DH5jcxNHgDcba3$e+f)5 zU^dux*AS}g7Y&G@^=6f`rR_N0x8tTbDynlN6bpdW?o6;LM?#`Wcc7>?Q(PmC18ThI zJz{nvTsvR$9&n7>cj$Jmg1KccJN7+Msd=Vzid`#gJC-)Z|4L}OU*xpL&@)M8puVq zYFFJBxk5@0P<*8Sl363Psen~AmNfzK_wjgqH zcpvV+@;-FiZ*11N{OFh)0OvYhqI9_JZp#k5`ftwQ%qZNwEjhBMiPf=?45_qQ(N@#3 zr2A6kQSa;~;P2LxqkQu|vYA|05BIxMh})SqP));3zwOT{6{oVe&FeAB+nxZ2^v_;S zu)Vzh;|!*N3OSW_(}0J?I1Oxd-v>8wBS#2Xq@$uyC46~C4dLv#z==)M)qiQlo8`_n z)suc#!f6C#3p5&L6h?v(ms?%(Ia$1D*sna#d|PUBXFiHX_;nR;DU$0RXbi4nLm(H^ zI}!VhI|Z|i0&@w_&E1p-7xPeRvp0S#ZA6`P5Z#s6RL?X^j4RcZ482<6@Il0{!B@## zc3;@YB53sz>37nQ_YwwN#i_B=fry;@v$hi%@9k?{Y_1+6N!kggdf=T*3S&#|_51BFEl!d}?0k3u`uua;{-Y{`?sN)awue zree{XA*bBbInt%jsN&u?JzDsJu{Jl8#jke}O=8uy1$HmuLgfTIN z7`j6!qr&GGJfs=%fti9-JUl@d&0~I;FYk}#;{2~bIABM9=g-$j!VMd>ELv-rW-|BY zZdn&G`!P*AJyb~ejxwl|)E+W7aIZ)4lgSj_{edDUjP+q)PUYmAfC1#o=7vu5;YOMx z&LIMK!lvZ-1Sk35cNLqsj{jXSGB|EnPSaO|9w+KUEY)AeyfTldNW>zHUHb(7UG`HY zHIHzqAfk#%MiIuf!)Md4f^17?SsgnG30aM`k*u(GE)}E2JYS%jf>|~(4$S;MI=m)) z*F}L`zO~_cmQuQw)#quzlU)2l?WSk=0Y36!H?at0-zbvB-#iP_N0 zc*2UwN#G3Xd%n8cXk}OCI+a*LmaUaq2b-s7w0zZUAhe;^*zW8iD!Ji|{xb{<%XQzH zX>~shKe#40xcYRFXY>%Dnk#Wb>`HPmXrG%!^!PQN`e8d-=LXz(Bx4%(^tXS;_Bb$0 z6g>ZHk~#bhUNw+C zMUP-Cb`S-u{Si<3vRzHiUSOrCeH9&8Rn+AWJXx<2>KgKtP(e$`4c+0A|H6e?lDU;l zAa%_X1PzC^t&jZ!7LO>f0M`UeXL<92;08TS7+Zm9T#mg|G+Ab6j7#b}tM&)zE;B8E z^#+~5k-Vlacf!$b-fKm^qZl{uW61EP9OD>{*ubmU~bmy*D+MLBdNNF7| zRWc2M$Q2>XKmN83wtvM%^CIOUlw?Wl`y76+l}@6E-ovt1NBBtWqPHfk5+&)Dy<;yK z$;Cib{xE8s380%>3RYQ5$zDkUlE*-nRVt_q(aXRnzh#w*+7Hg((n#T%EJ_S@V*CYh zRfN6aeP%Ej`|F?7D-ntvA!8(zog{`Ap6t4>E{^*K`3)~|OaGCPVi{yH)Jm{b;fD6@ zi+N>>315D)aS+}SAqO=A`7Q)X3}OT~%cI|axLf`|Or7;#RO|P*l`hGlOX-r5?(PN& zX%G-;7`nStx>LGEx*MdsrMri&@8+EId0x*SFhAXU_Fnf|?{!^3ApdUY&UlSC`dIc< zI4G&1LZEkgp$nAGVfvoL^AQnfhM@w;_T+jO?zk&-1>yzLU?Tev26q4!aSoV07PH|2 zoMShVz2FbyCZb5uB~&me{`}a{X|OJXx48wwk+9R@St)c=r(Ymn+2Ddt@UCF6BB!VS zJ6CNnxyu(Brjf2?Vq|fhO&+wzTNLZ8OB#h2hz(g4@#WelyFEgz{9n`5zvNwBEOnlb z%Nwk&$;p1pukgtSbVf`bdDGNnh%$+(x%?$W5BpgNNeviN@Fb3ocy_Je z`R_|8R8@~JsMdbHXaOMpL;!EexQC{`$9yBoDXx_erI)YZ_<<+$KIESp_;8lc%rrr4 zIFxJ>IlnBkIOy*ap?mhkcCWqi&p4c)ouP*xMC8g_CO3enY6 z9-YXEss~Si(P2DG55n&t>L+a%M63U`oh6Y>hP#ZuL75A9lH=rv8B1yWx&?o_Ulm-k zKknl84pvCIBI|;8SpN8Im}sg_Tctq%;_rd1UgDPNfOcd3-VujYsD`f-psI31zgG}W z>^^wVXos%{cW>xtt5Jo^M!%9AQ^w1 zI$}b8!2WX-IctTmaKwiXm_0(V(H|&$(*pz`L?s_<#meHumNPu(A%&Dp@bx2e4wYl% zupKSsw)Zd6`g0^3x#3&{`%zfuF(2@R-5Bq)V^ZrBqI2>x>D!HOf{j<$M8&>}Pkb^7 zZ9{EJwl|A5j&E~c&Wt|}>M|^;64?ECAK4ir41Mp}nXEfVw!5 zCyBPTv$HY6xz+>pZ~aHopc@Q7;tYEM5IQd^kTuPpbnk(EuJRj17wboV7mp*x;JH;> z%emN%rV=#wM3$}f5Ba{Z>Bs^Y$ph=soQYfl79e~j>L3X@^@1a=rHejhO?08iXZux>!`6(1aC7tN6T zi2%ve%j4Uf%m+juHOU0mPf9lIZ9Xr1V&gyBOVpY*rr=KeLgY{w0$$5thrJwqK&c(O zBR%0hAdPeqd|u2?;As2G?#qe$UuZ>pZ!(3~nGp~|P5d%fC30T2tFatK6EtvJpgP)P zB_)nJ8NgoAc=RZd9j<=NnLFRUrH^g2g;vu0O2qAZUs$b@*CLcIsgRT-@t9L3wu{!w z!c&}Fqm>+1M6$vH>@6(ga%AQQ_72FXtdgM*-|k6lRI6&1&b@FlyXl4z5~C($Ls6d> z>5@r_W2oKRlP{iyw|2NN=sC#d#PM$}LRg(Q8PcxorzT)~ec+_AXPnFA6u0l+_Hd;v z)#zYsi+y8|^Tk@6K6cn;!5L)-G}VLi;i;{IE;{!uRUT@~UI3P84kxyfC4MLQxEd0d zizh44I&NGcs}Cza5i%>%bMEe8rFHEGTU9IgMqs<<=r{jk8^Wl1so;?j5vN%M>f8#xdKbRs4ol@X^=e%rB zet&Zq9yh7t@yQDAmEQTJ2hnHblg8-9=31x|04yFz&Ni6bqs*Fy1-VHy*8DQTj3oPBPd=6VDs@l)ZP5(;*U@ z%>{krK)C^nCAXj&Q4nC|Ms6oY4e3oAFy;o;*mfMAD%7`h=K4e!yGAH`k@NMomy7D}Ysr zd1ez#Q!yDigRawFGvDyuHNwh`fMudI+ClsSQES_j7rL7CPsq-XfX{*y`Tn~h##=2M zY^c}j#?c~rqTnmoPbg=fM0ebNFdwec)NaODWr3m-s}3SY#kl z#&w4Yaa`@##k^)!lXh6&^9+Eb?6GJdp{@knEv-WYQ0Z2%Wn76T*YOefU+hsANMnrX z#$+dne*8V)VFji~wk|gufb+?TYa>SN&Uv%Eel;$BM(}B0@zo~V#z)iwfX^BLnNVzI zCSxU#FL_{6k6BX8u8s1A)5|52m2w!mJUj2J^mb;6@|<22?=`mE&9gO%Hr@{3Zo0yf zmHw&;Gs?d;on2h}-|@qLqNSxx=60a^ZedaIXbDJ)Z-Fnel7_DD6r7l`R8k@tqf$g3 z4d>B$J9%!MWbv|IT;?=LU+*5{wQUIO{Vx|V2AY#Kgboio5>)S|85Ps72+K9eX`_DD zLOP4CG-;GN(huzU;ondOrIe~10`Q|qgyJ21@<}6H#BZ=v*|omlp#%wn%sQ3tf#EZL zb!2Wj8XQkZ_Ypb`PhLaon~$G8XpqPQi^&MM%bVO1ufrN@O@7-6vxonP(~=wu$67;s ztErH9$D-*G%j$J9uEcFZ)DGIE7Cu4R;z|%7?S}yVOr_DOD@n-fR zkr`IQ^7H3ypz(knX4#vfbmZDE1bc0H$busWy@EJ5;ZRCLbkWe#BQBU9oc(OM37%Ur zqLg`mKG`27u5?czTC1sQdPGhEL+4q*by2h%+A(nD(hB46kWdkwRnexta^>U~>I{bz zC!?<)#(%%34u;Z=c4Op}=XB_1;vu9}aw7gP1`9Nr)l{5Z^%l~iMwPBRe^`v}UZ{S{ zrDG{JrhPu2`^0R0gy*^U0k9mQ_0T$RCurmX+hPNwqkZwTs`)*RfRXgX0{C7%hhT4A zlhX{bxF%3$Tn)~)t2ylvhD1yXdGn(v42R&vA<0yaQD^INZ!xLZ4>Kh$d3o+Mt7HyV za_@RYY~#vbKHl$l*_;Eppw?v)Jl9$eWjT+#hW?46%3zpb6(#~(oSK;hLZ^&)|_(uk84f?d=o39(X`DebVmhf-^^ zsQ#^m7l|xcMPaG=RqjcEo2MJ@$mAKpB%vRa|1vV3^`M)i;+jb-n?KNF0yf9a$6F8H zz>q!HOdPD?6G-|^q#UZt{Fii>-0L>e`ztD3FISj-GXUqK4V`&7!lM92BuG@WvN;gX zx?F?a8ikjd!Itv-MjDLY>A7qeM?}#zq8Lr{Ns;^=B5C85yB}Ap(eQ`48<`S`cWi=< z22Fp_>aX~p{Zw*eEEvOoXg{B)VRgN_nA)`U5Jr4dFiUO2`SSyb&a4(g{tn*$r;A(T z@}uEc^GNN8fGjJehmcsE(3wtQrBCr1JUy&pev@<9KE2s^_59rA!wC4I?w@oPIuHn>7XQ{p)7jDd`^)xJhL87 ziGkh(9cg!N_^JQ0o5TsU>7sXawFePUA9JYH-7OPXsF02EqZzCAS{s~Co^8I=#22d8 z(Fw&;XhuilyG7>#bUg}-#j1s2!`Jbu3Y~zbwUP;ul7E}TV6nR0|Vyn%8AR7 z{{|A#Zv?r>Fw@6q-0rnEgKe`mYm{9-M0;RY#y9L#OcGj#j*0 zT&@2%-t$&n$iei0fGHzrI~k@Ki>JZ9o}e=%@`Mmm6G2?8X)3j^BPV9|Q1b|^%VO)Z zl$R{Bt265sFfNaiJtX?~oR!bF_2Qre!+t<|RU|1BnWtN14~c#l!&mOaM=S0NX_y`g zwZV+6CGKWdUiPe2yw~JrTgubUExeZJN3Lb647HjH5^`cg{L*zLhOb)Y#zUXkRVGVs zMy!-NK)xfgpv@N3G8Su5Br)(-T{-SnCxGa32U&8P$%$+exnU3>X2qfx$Jx87$IzR(0IRma6z}jHuhde zW-!A_fy*G|%f4{YE}7~UYbB3q7*JkWlBD2wiCl-|C)@VFnk0M zQ3hNm2viE`G%rzA939YlyL3?!kn?-3AUyv>7$OpxV){LpD=#6zbmK7HL3_-FMydc0>*sFPH>{@Ia zFE_#Ev2jbIo>g$tb)upo$eixxiIF;HmvL(fTYWu>EYfzx2IoITWVx)J9#$2ZkRu>P`H zeW=7e_%8RtbR8|5Sty7YC}OAA8i0w!#^AYyD;}Fj?2PO87{e-EF=f)Qs@EV8)2M<& zKU%?`JzkH9>Yg-V*f+Tt6-+3ZpfPCLN4L3UYzvcNaO{aq1D5~zsUVlZxBT=AvY+VN z5dKphB2zC^I)nYEswDk10iR6X;NoT!!!yxkW6;(fmoXGW?HeeGws3eCUqs|OgAR%+x$Pw**kKl->&v)0k^uuGaf0EP^aou z4JJuaU! zy)SQ63r;xWEfVtR3sk?ephVBd#5z{1c&KIMet`&w`wX)E0`=RApDE9hEt^0dEIw7Nj)!hCXM<;?dk6&*N*B;)6k#5n3OyG-aXz3EG4Jiug-rpKt{We7Z)Juhda+My;!6HH&*xFa+7^TNK)bK`& z4qq(hhn@|Q@sfa$VN-~{!dLnmE&m_DaP2}nD)23wUcabLwQ4mkF_zv!Au|HQT!GIH zgs<--w9`7D5>38T;prV^zHqw+MctezANC$(c!`dYyLZkl(DAnOCU=oz4RXGz<7$;f zM%`<0t;Hb2Vn|W#{+nVEaW|rsfZV8edyjdG+z~%LDmb;qT;zkg8_9vEz57X98oNbM zr$7AWgu8Wba+{Tsva&DW<6euK_W-Ds##;liWL=&>czGjUyLlG-9>_R&`2t*bZxfNB$sa7P zC-hQ$p6P9fi#LMv>KfBV3!*lEhtD-WZ06O=pRyy7)g>r_>>HxzD{N^*lnvtSP8MzI zKSg!=9F94WvZLzne;*8kl?XA)syFZpijHC4#4*0JbZx_6+gl_rQFzfHCySXn{$@wP zoe>0gEW68m=41W)g3m5sun_^qpV7X4uaRXPR|RRvfy~hAt&ZmrOJcQ*7`?b*EyYrN z_T&oo8>)~Rv=pN%(OUJ5NB>P~xO2@7_e1Oi0nU@FNpx)Sjc=+bNdxk%PlqiPELnTK zn??&vup&URfnf%|m+l&O3$M$=q(E5gYvQ1F8dGH+4IOQvUX|d7ADXl>p=ZBK!CE@5 zL};>Vc}qevrk7Xe%!cfEps)2z6a8|W`rZ2_P{SFGl{BrS(dTq}l_`f};O*q;sI0$` z)a-iFttZ)aPVwkKYc8ZSe2W~Hk5lKn4mKC}1((qd*ap^$#1n)sTurc1M=Pk?+uQ%B z=VvtZ*MS|Y-q$dC>{W*IYHT+Ab!y%%P$_tMm&q7%(-_$Bc>|l_4*x2+0m_W00b%AiRjHdXbRYg^nm(m*#BqOybBHmz_xx(4f9`Swp`frit*+M7azSUTo-P2P zS+!H3QR^r7Vb(yH*!)b`_Q@n4#N9xmtEN|+TlZPw$goJ%Bs7F_Xt+SC9^1X4+Kd1e zJIst2(xSA5q}ChPh)P$3oxbC?whZ4(7{)}>dPJ1C#`;GnQ{zqju|Iz=*A4q;Tg_+b z8y(}n0{gaKc^HWuJ2AgDTF-vjwS)7i@u>gw)B|g&x8lWbC3r6W7e9kT~&C zcMi#3eJDK+7w5w^bSku!s{SREHD@C){b`K5w`vs&S}*vys%6fwk`w8-eI|iW^qAcP z7F{Bvdj|b;R)~dX_N=#s7*Ny$K$-P(IZXcXK_)&WRklBW(XkgG>hHvmB=R*BjUFd`cG&K2 zjBkR)qGyW}lkxQ-{re>ILer-lpT~te(N_s}AeCAo3Sv@hA*3g9g=WW|0n~blp0e4{ z#D%}*cY$D$yL2sgQf;>;`B&C zAV%knj&+@bn~?k^R`z;^HAp@37pT&&+F<}AC3^H%5RoxoB?#P|inl(Kr%39KNTz8e?ZrMFh2q*bOc7d|s`x0+KB#d9He%zk zN@2AnJZI@mnvY1mUDRex(F6udP^t<8ci$JZWOO~p-)*ZUrLLMDX{)Q!=4McX-6mQk z;5DR*X#3y6WZi`NfW&B#Sk8Z}Bl*e%(LMqNE~~V(uZa!E^%vuXukUHvK!u0rdr#w^ zCG3KYa*05|)2J-PsNY11x!2{e-)U6$Iw-*LGHADGqn&&gF!-P}1 z>)#H=Q4lOBTBQWseI`$9USew*+spd2JA@6X zADhc;x>?OCTy~*-DL8vNcb%+Xd*^INdC+DaDjc)U{m0JJRgO#qJG+Px_MQFg)?I}Q zsl*jXwB_8f;Ho__(ox+MJhn^f?z#4#zxJZ-&eku(S8@uBdDBDE6%I(kf}gKg7k`<* zngBg+*MnVNo^D=O%*B`Ow_0yjy8#NAZ(JPaG%WfAaHY5L|L16}u12(et?9GZ4%-6& zu-1pYj=YH+RJ~S({|>nV*giEJPW*U6{-o8c^$BD1HLLzp;T^!rQZbd5R1@VgAO0&Q zCR+VCDH?)cf#cg*uOEW-^9dO-m@`+b5+fcL`ttMzW~w67&kw9oga9K;68;H&r42jE zb)C%F@O8$pTCw#Rjl#!Qp(YnRC8;pP^Q5Ebs$Bq|)=eS%R4W=A43&$EB6UWoJ9)P= zqaR5&zLO#mf&A{rq;9O!-q%Ii^t+r>VQlw--aQBO6`b!QyAoeZFN&74p{<84RsE!$ z6TOp#8U;)fr&azGGx$!q`(YFl_(6@%y1KbR9>@3lFjXtRs>4|*fv5F1g7V!ZZQsgQfP)QEXSJR%__z!YIe1`|w~>rIRR9 z)TTa9Sar$FU+F9U)mw~j>#_a-uD1~hB9M2OwVhr{KCRlqGrF(Tj;O&8TQVAl-v3R6-f820X$SKRHQ}8-n>Blsa2k*VGFMV zOoEOT%KtTF-=SCo&j+cKLqEIKA_$9GK}<|6fYvcjs&iEx6nVgF^f*C!e@J%~>~=kO zz=$mSuklMN$~-R-1X)JoMd?uLU5)CaIH+iNxtIjopfjm} z5ck2&==9zcdsH!@oU^!E{F37jB-`a6gQ2TuRUgJ~d3>rdCUK7F%&(Z}LN^5Be5=DM zG3UyvjH7~|(@lDWxOd)=8F=nBE%8Bzov`tY(d4`7a-zg(K2Q=Rs@8n1eI<;wJl=Fa zduZ17SbSN z%1WI9>LSjBx|S$^L(FY-+&cfBSGW8w6WWo}DfOip36#mC-o)S}CJyghE{}pv82yXh z&$XsjE|9dpLyOcTkZh@=hfp|$Az=wYE8XPaLIcBIeEI7*nTsVtmbM8X^AnVUPga`4 z@il&=jZyjPwg11D zF-{ePiJo3|XdpRA3h)d?d>ZYjGVI=}rW^TW1Whc&0Q)ZJS?GkhoRvd40961LX>Nk_ zWa-)_607Z=8g9)Fqbu)elGU4v?ZEQx8^_P6CeSORprr5P{*)pOmD^8-z^R{wT&_*; zqC0(LquIweG4(I#+Ts16qPy*t!+0@1Mvia#qvlQ$aZOmQ10D9;wSA5uPkUz?ISOhk z@r#`+DFtas`)dFE7=^w%(3|~3oF(z=!V709#F7v@(B8o&Pmvf~#Dp>JFm_?$)E&a< zrFuzpz1Ui12~PkdqotH0Wz&$rY!rv@Bq-q#4jE@F!K&|YF?=BTLm-S*S5-GFEg2a18t2t}hZHsOS zAw=1qoyosk==9vg-XVl#IwO9_arp7{*X10}Uu5Cu>2`B>o4?)$r6?)QYM{7}c_o<+ zT&cRD8^eRhoO)^-7!*@G+r7^{%7sfiy?^<~6@DcZB!0+y3E?2hByT#@q{^tQ6ij?G zHxt?*2oI35r#ZaCo$5QvblvMNV#JYwm89m-rR8NqT73ky$;|HPY| zJ!J|@m3xwP-*KwHJ9;Z-{I535sQSoTDJBgVwoOh>I$c{IOyt2cHXpJ6ve@-<8PhRt zyM*SDrT34mmA-f522Zh1TSNr}5o#y^spnKS@ike+&Mod2iTY3dhhs1ALR=%Wn;K9A z`Oio_xS#31K38>FezIt_Lsl*_(*M23A;ss;x)J=)=tJ8`_tg%*Rl7SViUp5H3eYVv39NUg>O0fPiITwO3mUleg^@Ii=e?0h+IlY9$k zB}-29rax}tcs{)I`P)VM^G1`$h&XO~IDjnd=Bj}-+G`p$c;>8*356h+3V?j@ymIE8 za~G2*7a7ST(#F=Vwt{nc%W}nt>@juzI;`3~5z9g>vLi;fK2Kj zCaxpr9pBuJ9x)ZYa4?V4tb=x?VorRC`c}B+7MM@R8|`G$cuW}oQ%3MRNNS#JZ09>v zar&l#$3a=v4Kqt>TJHj0d7ZB$4*UMwBS+!=DjJPAe!4fHLl;z5he&fYdk>|9l zRnv-C7;{kFBrnYrHNSZ%q{y~_WO{rM{_bjEqqjRk!QfKw{^oe7IH!JL4$%1|0d|Dd zy=?+Qwt_LXPi#pW$5Rq&dgA?55c1xy>n|p^N-rB@x+y6~JP7Cn+2O8y*jNOL68c;M zXbu9AWrzFl!wYtsmM4S=6BZqg8^1CB#ulj5By@f{umO&?tIVR>&6 zJ5Q5NeA^OBW6t^L$WAi(T=58zs<_Wcel4R8^&u|Qq1BxXFD z^rIbRb!6Z$E&@52Jera*tYO6hx%lm_&TRGm%f3~xhu{VO4&`6UF>JH6FE@2|Wqnr= zM)6siruAFB!j6SsfdW8W!>mkP%7c_(o&3iL*=uIBWU0I1e~RogqcFZ}s+YmpJA zl6C|*1xya4|N9Iy0j;YrQ2^VBgys2goq#qBE;;)8KsNO)({t1>)RIB_>%KnNowgT+ zP7G*fT@t{(g`uIhWY31DdfvrENz?Qhm=7Xc;S7pD#n~7xZSO3>UQy0y>qVdfUj|CP zFEQqex;yQ@@U$8DQYAB_;Vcqs-mempHkc%L=-)*pt4@y;Q?{75lx5xJsc+R^2J8>g z<25-Qhp`yRllwv&$N(qd^4{b(xbt&D$G%I^ek8Txp4Fv}ispCDH(``j3}z^aJNy0x z@ooY{{4Xj^Xd5bd9C2qc^leAg#(GtrEBbEh5@_`Jw=J~xT z;&(9NP3W8Hy{Aw7zW{&Co8SjTdxq_N-uPUCO4{p*VNK{lM@45?G@5vo7G&hP)3?!E z%PZskJy(e!Gv7Irc1Udb6E{sO)~@vaXqp7fBxXQB&8O~( zn1zf<6koW0$$F;B;{OBHR1|L)yiIvXiVd2Q^1N}3G8Tb$c~0^Al4#==!wwgw-O@L& z7`>T&I4V1k&=Df%@Nv?0!0X$U8$rnpj4zlA_C*8v zXnpx31fPiG9ua%O#k0Z4d+5Rz9Tx8$JTGY7A4S{%d^INkv);bVpvo-ZI)D=wzk>Rr zk|bPyDMxqNkx;f zFW|HAOo}a3y$-hFyZHAtEp^Nz9@%Ku>ud16=p4TaOG7J*(R4LH>RqYtTTZ!9nyy5M zUhZ1=#(6_F&6#M%N;@7EyIGEpf|aT`26exSH5w}F9148rYuoxfnv@@VP%VqbB8cHI zn?#!TfNitc_QD8GdUK=W&=z6~SWwUyTh2tBi_ze3_|MQ!va}*jUWPh7$66z|wyaJZ z-d*Kke$box1;h<2RP>>>@htXA|zD64B+5&!3_9>?E z$<^G(9#SHunmDi!XAfnqR3yr|$yug8?0mLLpL2SGxO`e?-kx6bEYRPrf??aH{xtgg zseoEn2~yW@Y}WYA-@FKXp}f4|R{nUutQ?c?z*ttCA~;I962Kr^v1V2Q2nX9mHNJ=; z7a8~>3(N~LYUr1aZ2aL`Wgsow5+xpH z%{x4O^~g#iGL-&s80=*-A2273|0DIPPQ)&upo;~Z=GLyi1l-T3B*FdV#$R$Bb?D3V zTEDY?gHjep<(yw>_05U2ofWJ(+CX1wwK5-WQU>CN^w2@CA2N z6h79UD#cVr1z}TDk?eGfe+M@xesej|bYc+3G?a+{K9C~uy);|KJ{u1d*E$%_Swo!? z+>r~Z%iSBwlV$o{D_wDg`%DvIqPlFP*u`P{#SvpSgBo;9bB3J{#9TW{}alBGS z&I(l|V+JPE4jJb4l9rB!rN#Xlg1K!kdya1DGc=y{#{?3z26J! z_|=^7DKDN|`Z1Y>-Qj+>ZD)#i+-d?!vMX@;o+#7$^lHLZ>1%R1H(GYwJ=Xm7Eq32o z`aH4q$i<7C5QD_HT9Y8~^~{NL?voaP#T+}+EG&$flP)zHb;*3slRNr0kg41L%f>fx&Kk*1>VO&z2+8AB)&g zhG#iLS_aIa_FzK8==v_UrvxJzLqbgdbS0YW9#P_SJ*;c=1*iUx!`qtNidS8v$sjqq z9~*T>Shln$Gz`ZXB3Yn}86cKtSwsUJ;Jf~Dv>BN(Vg4TT0oRa2xVjU1)e3p|pSYm2q!--p z`%7d}diEocues3e;?wpQlFHU=f*@4luyCd}ybK;EF>5_voy*JJG0sZ~mW18pbsFH_ zj|(t(|9iCq0(v=N;kU0uC$-O?frAzXHg~*Vo=SApwi+m$a9tLCiS6}aIoL=7MdNy3EyG`#_lA^@Tlq5X+ z8}`JKT$M-gTIubzp1v;kjgV-^gEO_ow>y`C|CIuS`p2b%^OYeRD3tTQ@YN zK2mtH1lHxLZq9c7_U#^l%_wd?%*MILd<_(9KW7Pb z;j+$!hBQmA2_wmx1Kqd2)KwP@VKEvq>sl)V8!jvnjQl@|bF{Kfw7(p=ClMS3AdX|K zpPQ~|B)E@0>;(wHA}haV7&Ju_Z@MG9VqXzz=VpG(u93w%iV;0==-DmcfNuf$UZ*5C znm`itu7w+N5902L71Tp!5WE(~&CnaYWTHH}vV}Ni-?mlIv5z?@_~$oGelAXI zBhMiTISy#^blV)Fuj~Pg;q=>=uM69H_CS-bJLQLjOe3B9Aj_WNGbd@Ph3_1}ir@d9 zhvBypU(7dU)v^2%-u(xg95HC5ODn>nD$#SC`5Y3xwsN%@zboUKKAE*G&VVQ(g*Ux} zFTq!;KZJw86N;qrJ~aMnSwcXQ@sOFw57pf|tDx3=*tdc_pGX0i*6U(S)S(5fI+IZ8 zEP(8Ep*dsLw8MVq8{9YE7%sew^i`=o_9RKfWnlORW^v=WcbSs~-6h-2+2Qe9#yr!4 z!YF;+^iG>!I(P-g*A@D+fo#+cDWI)as*x+6%`s{Ny$1>L*q#ou?FYHVG~h8$+}P5UVm zg(AI1E@AlUK?~ENnZyL3?}P>3H|3S8i?gk1F%l6HhHKljVpC_jkiA~>?{>3{?|+%^ zMV2?%7GYGh&qbel-)7Ma%o;09KU4wbKHjUH@!yubrk9E4bpnvieA;-8&J32UuQz*l zBzY-=K7Mih5%eN#=xS~iiSdD8Q!~f5GwxH9#{q8!LLdo`HN-7ysd?1S-3;F>9@8v| zPA2KRI>lpHoih1s>zwOiu${c-m}yFb&cqShv>i9JN6-~=h$J$(EZ6gq(;NcOM|=N7 z>virGeUumn8a+3P!y+3Emv*O5Xh&2%%3^thA#2S6+qsO5pVUmaL~L4d6!<693}nnB zGYh%+(H=L=0P9@eX#vqyX7ecye1_msSh(G3+SJ5xlVWUoro|+C^WkP5^rWm@f{OH$ zj-^JniR4o){d7Q(bV;#M3YmE8iLrl@fyCp}X?ZZBZA@*GhMn+J6FnUe^2>jU7YO%LY z`JJv6mrgn)`o(zt7$JfYogs)VqmYFWE?n{9kIt%UNsp4ecKLZ3ZT)%9cOOxFJU!CZ zjVKQu8wp4iV?|9gC9MWO*gz3`gLtpnJH6f1|tc(C(6Zlf`lmqo}N;>(^&|7bC-WvlVj=Hr0gi<$a7PewDh#PR`!iBBnU)N1`+GCbsqROils(^Y zy1YE2%e9_JdU!$Bn4ijcDgJgO@qHl`ug4I_N1|uoEkzS7GOGxDb@WY~L-P&8(XvT> za)(W5`ooq{NF!EHtm|xbpMAK$$>Mt5K5<$yg)vD{75>eps9ag<9*o+hedJkLqO6=T zUTK~lVwBe`-f6yqTqDtF5Kl+3?#z`HGFZ~CDxDl5cYKN$*pvZom)PJxQ2 zhbD@{25npayra!pAtZ!J!79+sm_5EvmgX#<0oDlXsxF2BmAzkfz&IHy!w}TEw-f&D zEdVuk1KgGPaYgz~h7C(<|C;Vu4fdr#~6{*RipjMCaa z$2w6{G%(<}qs8}aX<7gnx?&b}upgJZ*eouumeY_olS>A3Xu@usbc^1&VM?1wy1hYF z2vhakc2zfOwDU=0YL2Lq<~ z49$c@G{35%G~Gd^Ge5zCxn`R|4mL%M%MWPJR$Zyqf+2!TGKuyZ^=d%|pUS79+C~w8;4rnsVl+$NYB7 zvQC5ovx2C1Tz%o+5qt}~mtDe0Da<#topQRSV%aBo&WL7mv>!*<4c{=_p%nft8Vi=B zEfC!JNjJ~f34`kWQ*=lcl&2kzm@S_t9ssNAd>EY&CBrkInX08qDP1MJeyC+CV;7y9 zKuCaz9yTSHQ%(#2nf`dL4BidY2jEhgb^6bIZ;C4yhC2WB|A@CwpKyJ~wCKNRzT9$V2SY<#%Wu zYOslQrb&Q%V(G=LKd^K+EH4EUC>r#88p{}n?TKOspe{f7ptX*KniUHGdOhQ6nB;i$iIKgw9$K?p8vR=i@yIX(b z|0iG$-`4or=?6>0z#s-N$D;Tyr0)J|llI!PHf?sLrJx;@BJs-%HPn>RwCG z@WkQC{gnjoI^kU%WZ>PLmSRj%35BlN2w5p$Jag{zfO)St{^(^LGs2$S9iBJyZX75- zbRl2x|H|`{A3K+@ED45q8*h3gp8wtpSWMFM#Uc(G7bHduLWxOjK9xv1_-?m95vq~3 zwT#qqH$t|2^OyVtvsL%WaQaaRzR(~Iu(4@&qa%eWU8MUhvQFuc_wM&~N(ondfE-f% z@!yS(yi2K(jSbz9dq3YFvq20igv1H5Jt!ZZR2-))uBY#WS=M77vd^jE9FC4-TY4jB z?3laQVV+Ze9Lxn@%PCZMgn+#;1mTZ=w(it5FDVfl6ON7eynl%UxXBx}BYgTVg@aRZ zK}|G6)!_QM>K#u)IlMe|NsMqq5Cf+fGqS9$dsMe|4jwQ>w>1d^`!2gOXhoan-IU%a z8YVapSfbKh-D=j9^;@_-&7^E!ajoA~G(?j@o7A01hGTrZd8TthVzW=DudA_zYE^J`Tk@YfI14@^y}@g2sENP>O)DwHdLr&-cF}v&TNIKR2Gzv z=Z#2e_VwLv&TLsMb4U*&7W3wC^s)v)6IHVP`c^y&VwS-qy}qhLFLnjZZnB;qD9{K? zezIb0aOV)Zzs(3dQFny0jdkd^zGr1>#cWN7WSL_qteadCU|zJ8BZhuxFqG^p+F48& zxX7d7g#%BlD(jz}9QLK8UGrW>m<5jkyTE0j%Fk^hMYSZlnM->TOi7zq!4wt&g7yE) zoE;F=R^-Cfx$G)7R?G!0eVA#x2pKm<)xnVyRwA+lSQOzEnU|JmkQSCQ5fwdJADc8L z2U?T8d{W-P|^bbg}PBzOr^rsEKg z!0){I`f-x<*_%?Pb~v_$45n1?RwtmTn0h&w=^6G0s0kNCY33a^{i~lRcyvo3gmXNKMgq$18=}L%8@j*X1lT?CG0+hhKp{ z(qzxHz6hjO+^SohT=O1Ly{!Eh9WB)F&d6u zYr6&LQ^c9UvB5Z8?K@&e|A>;eZf-ja?<8kPG97>d@;+LJi$Y}8LECj+;1(?%PY`fz6>wr4AZCK%&Kt9=%4R(Y#HahnOpGHTt9#U*24F4qA~=BLQ=*Q<$2(geOY$BYm9N; zwYN5N;o-x|1tPY<%FfVt!9NceFEc}O5I%(9ndoCG*?E%o*{5d z3s=7Bghv1@EEz^bhVAvp(I|hb)Z0ToZ z9m_oy1@D_fG|3Oa3bog69x3;3`+REcrej_{?j5XSLn@nFNYO%4IvOr;@6TGQb$+a+ ztPVC7osJu|v%!fn)8v;BDHL`uQ}Y>&b-kPVGnRpdCSc0L_+vLkWyI-;a($WH6vncdz}Nm75@y{64aX59qOC%@de zyzJ!PlgD>IajQx7>XnZ)wI4r;chvy>gF# zf_4?~=K@ha28w(GTckVfWZ7-5RSLO;_+uabIGZrjA8Oaf)%Rd|4S9VgtY2TPoQh$6 zQGJRQx9-0DUVT&;pP0B2L}=ZS6HF2Y0IBu9$UUlS3Xd9bcSzBj>lFF_Hxt6;C^BvQ zuB%IoiG|fm++Q=pPs4n8ojlF}CV6;3Q1+S?^KKUw6_E>MQmQg65Zg zdu2?wyIxGU_mshM$X1v_zlw?jh6aU?H%x8suf+Gvfl9)_F|^3@%8FLi@&19bR)qqH zX-zIQpH0%Un9ieXrKiUR=O^iRuH;Fk^%oa6?B#|-&bg@&s#bnP?DGUuI6uVS41op7OLrkF;v_tidr`*o62Zb$MPza|^h)2W1eYZikyM|h zW9eh&4**8t4!+x{6W#=?MEfpOLJpltkFYf-1&YFra%REK^T3@6jSR9U$>r}96+NEo zM;&*7%~4rD>o{@DU0+hNj1U1@ggnTs>UZw^;zLsi%=B)$O|ChD4ODruiS2$4;P20~ zYQE+&7DHRMyEojM`2ef{lXyauQAh=dj3r6Snf$4e>&OttTAvUTnRG!OdVuOWV0)7L zer;*ZPf_p*q{x2-dX=kMR5ZfP={jeGfZJiOb&abZg{x^x|9LY!dYv&HwG6KPGRGq7 z$B>jhUG@F(9$OYPr6KC(K7qZx&L++Ggm+W;gm(RVX(8=o2bX1YL9NAG1NNstvTva3 zg)?&Op8dr)xy&m})W&<105(K2ibs+79eTUVgr6tR>k9XMu2y+!9VRW}~g z-FW&|-I@9#@X4d)1smPhtJHpU8OXV-avb=JeCZ>gNioH?|NDN)DdC0vPPxE6xJ_1riquVNtCHwSYgtY+A zq9&ZI@T7M-%E&yAV!A`z#SnOstMxQUMoDXSaMeNC$}edclM2Ob-#G79^1NaS!_AOC z`29MO$-ZmBVa&}kxCIu|?rFVo)16;OANu^Buj(v8tkgK@_N4h^=+K0{pn)E-D|o+r|9JnLRsJrly9;pLYlQMf z`Sk+-=P1-z;P+Czt_$%ACN8^Er}_2iz4qCivzQi;)3@F`BWb}OwUcWe4_|A1fOiqZ z^H0yH=H*9LR{Iq3T)s3`I(Sk#BrME6s~kRU{t#{VsB&8ge1F!kN4(V%P{x&bWczR%oYZMFtD!CJ047+y^OePqNR$yT=2< z%mcQJ%YCn)Z^NwVDl?mPL)y{H@tVBXFt@`QFJtC*sG(IB;Y%iVpmtCG1{4v&^E z-Hz6T`>oDzPX2gBDYJ1K*cG6p7zZGHu(LDo9)%HUHjStF&jqNgjxk(S17C;w=A8-& zOJ9Z@!e`I~I;t)!){&=Jeu*3#`e z?Hsch*(6*MCX@7vmg8F6jEi0TP`uk*YkZPptmeK0sU>PN{(h#f=gEX};5cMcei6;@ zEADV#X`(>Fk#OatB)cMs;g6kf7)1?-vf4DKj|6<-JK9tw*|6qIY0Uu7e-Yfa&%O62 z3RnZ&a_YO&%hKoz12Xk39y$O}g;RS{Aonr3X z@f`;T@7E{S5e|MP+(Ftz#zR&J761Yd_O?D*L1g`?Cg(4=xFy)ci?Y_zE8XCk3p&?p z?cwCgT9k@iN*4*=)8*~(itvBUj<+N^NSD5RSr5yU7P{|O@E#NI^UUjtfZLkz42oRG zF-b9K=+q+Qm@JC3l4yBLH|vp0>ESa-l%RHe$bHcD8j4Ipg&17Ap`!cH^vZ%~v};u3 z1mfcRD$(DPJ~a^;NsdU4{s)Cz>2qQtA3?Vajz4o4Q7xtw6)3~61=`X0Q+4S(^h2yy zQ^!qE;9hsb7lakwOmRfO|JLu6c5wtIy}eY<;&vJ{GN&}DBpn8ZTwFij;3Q` zVXyX9laiyWr?)Eu@SWTs_gM(n$&~o%WjKwhcKm5izh0!m`B6TQn+ z-`3*F$WL+tw7-qJVCW8ud|y^$v~vCCMQ5R6#rPVzdk5W&&jPEyFIu6FA~Z&5VoWpEvL zX-4w$nBsY_Es}AVpPEvW#a;8*2jA}G3(zLB@GDjqm)04)P^`=(#i5TvjTO;JjIUiP zS-Swk*W?Vgka2L20=i$98+?bPwH+XENL|l9g~xVXpkMyw(`df(Yo{FjnuWJSa#;(r znn^=EzfJK}*INQvT<3(M$r@Fl2YVwuK^IiTp+DS*k@nvyd&Bg^1JaD>v8UKj*&SD$ zp)SQ*;$^8BabHmf%XA_e<&!4Ulf3x}XT=dhYomtcw(C;^{wi0rhITZ>(lVnNGwPEMo9M7C z8gC~!xd|#+Do}8GFv>5G(UUWDw9b#^QnfDn=`)_MZIYn+B6HbSN{}6X*eqrmJPuSq zjkI03J@i@GwY=~Cb;`N5w#TU722d7T$r%{Fjj0kF#xU9O?p-g} z4c|`i-)3^3d;?Ps>Pc~{`Na~TB)0QgjWp#86Auq_cgrP>g@C=e834l?OJVmG!C;X0ud zpW!gZ7#$;Y4S)>AHFMO6KKh${JWg|e%8+6=3VeQbF5VHyS<`hx<-QXXz>0JzC^H+Y zZ<085i33=@zYqKca+nwJ2HMBA#*;mM*Fr=^JAqkg4RgoR&@-MNq}OLum(l9)PCQ53X)oifHL{w1YeC4mzFd3P;4(N3@2?69p=a zkx8Y3-Jt_4{gWoF_5wbaBi8n4GytIDp%}aC@@jWI=jIocO<+;G)1-da2{K^}(}aY1 zp+t+N3f^DOQVYiO<4tz1WZI+l<*TO=8yJ(^lZ1?6L}B&&(|anZrIr#Rs5Gyf16RDr zu~IqLczuS6rSCy2@*bry@T18rZA38kD6xTDLZ3#hJU%|=W8w9y1e2xb=1(7mDV<+>o>HiEnUYh*Z0p4)6bb( zuX0nk*h_Q1WM}Ujl<1Lm+MokJN;`R#U5cGzC4CcR5-O9rshQx~Q8AW%$n}ZGkr5(SQgIH?X zT;n_MZ<@z_g3jtQQnOuU9A%8YdNt!VAQQ76N^=s{+FqNm*e?n6%90uaKSJFkm4Id~ zm(Q27k3Plv&wWl3`ba~zVXf`xt|{I5La|QLAEb@UMb;xJG)R-JI-oX0;dsq)VCm$F5fGe z__pc5>xT4fF82L!Ug~2L-|Ahr|KB+*6ShL|bRJ6g(A!H5H883&wSyY`s>MrkjbH69 zxrz%gymJS+-{8=!aGd;=viwMoXU|QLM&#t%qB8k8x_)0H1J83V;PliMda9WePOg#U zSTSOBwOkaBg1!?h{j4<3WpAB(ZwF!4`P+Lw@kVH@R_mduwM)F%?bsnnK3DLMUVgfA z0{S=8!Uqx&@X>$Vq-6nDoG-dJ&iKXg7f zF7iqPbI-^xw3YU8mBMBDuYeRn_Fc-}PXn#jD^&3qJoZrt>-?y=1TXDlAAhA}u<+W! zwmaFz^^blR-7z-x$D(-BJc`0RFT{>-&E*9SmC;{oMECB$m5t;ciGGz(UfzhyMpHlt zF@0O@SWzv%dQL?41*r}_n!xz{&#a-G!9~9{CBB?!0_~a4H76yuJIUcvl_>P9IKMv5%mlcx+ z+Y*VXONkFLVs00Hp!5NyR7%-ZKMbZd>^y{T?d;DMoe$7GX-^?Spx}%juX>)2dL}q- z{C9V;usGQ`D_vJw>n`W4-n`yl$DIyFPQ?E2U;6Ju42kg>_k`dncv||hqP*M|VTN;e zw*_K84jOX{REj4zLJ+&2IH-jh#vy6RD^il)ZW$x3j`ABJZ3pS`so`AWJDt)J2GtLn zd)rOkK^hkDtQ1@5GV54B%#wL-ihFC(FR8-Dt!Tv`iry(tNUspsq{}Ft1Ky5rs5RXC zb{a&RQtI7^125tGb@bxz2wFsi0FtJEU(}JR^uhZhPb0O)kHM|SH=n$L{dYnmEH~9R zQPe!ak}Gat2Znfoa-Z{t?)A;>Y|qNv@DEGQ$FKR(Q#m zD_4(ymtr}S8e)^+5=Um^+0)XOD~pT>JE6Y*wGtuC0_|DD#zVLIvc#fJ@La9BmW zO1NmION?TqP%M-#^ZI;L=aN72(Y@7fnQzpS9L&w{TzxG|xtC8mzVYcCP>)v;K{-=p zdiR0m2=$X)C5Fn2=9FQc<3uO7c_-l|AYj{!W$ja*ZL~lMBbTNWmKaGZCoXETOwYU& zb_sM{QU6L~jjnoJ)0}Uq*-49v?-ag~uc9$Yf&Hcv0gBopV)b@Yx9*gn(ER6zz3w>0 zV;tWFH0I)&nd{^BAxq}p^05Loob130s?w?|4TN{)bKb;^2h`}lV>wEH{bazBbGEWj ziy<`RztU_4#YmiwFkQ2~eDfhS$9v6(Y$%PxU8t^&MkQ+HS2xl7JjmNH?D#zPS^d?@ zhF`oyyyU%#N3_fOY_i(iFi&OMn^4BNvhqc?H(Lo~ndJfX`#a;?4}9I0)wjQ$wyWsM zQ(#Xwk=tXZ0jh>w-o@M^-i_+wE$Y0rtmqCMZd7L4k4!7)^950@^7i4#qPh|uabXaN8Kp*GhRt$p|waQF>;Iho?dRDNy7?t3rsPnPW{3mwP%XJ zJB}9_-14Q@yL+6xbN?JlIZTAnIg(&^nM#%nwfAS?hns6>Lrq(ZxM=k;x!Wc-Q)F!o1U?U6yraSor^GbYa{wZ( zEdaY5`yo}AJwuPEG;G-GOqHY;y(Yh|ejW#Zvmp02eQh$#GOjax6nXgL7}iw$ybzy$ z`;K}r<|B{mjHr;#aG~MKNu)DL&b9UVOa0KerRxJ<$+_u@*96}ZUobRPx=?>qWGKZL zQ4cpb-%lI$u>U#;QLCPhY;^{x~Zw@ z_7>f9t9q8;pw#F4vxK0^gpAMjnh}uJ=_XL$;9y1`Uz(2~+W%Jug$SkvW#RybQY&Zv z-xO5IS3rXuQ!f)wEr{~#qsy;Ue~q0T7BOm`!$-o}q#mk2Q)h#zg`*P1&ZCMIU8@eb z0t$oZV_k1opPGh&g6In>ub<`0OaklG#XY}sikwZCF7vInVLJ$H(7ZlKZEjjHqJyIQ+Yqpm6cH?%zN= z_eoJ|kPO4Io`)@qtR57^GSF&KAY(7>k5im#HjIsKq7+_fkw<3NwU{xg10d2dIXKFvO;0M8(P`I5`NVrw zsR@CXMduO1oqhD`0Rdero-p%kSp^M^IEnJ*z_>Ent6ouTM#s+!0?kZ7kBZq56E z_!6v($jwiOr&51nk(gfa`N%d9$d<+=9q0KvPC zYZ}7#Ujh)F(S6Mp#9Q+;An!hCaAXTL8~XQ}xqTo>DxF9aP}Wcg_e%Jy9mk00<`WyB zh1YhdW*@boYWo>O`bU)_2B)_28^G3OfZQANHIFfi=t|X+_|vsv7Sm64w+|m_H#T~U zLXIBtXyKw|>(7sfphH6XKQpv`LG!cw6}{;mer2B$f|&{^Tm`9hMM>qeupd85*5ZTG z)5LKz<#`29x?0T2$t(+dxVq9=mRg@38TQP7&N9{`v{61D(yilRKK=8pf?NF2nv*M@VN~*CkG?#U84|!TiRgU+?}6*^>d`0Cy&(_*8@_ zV{AmHXuFICeLF>KLDhWK)lYK&4vH`(!p+HZK$=&E zAaB(pJ-$@eoUNtTG#%6!TMOL|2-D|TO_4;}#*5kpdATJ{SO!SxhmUgAIv zotW>(V)_G}DK+f2=^*H2&w|+@%+GZ9t8pH8V?&?#jL4c?|5ae5GF%B(vFufXPgM=# z8Jl|J>*VY9Ml9&wH{gwldjpHL#f9N`iaoDP_sY-nUZJ?5hJN_PH!{Pk$qK z5Ekmqe&!AD2pU**~g>uPmRNs6{~jL&=ASA9`H#6a|znNT~n8JM#MLg#SGtp7|7#BHtrK0lV??&djB? zU$UjqG3s_;fheC-%GrbPHe*^VKcYDQt)>_4z|4H>smSS!tnsr}Yk3>*Fyix!G=PfA z4={8R$&Bp#SCW^$TG5zx6D+bVLhjnZ4bGPl-x%5-C87j~Ele@Ewm9H*IX?piHHQfvw^ve}AkEHOW2#4avHT27iYKR&@vmZ&# z=RT42vx7tJ-vw)!C0|CaH@7qCWWFU95A^2xG@!pXCcNS$bGcP$d1T@du6M3BZj;*b zbnAN!#ig*LXpqLEl&OETh?S9QYiVTxsuc#g5oN}AriZqM!N@CQHtbz)>z^mRVsxgM z`|8^UuaIP_KJ^=C&rK{x6{0Kt?q+v@H1J}kxzG0;^HP@9s?qLBEVkSTNS0LRpEXEG zaIxK2G(ZtQY&U;x)t(TW=?Yu1PjJyJRK00tf#DrqWr<7(-tVts(I5fAZl9R)kDYn1 zK`LgkD`Bk|!OmXK+jyvALZ^Qf#gnJ`=(!9)NX=o3x~MD+)EfU*G&u;HD>5QSC>Oll z?tc5s(DQzI{i*rkvPAj{-D#OaeRIKou!AWyPfwBx4g396jw3_4iT26&Y}fj>*`@O7 zLh{5I&N8WGG?sU0^yDO$L{RRhGvfa_7A`AebHK~ZE)6-N7!?1E9>);2iaa?^QHwKr zBoGZAJmL*pOCMyJ#8~VWz}JMGF!7k}(+A8b74aeweAj|*i_@Htvqbgo3TWg}oe%oR z0XCUj>G8)7+S znSXQbmA-cQ=fgGnx+uj^70^|5CC4?3TOl!!`A+(7!8Ymg@P!A#=Pk+cj2N>UJ^VuU z)R|6=Lh#&R9HLVzt1r-)5^FY=*e-_fBb+nL4LL~w4@^MMb7XAUH}*iC;(24hD>=jB z>E28O3bZHNHVuHV{wYhN;U4`|iLAjJwHW2>exKPelRyg+ObT@>h=d)Mm~kmPLxT;g z2~w0S<2D(EvL&GRrSM@68o&LDnj9Vh7AljQ16@Il?#p9vS<4>7PZFNTM%LCuIw}*=aAMmW0*r<=h zwSXuD*nrocvJ`C$R%)&d^oyMWco|BQ+IBKM$PV*9d9~j9S9(a=zkUzuIj@k38f-sAT5&{4s=#}Lg>Jws)r!{!) z`W=nh>fgYC=Hk8;SkIHE&#m>NUzwaFIbPGXS3tGxKEen%V`(X*Cq=8^{~l5Aal@#> zI#s|@FJnYDh(=enYfV@`pN+__+8(iXrN(j?0Z{sXz0cQ)m;Z#sgdw~mrbqU^BLE;7 zW_>P}4FY<0ng7NxVrhHc44~yC{PL-B4n;IaAdL4rTIaqfHv)-Ukn)&G1)sHvt)_bL z*J90}6L4~P&E=kdT^CSVML%+DsOb?0OWpa>s*x*3SReh;AB!7 zqcm;;3;P`>ZBMEDp$$P@tq~Rn@TVeqYijAOYovDoQK4hutg2%&Ex5EJ{ZkN zvW%`Gd4x`Bgi}zMw5{uX4r_f-u0j|-dAQ?{p!XtgH0z-VU=w7%BP-B5!qBDZ9T{mI zntYpq%8$~YxW)a`j}f(=di%rDyKo{#pgs$_ao$RI(*kaK2S4t2%#I&4VsQ0n5qt=t z5t}7iOy+=o92$MYP|WmKUb@v61$0WlprWDJ z9QQ%$kaAQ5>gLFt0AS&y^<9yJnXpXLkLAeIa-`~RtZVFDiqfIIlpAp#w7A(nf0 zpJWrw|9W{OpgAeKbj4?@^p7SB2%dfj0x;{I_?L!_KZKW#EGL zV;NNG2ai^rx~6xCA8zjzQ6VPb=T!mWRdQ+iia@ur3D~X%&CNu!a0Oqk6aNVX`ILlVt3?Ql}3`pGSz+&`nP^XS2b;w?WR?}#eGF*uL2m*yWRr(ps1Om z?lVC(?Uz53#ql=(z7!<`eu#g4R8k2VlKojX1Z}yn0H=_vD!B5?Smb45f0lG<87rpT zODLD*7X%c$Sa*}jR=Yx~ua_|--#_`#GVVknqZwk7L`^&vGmzUr#I@o0Ao)z2*BLnu zlrx+R*$oqlSbVl3Pszv_Vne}<*dnOlSMQ@|G<#R~qs5+#9C}joown^`+m{u|%*!t} z6Ca%ea$2)?`tCA7k@6u=BECHV!XD3lk7aAq*Z=^;Ge1T`!ch^Qe z%pLf&SJRnWkk_))>JR3rIDOyR9h8)m5RJpvOHIf9FuDE^7tVX(ZDVGZEjnz8gG?Jy zi1*)3WZJTtls&BC#eYMLr1w(0=TX6m2x5OxpO^t898-cSVsRyEm8;+8?|97N#!Y9Z zg*Z7P4IkzcC^=A3fpbg_;$B$=&*;jLfEAILyrh2%-veIu;|2%WAV{h&s58jvA+?hd zo=3aYj@d#rs9qzhX(dc9Qf>xU7|~>w@29>>9Iv!BT&@ZnJI_0%6%1w)GG4%`Y}X=k z-A^hv-R~^BbuAuequmGTw9+r6ZV<*--#zM`RpQiL)?DsZUdUu|B9m<3m|eR+mZ`1; zzc_%`L^6LVhkdt9=AY{6+q*{r#%FC`l)iDE5isUoty6CoZfAxn6OC#7u$xe4 zHohR&lVT#it!#g~G$bV{pl3zjd#==^5PL&{P#;0hvewC-dXQ=4GX6{|TR-qdYIof! zoE&Qbhu;(yiv;_wu@n)~re;aA#5Eg&Evau)MH=llcjjHy5%47Pm}a1C9vByBWSY`` z%^gWAlig(Vb*=0gc@m_9EQZO~bY-wBS^yi;F?w?f%+6?Iq|O8*znq)acZUWtW!R=p zh!0!h&cMR59FXgSy2o+`-(rprIp7_{PtSSPbpHiK;-k;(etU2`_cQ{t&1sG z{@A6>j2kx=GY*xPb0^3HWyC@`2Agrvw^`mWIPAb_s89|hwtf9e_y2~)r?p#gnw@_M zva4K=TRxpX9F{8!_w9Zwr!AxUc`*S_;aWviI!5pGc)#m7NRLeDtNJ7&2ei*SqyecM zu!iLT>+g)#BvDa&gXgQL0%D{Iq!ysgnpqB`JNGYExjm$0kYrf7Qnl5o^M%zC^`x?9$ypKQS1pAgO_oA1iH?-?n@zngzI z_sQb+Ju*O1WPT^Ss&eWZr!MN$rk*2VswwRm(z$aru-zCfxkl+d#^IHRbZl%>{aU8f z$uX__=*bYS49ABo`h)mC>*@TE`63j%vs00Eh@`pAHFup>UVffuL(e8S3~QnL!1_&SKM?}XGU?{S`fB6>46>|=alXj&lpfVs04Humw zIZAYB(ZmcJg73oeEw#IMR@m{YC5j_bD`>UO3-C>mRMQ5@!4dt!?uP@{Z=$%DZ1ECt zXJWs#IOAxcS8tyihJJ40&~vv@R2gH@b&~hVoP-~JIjR+DgwZU(4^W#e|14JoIQyUu zYp8v0n7XSr49x+Upxj6_i~&Xkl&;79s>S51&5vompySgvf&%-=glYDZPo;nH3P1kY zyEfHs_Vx3t;yfhp{)^@_K($71WbT=USe()&@de$Dr^hBd6sJYuM< zzgO2f{KZ=?^EK%a-Z05qVN}zsdN3XS@8aW2SZ47oOZ&gq|?1b;h5 zPib^~I-8j-SBL4*uiSRgGQf(!Se^upJ~f5fDopCP>#LiBZZet$r^kbQJf8&8HHWp$ zVB8znFYcu7k{h!Y8th1ocB#vzqn?MWpZMDe@W-FtzK`iNFWj8FH!kac)9F3N+M$Z{ z9oVG_?&U}}YRhrwVv}KwW;$dyR74zJVfwMas8t?DRhJv-Fx2RT^;V|fxc+$Vc{+U=XDqLQ33aursi4Z=l{Ve`K{!8O zPH-n06rl|v^To#7RqwZo_u?tCV0iD|_-peQC^HTr886m&gx~4o#e6X1AOo+JBJP=5 z{)Pz7hy)5)#b`l3`)H@Z^7i=;B|_bL-=Ys`rF*^|cHayqA9F0pWevJA3SvRH5*0n1 zXY`~ZUV^dboA^PC=c&3fO!%B=lCNg>?DNf8YmPAW|D9KSvXd{(PErO6{-=n)cKO|y zhC>(2WE`}uTRD5bI>z>)k1wMFDL{qaNTZz=zXj==rA^hR@etBuZlF{21?;xKhUe!t z82}71`hof;cr{rizV=jBRYjxX*&n_~p~!7+WChks+o#|AGMB?}{hHR$sqPxN_&EA0 zIrIq(vgU?}?#S6Ox04y|>124za|>OnGfM4S6dE*%e_hmi6Pi%`(MHGDe6wNP_%7?x z%^~$L1E%_MSKFSVt(zM9dao*ZZTcy+Yq*IzxwK2Gd_8LfDI>8hu6^1646S!>ZMbP% zleoq4XrmKc_Yn{Hd@7s~NFS6_qwa{uCW+5bvyk72V*G`6oExb%hZtRkrs z)`am~_#=JVqls0^SV`UHXq@q)fyIf@Wno`>bC+{psBb=DYUCsI6a`%p#2?7V3l*`q z_44miD~;>=-A4we$KvBPE80h$kT?;-0kv5FzoB%g!d(X%b`{A_@Sf)mget`?-Sghx zSAdH~%J;CW#FV$+o^hAlRh=3#(XvJAbFw?ZaXYh#`X6)Se_N-(o}IIj^2maR0xA7N$*|kK%lo{8dziAXGAskh~wPG9QhMtN*8$a5M&6>_15kTSP zu+lHY(KpCQV5I1js5r^$g0s0nYGKOyLShL0N#w&jpLk&_m1QZg+38(S z)z>xz%)HlDFtJ+Al}>Dl{USyl0Ox?l3;m<#ryJbutMz~yeV$oA^Y44p0Cl_(?{6CS z&3NQ3vT%9QI4TB%J(%)Gch1H)WSjY6=E&(7;VWR7`_uW09RGU#o*kaz(D;LhpgY|I z@tR-|R4SKh`GhE|)0hz$xou$ft%fw1UEx{qN&GZLS-6$3AP%%a%^n^)<(`4W=P1nE z*a)g3|HHku&6CN%8W5qh-P6Wypo{qRD;_|?}hfZ7Gg z>k5Z+e@T1UR(1fPFgY)8%xjV>N|!+mVdvBxACItWHS!Cz|@FjW`zBNdc0`vvH`%9-mFcvL*xRq1?8Qy z!9KCv3-7yj=s4``81UH3Xen(kP;;=MaG>M_07@L5F!d7qzn_bhWRN}0XO z$hDmhdGQC+9oaHIe?1JFDZi z|1MH|jL;UN>jNG3LxTTabC-W&YYP#vdt>F5jLGl$fUW#6XmN+da;aD-LHlTa%ZL3J z5*)qgyu<}GmUhCwSJ%L(1Pu7|K*=C?;^K8Zguk=zaWc`O)xdKj3%KP5C5?R-Viw=x zB?N!adF7791PY{Q;uXz#V;J|^J~r4X;;)hi+F=B`lCIb{A^D6d*0YY0sdU%2Kfhxi zZoqZua(_Ssn~hY`%hXzil4K%jiB1l+IUcVy?ax0aJRXO4|MQ;RC$NYZeIJYF$<@CGiy{g84?FMJHCOGj7M$`A(z+l0!+k&%RW#a_zSnbL~)8~2jL6~ zL%vpyHbRp1ZL4Xm$CIez0XJsEH;mi zDaz7l7!W+y$F~O^)6aRGZqS~fs%D=e@8se^pUc2P^PAWSW}u0%@A^F-cy+*Tk zln#rg=j!yCSN!G=*CX?Jymx2OWo|jHw?)G=^sO;NZG^)8jzYWuJqG_DhmMg#wMdz2 zgrS09KPTqE1Se~OJ9?vA0`*V$T-%^e>~6&v7PGbr$&4QBG=7~a0T^c%EJN&X>_1NS2WFpf)J zkgVgHa4d=g3r(F8UhHz+P!Rqn>incrybMab_LBi21RrRgtdeq<;h0&ec&B~bk!zZy zzpyC*SFlhr!7NY$H@333Gkjs)Se>^qVr2Y1HEKlQ&M?O49l52OG4l5fxmL$cX zMxv}7r2S*v(r2j^T-13M=a!lf@W%#akPKj+|8!ZhQ$+XZVDc9Rh1zX4!Yur%5WZlN z#p{N=G1~gNJE_{{a$aqQqK|(grBe}G^`3@ihNsGkxjh3pk;7YG-v4%BvC3ad<^PxQ zsPvD_dUA3SEb+!>IKJs`=885IJqh45u2A$UIndabL8-L|53v@9tK(;$Pni)}yX+du zGe^~k8XCCC@Q8cr_5A1v286cHdiPTGUtyFvE$&ya{|1UL9ndIjBNrW;^lvI$Dau)t zLraNhU+jLYqUvPAYx&xobW$h9&+erz zvbD0*blnx6(0%Ov!=+;mh1Ka~BhV9mt-787D6xQ^`sI&=F?Bzh7|6H%eJbfnap`vs z>N1bheN$svh;3mg=1|-Hn0uPqeSy~-3^E|q6bG;|L{>k6qu=M6bmwc^H(a8yf$cZn zGx3?x%Akz7bJO%nQ05X=#|+>?u)kHkWS#ZTtzl_R<``O|&u|qWKYFxnn@mQ&9;$Bm z*jjnb0Szf?v-dMb(3VHgpoZ9C*>lu|fSp1{iq9-|r`8o#?s!Sb4tC&rbSO6DXr{g1ArM0D_H*(`pKY;*}Vz^B&JcQlfW zDUmlL!__&Q6;qN*A3nU0zkqvrjlrI-jFVE<$u^e?9R|Lxbz4_|2Mw(Id*US2a48^exVbvv}!x|?h&-T#7)j#)A|YkXPxjKDZQST{=F&n9fQ zA5}MKuQ2K?+VoykmZN@lS*-1=MvAJ`Z&~xLxFTkpcypZShwvo*w|3QT7)uYu{~vDG zy+*j&#z9Fw?<2Dy!hMZWx|?1BM@IIR@(aHbFzc^$#p38tcXFpryJ*bE23OI(MFrxg z^auxiot2BkJhy6ZW~2ZNx9rB5j&Jc^F@HMOBSjB~a#Yg@=`k>pGg`2RsoHuSwklsS zk6|Zm`M1}V1Q=dj6u5TR%U%Bb>1VoeJ+|JRRQMv)bI;s6nt&FQokCJ&r9J;XaVTj^ zRms69HAaNqiaJdblj+A5F;Xx$Dya7UX~+19wc>O8yDU0knoxFZjM)T{U%>p!$DWQK zRqOOR8fp6GRW75DLg&)c&Z83qcN1n_s@9EXAL0fAibCKx==VvkxYm}5kvXfs!7)Se(i&_;x_8H zbC6-HdpbK7GAP@lxrdw{rkv{*Ed`c5enC~03+bzT>X$8j=h9$ND2S(6p`dn#ZC(R; z021c4!)5Vd5HHCkd>Wp>N9NTSF(c}5j!bL`n~|?ZngHtsVLCBpn3_Rabyu9=@z3=P z{D)CG)ANUK*Fw!>-rYCy6{e5s$!9$j;cCb0Psi(m1NuRyH-TD#=ZLfv{ZfsX9;c_< zgy&DnZ%&!##Vn8(UE6lZu=9r*jK2LtB@hg-JJ+Fa@RNA)laa8vp6HiUR6GBeLE%N; zJ%6gOWi{XnGgz+R_sFX_sI*5{-blm#fA~5jJ0AypIp z>wLl|ZZk_yPPx?Pk+E_Iz^kA8flKA6a={ZVMK4224wgaT*R=cl`N3BIs|HfunwGyD z{70mKLC`HevuRsD%G3b7Y5npEV&h0y?I%+M?Nmn)%C0NQNnPHJo>C4Yj}$Y0^Yo3N#?n$4&LIaSj~Yr3a@_exbE(obeFZ zFezl$MxI_Z?4Ai?82W^+HB>GGJv5}TvKL8{H@?_X4#-lLUZXci- z_Gg~{^;@lp&pjSZ@Sx81SVQc_UO7xJu`RJ_$QZrV^s3#Ua^Q3A8UrJ$e?mOkloZ6x zt;LcKo0vZ~5qQo)goO=2$tzxU28iEBCmJniSwgw&*@%qh!?;d~hLK#(Jn_o#C(Vn`C^<-XzX_m> z;E9{7UorBXM5N)vv^5S~0WT`mV}anXk-*(o`2vXE+Dea?P3)A{t@1h_5xloMj0V9<<^U3zZxe#C)IidKJ1LUR?f z!r*`3?+gyRBn&ZT7P@r~2_||o7cbjv3}JX|30ppQiU!>Sv@!U$ZvaW9W7LLIS3dT* zHNq}uu5Ft(58ox#R|4bnHiLVA94`V2g};W#OIMdUbRR-@gRw zHXRZjk&iPh)a#X}TV#pig^jkCaWGQ3Ei@l3W_W}%Y{a&aiZ_k=O39@Mn^U?26tcONEc)3SdigJY zM|IYhQstx8n{WJeK10dRoI&k# z5OYpkPF>xYi+{_nlM1tV4EV9K;I-uUvC7!B`SXX4Ky#O~G-IA1Gqmz*GHk3OL-#-2_%2$gtDk8frJ&(t-CtDeX0JSh}BHt{M-l%t2b0vF#t7MG3fX5?C zX~3q`Z67`!m}cl7y|wKySv5qsd?k5+7k8`F@IDyd-wNYaUWBs6b=CB~%(%n*ls6!w z>NUoesMcBs_a^eg+D*67{b;Pz?U+$Faq{S45@jor!uJw=2`fkbcx` z&9t(%QBkL9K~E?O8yh{>Nu&0IR5zO8Zg^RR?raO%e`#JnuiEVW3J9}ELA`i^1#Sk& zerZ;n_nvp3vcpm$acy{_?bhdRA*NTYpFr7mZTPz&Np8cy_W(>mM7)nI9idfrE|FEK_zAQUgx4`3o!=DB93`SxCX;j1q;Us|_RG>HB^ ziH1O_(mKCoW5Dc$o@&juN`lj`gPLgy#0k?8w95vy8+}#|B951cl;dJKn*a z&p{c2evJqpditql0V&20*q5(=HyHENEhan#0g|cT4F^38Gx*%SJG(J>@HQ~*ZIyl) zkfui70({hxy8C9}hL-4F^$if+JI7s|>#P4UE|$&?vt+3+^a&--z5VfeIWp`EQDIC+ zO>zhhFp~O{&)s!v$(~>f@c-US4Rc_LB@VMrd4{1_Pvv}mcvrW$B19Bo>f$pp@ilEv z3`Kv_>ZMS>k$4qgLYeC(@SOR{XM2@|6~X(E?zG2yTSQmW&MW=a@c< zX1}{$5^)ExG-#$VqzR@J-Xiaz3W6=uwtpj&%-C1M#IN*4*f3;cni|^F);u43q7ig6 z>Ali3vhtUEaShZUwtVMxCi_|$%Ob2j<=$`cYK)Df2KgGTj+oyGc^6k*N3SNU(urnj zZYrc}Pm4HGY!}&TV15C*jQ#3*c*-l_QEIK{r;tk1 zCL4=B@r{XL9iDWc)kK!smvg&K658EQqrBksUvv@O7EF`ZjYJ?0qz@K+A z#T_193p&|RNw02Hq>nN^Wz0N=#y3CzARLy+{yrUJJuv8Un>Df>zEF*HCh3Aoeb`QV zu5QRrzUmsl%5OOFe47QKs<94L;IgoLbi7a;PLuL|KD9uMQBoAm$RKtc1g?AAbfv5B zd^lI4i?fs@2H^V;|Pdu`hPEfR>JEvI|| zMivb}tvUY}USZR3#Vw5|Kl&FIf=P@;{W>n2xxX($?FB$KuUVo^icao(wsD1wN%RQS z!m71(k)buAy_RlR@v$Y>?88NuN5lhY(ri*xw)zz$Zzum%<}6>jx`i+wnc>(AF}3X< zPRnkJFDGzQ*yK*|PK7Z@2+yM%;t9Il#maAro}Z$3^NwiVvLtn##DdnizZwjS0M;5KV~8_s5qBp*y=mz{V|8Z z!MB%=c?AZ)e;oVv)}Zy5=xJ7Cw9wcn80hpXikmV24vgtyUaP(cYV;lwxbLCN}NRWy~?y<34)3TgCZUk9^#!#OS^cRTpTbKx!tl40P5wFCop}pY=M- z8N=e)r5M8eG$Nr&ZZ`5WNuKeN>w;w(S}xeaX5BdF>5_PgxA(Hz1YpCF#Y@c@4m{ z!gS48G)ZCWHvl6@;<+GWq6U0qoO{VMB21{QO`Kn}*PqU56p>!Q*W?sLzM5JD41gpV zIhdrJcWoa%DO}((Mg-m|Ak>Zpnt+vUOj?qfvos#B-$>2+W4#651g~cV1+CXH;=_WT zt?%Ziy;as>-L4>93iMPe<}N-ZcsAYEI_3Zs#g-VVpEzjVpJUoqn^auNpg-eKk!yCK=O!ii3VJREgbGiyP+l<|hUe!5@`u^{(n zk^^?OJW8FkodGIT-#JDS8YAw_8U5*WGZK!y_Dz_3-J0kdYbptAhG9BJ;$%J zQSfgC0~qe}2XB1xoVzvh4cLOc7xJ=^{f@A)o$lE4U7zjCeEKz z5{I+hs72sNw>ae0ay1yWpa&XleZ7Dlj_M^Bf#B z31tV$LedA`k!`tWw;4bkyzcg|ZU4>_-vwF=!sH|C7NdNzPojLk=@yj(SVA2R-j|Lr2R-*Pi1uC`6n0?FMfM1jDw-urzB zL?ujSO2qWcGykm)hEE)ZXhp?q2W^`yt}s>d-^$~zgWg%#kCeKOaXxMb=)|mk+kgpaY_RE`U5AemnZEcjSpxp*L9=;r16#Skz<{LXO3ghwAey zC^6py8jQ6QIB(d5Kp$sl)xYDphi)7JC~Wuic2cCBd69U&)ZNc}xlIO>mBRKyKV?M9 zdnSGuNa~G^E?_d~o3H{Fu^R`Rv|PZ?2Lb|Dp77N**Wcc2_Cc#JHDA#h8v%zcOWT(P zYbDrH#Tg1r8T@u3PWksg%lF_kH0#s%n7elj3%b4c^QD`s099V?+N#5f_}@t@snqG6Q56a-WsQE%#X)@?*uM!RtvNkW+U$DwiZTQ2id zd@{ZaG|5iCm1Jo=kd3zWBTZ?-&R-bhuT@hY2|OS^#+=iJ>H{sik=s59@-L~$an0zyxb*lRHwOn5NJh)H~re; zj2hA9_b&?995teN@i>+LId?=OpBB%@?X(kk0s}J-t@THtzM_-i!Tf~dOcR#HV|ltH zI*w-ePI9bUjif7f|B zu|=aQpVmIv813rSYA3-ne8mpu ze|Vy!0hYfJ7DlAQ>LtD`LT=3}OSC^Bb-?UE6v2n$7ADP!Ioz>21f*g&(iRv52(1as zeFb$4N=N73_(}GEN3ZBR1L2Ra0;ow{$qw$ zIcg7|h~GD>L0tiqPe`v=!U5Nt?h!uoX&#e7UN0hh#xH*q?xxP718-h_C;6BJX9YgW zouy6~KH0p^5{U2e$*9X=#Eqw^oM0>@HP0rv(DO|a#2}pC{haWp7mkGJt~z54C+!Yx zpO1NZ&bWfrI3+yrd0q4oRF4FgMJe8F3}hnsq>AX3Uur)P`sD0)u|afI3kDBhl~aw~+4UM%ac81}ENm&!xUv`Lo9DhCagi;Yp#Y zHW!R2^qO@tBCyUhIrGr)<`%uNH$1`$8OwT*^iX0tcL?+U_T5{X&e z)Zg|Qk&d)Eak&#HM{?i*=tHxisDTN-bvI7GI&q!ea=8|RX9)sf*?jF z&w?wU*FQhTldLY=rkRZ3SkBBGP8oJWeO>7KcsQkU9f>$|5rX2?7o-D*CPXJXNkcw0 z)3{R7UXb9`Mjd0pDO_fywcyJSRN}QkR#?hxUwD_+EiGyg!o0#ypxX>c4jREJM&b;vr6p=;2Mo>Ntfa zWgFrl>WIfFk9grer2Rd0G3Gmf$JCAWm)MFYNP_?YM^#URQ|{mmR`+D+PKSsW2b?NB z#al#4?=oGq5*EEUSUsi0^SHGjCX|{x$4$zP;~rh?KK1s1tA(*yp53~NzBrl`BJ^u* zUX=+PrA}q>p#jf0yWs(qnhBuY%7i~mgfmO})K`|-DP21Ll2O`0D4rIRz)`;A>agyg zghVH72fnS=`l!vMB;)oGCLzI0MF}hIaOTBk*Z$b%Qi^xcR0Y`kZ>j#D&vmks4#(hr7rO+3#S`Jac9ZyxC_USm7b4IJ%wNF{d z{ne#)>PAL6hF{iWz|bL-Z#VIWt#Q#hxg#&AifX!$f(H(zcNK!bEeXC_Eek1 z7mg7rzaF$7CeLD^y*cuhi@zbX`MQI#r9jj>f@hxmkl)ykPjsJ&SPXWq3GUZDIdMv| z>j%53WL*;hwYr(gpJcaD5uNrbt$y3tzOvG@3~O#O@%l}7+G`g#T(nLQLA_~Y zr1c5M-l*&ngt>5uc)xNT6RyOE9rAULR~fX`=&`SOmz@x7#28PddtZ}@|LZ%sYpTd8 zwD>BUxEIv^_}f-Oq{QF8I{)dn?FD?OJlii**M30u&pc2Lt{${MEspwP+0u)y< z0B&6#)7CY%4yMYlp1Q&gz8#P*pyWP zwTlz=ebg`DTyskT)K~vh-BLNiq_^w@T#ob~lJpgp+n_uaCN)=MW1k0bOMS z)@xFgzbbJ(PAaL$W1G%7?ms0eM5E!<3KWc-DiE2T&Ja%{kQhulzY{sy6-$UxHaHyq z2~d4DYM!=%6t~lOo&uo*M$_)_f?UoI&ovt7Dnk1L3c$K3B!)zn4XJ1s?T{{3hy@%q zKEd;T5LYoez+qCzdJ*Wi!cPAsx_(VJp4Oui$R(%Q{UNpe9EETpa;Q5|;)}|Uiz?tjJ16oRy*XLhSBXYG9ktbD z9Ct{bVbTQf?>5zX5?;qjIWfy|L;Ze77xHMI;gEjo21&HXkiGUy#L+>2M*`T>NAz8Q z6|(n?xB2Znj-$7Vs=eG8ZqmE_am7B1uX@^ zq}2QVsQkF;ZmFrW;uHI%2(^llTZKHC>GN7p!hduo2K_i%Njeb$M9P+jqZsW{2r$=2)H;qiE5J^@fvb0;rXqf_nV9CIvjc?6+4i_W_$N zInP@z-uUMtWR%4>Ot^w`bBL!?=}-?DjJyX)sA|8U#INUymw4}hyZ1oulKfkfncq~i z-&%;PqvO}3gYV}f-;|i?xW&I{iMyFLCq5Kvh~<4k zImyBsS+lLr+m&b@N1rSqchiN^2L`lEBz`j{to`kO;gp};^ETCUp;OW)J!r4nv<5?J zP8L9T&2n$+;Xt5Qh*>5LX4VLO)t@H!vBm38xJSRrO>0}X^YmtbmO*KIQ`tYO>a99XP?@$^0KT-!r^{;-TYYnPqn zSw*UXo;-m6*pC)fd*GdWZp}dvo!9)(-7>nB-@-^kcqof801<|(4ThOApH7RP{iI70 z!;$<8NB%59sdT}H)y5RL9z%v3Z25sO5o=vrTNWej2jpAHOc(INSTJZgJFx8Pc^!7* z1Kq8x>ovh@OLxC5Z9X_ax%+P07D>3!=LafbX(5&s%*Hx`?rI{8$B~_dXeX_{vhSR5 zMoLB2gv;?C%}IBR(ueC6i%Pj}ApDM&=#MnS6!7~)%Q+_A-9@B1qXMaNv6TlPv;Vbs zinwX1I7o7dQ8H5^WtPWh^^9LGGhDn?;7-UmweuB7VS~TVK*jm(b5}83vr^&trvSU0 zzWMbO5IxZ%j(hmhOyhI)NlOf7^$NHwc*LG~%|sL&?m?2La=pj)NjbJq@FX<>H5B6Sv&jL!@Oyny#GD+$=`bH zB#~qo)fR3W)stc&2%L7mR)4;c;>Bt6)@X&h@!cd@yWGb8Xw3dBM*IYahi@|CE108^ z9;}o)T67CSN40_~ar-U$n~`Rq-qnd~u;IpK-px`wb3A0ka}<>bA`upF5@Y&kv5cK^ zA*20A;=Wh{p6MS<##F@*(<1#fKJ(95M_ufOqlrp&RxyhyG{sPaAEcQmK}s2%X~B0H z!Cyh6+aDg5hQ%5GLBLSLmk-dEZsFpEj03Pt7&@$DQ!Vj-3(}S9P+nmXk%_N7aIM=z zvshaJV&9-gq1b^yb(GtPGB6urD|qCForcKkH0a(2yjc2)K$4t@EQbXMQ-8<5E@%tj zT|HZ9z5RqsbSn3eDS3)+O$6`_nRxj)iMWunEob8f~y=$~m6>`hK5cETR3R_GO`MZy#HX z{_MW0H#v8;&4988q-*d>!c7xSCqBPf>1ELFJqtqF*U8Z~PksqoSevC6c$R!1Tr|g1 z+%a11-B|M#OskO8*MPFpY9--}{Am(<%qqA{tYhCUD!E0ZDU0>ai;4b(u61jb19Fe| z46$atkW3VkpAG)bsU|EA;2FE&_s){x^QtYQPH6A{K1Cph8=ju~aRLw)?Ny=z+Yx*2 zy2Ri=9GBgqIRTicnlNKgr!(XjqVgYg=e z_zG+4>Ji1@$lqJ;N-f7K4e*wg_!#pYlnzZ|0>LQqSF0pHJVtKCF&TRV?l2I{NI+jF z)p~o5rQ>4>-)Fcv_2+2!2^~vpvDLlTPrDOy4iDcq#A@des#VP6A$MsNg5K}frQJL& z%PDgCYV4CSOaDQ{pQ4f6RFV`O7$KCK6p+$4eYs!6MlY_`B4D8IHLOe#Ls6%`4xINf;z2bOc+phwQR`}yXrz*U*7uKA-TO+?0@h~DM&I>q&_zEsGLP%iu z@H$Z@2Imx9BzFh5Ja9NJ*0vO356=b9m8-RVe1X>h9AE$w@$7#{utV7*fAMzA|MG_Z zCPVMSaENj|0vpWbb%Mxg`M<#pBrehdn-DtwaX$;`)mAky_vc3!>pc)3B6Pde{5__m zLPWX-M+-jcT3}GD!KBwY&B`qd5wMS>rg<=A)uCiB~e^g;lTfE)-Pit**=7F z!umvqny@k4)^uGrYNG7RAhoEbHET#6ffQdobM9{DIc)1?Y zLBV^6d=CQ4D%kl90;iA0-F1T~c-#nDB{+bf@YOgeM7mK|YKrMFH!H|+VYg<>;}<7r z$kmNb9N{9JCk>hle&Zil*Le03Qvj2362wjz)d+l%!z9J$o~tikJgF;1n6l$-mOhG} zf7pdGKIF!vMuZS!=zSp-740zr3ln2mw;7l4? zoBt$YRW*;d$_L2OgpSu`+1`r!u^gVlhi)3~8P`KJr*Lguc59U5`Y{_ROnVafaYvAz zYqKB2SzIrG*yMLUs=EmMoa4xc?M{WD>Ul6qy)9W1Y|k|$hBE{vsukC9C!AK27?L#} zPy3S6`$~YOR)V5!WuI8D=vm@vPJ%)!5Mbv4_k%1)&=L9fKEs|7BQqlZk&y{afLcV| zwje@Hy>O^{B>(Y8K8YJEQ~baWA`HoQ&jJu)*s}^U^#1v#*OhSCZ{y%eOg{5h7+Oa< zTc#XAEP!NZc5fiHt!tm7{j69XX)C#hCNRT7=~2NTYM3%W`T4;0`2c#kJA}ab{D73F$vanv6`FI0~ae#{U`s4hPYEz_dQ#7ds{{tUFiU(riah18*w+Y8mZe z+V*%NY(0>!b+NIk;19R8ZF(}E1z43LdcnILuZwVZ=V%tdBfMj_!CWgl#>jQvJ_a%! z;(5=Gr)P5v!-)8k^9n0F5jV3L261R z&Ylq3%8*&Lj-x5OY?;a`lMhioM!!Xu*fu-#Xn-`$@nzD zfDGmWQ(qnNZ|HYR=O)ES6AAf5?>6*aBL97^Wo8#exTf0Ok+EZ`?k`& zCoYY^3lO<`ihP~r`F=ROeXtv^Y>H&-d5$M0{qTN!c}Nd{*c6uXK40#Nrf`m65?H^b z6MdPObpF!&^3c1lEATR&=Xv_)Y(M`@mh&_#Q3-%MDG9+J3cqy&aYq?)eD)F?18AGx z&t`mvE~qy9QtpVyycZOuLdevZ@g7ZOxrSXXr`r}0>pK2xO@zM&=E(tfDz1j#g(c26 zSYq&x)7uV*e|m7b&VuU`6a=a@Qd|Z@H2NB8+i(#W-9BRQoLmXP*g3gqOg0~&GWf8l z-9V@4>^8;MXMvvS`aMh++DW?#vb6$>t)}4k)>Kbh$*|-T|7p{yi-3J6CjSoh$Mkwl z&jXD$pqV<7vt6)ljL!+M6u_ylO+6qhXj9}oyIyA4waXG@Bn91ec{yO(-`o_IBU1j# zPCPwn+_`5cAi=!3+%*OPZ`Xu%f2Xc{0#RSWSIE|3jm8Q5)bCAHmOvnY)AN9`Lp@nR z#4*AifZnzwJ=2#-Hfr@$82_xL`x`Q-{)e=0tI9`u9rxwqEi!tJul;)7W*Hr=p>XTV z)76%D!S5aloK`1C^IsQ*g#~?;*FhcczLQ%aT*=08&L0yy>4t<8q!v&CRs7ClA67n; z=f{jwtp)oHVGC!AsSh|4iL|pOr+~JQoakeHzJ-g6zMf$$clHL%J>5U{8IQivw0O#* zv%8`{GvK%Zn@s{1M<_tCqdy)Zn^MI;jI#m2oPy|v^^7SN97lWu-;IZ9XkU@&8Va3s zO`*qtWc5BL5Dl-bHGJ$fAi_X9MMCa#(VXGAB^DI;dkpQQnf?V}a$;GfV^A5J#d6>iPz*G!IyF=c z8{0V;AVm>W4i%qVY&Nb080?v5zcwA#fqCO*I&E;)`cxw-&=BWmvqBdq9 zYrvqbb8E4(vwoIo-oP4&Nc?baI>Tv((WYpSqO}Rc9x5@Hz?-j|K~UW#TzidnPm)&IYfsM|0HGzB z_nuDvY8Zm7#Bcg}#QXJ^-S5;$@nqDL+$~E$xyI{CR?{ObfkPC~68CC= z_QWcK1-?rfYf~N7kq}+~9^`}UDZ`{n=FSx%Uc)z39d-F4`5?LOs@mhksr)p8r>Ftc zo1|;_a}94(cfz<7#hLcyyFSfg(1kyS<$es&vx|;r@JF!jT`=Vm4oG@cK(6;lbeqRw=loR%cAW<_Te~Pa_kx zM1Dio^RiVe{t;HH+* zOn4)w+juMc86bxXLtY~c*GAwX=a=`oIL1tr3tL2p))!#e-iz@%*=nt zB^5_M^jp8*+M;1!>}PP_+(uy!p`%{)hO2ekpQ?g6S0&sl*Z%C1@4;Ii^>wbbJ(4|l z(Vka6o4g>5E;{3$iWwa;Q! zIW9BQ8VcM9TFQ%0p@_5auOBF8?MW|d#jj~gvMjoq`}Hxd7T^=lt$Ru^t2Dy2Y>`5Q;5D7qyL%Fd)f=mFe-DKWPh+#Dr(tZ%NcwXd80oh@K z^ZdSOUrZ2Ef64LMn;!U)hDw(e6QO7pcuO)iW@DbM@5zH==A?ZkS_G3>(2pj!)AT9eNu@ zp8ogcXRu>1*UZP6>%o2n1&~|$q^nfM4xP%tm}a)H_SumMBgd*GzC# zdqlUJ>3WF)l2i8ToD`qFq#tK|?EmX#*PyS))WxKn?xw?9r^$m4$K+TMJaVeM+j<2g z=aS(qkW??Lp9sEX|yu+2S2Yr-3kLj*>mPD)Qf4v`kJ^9MUPP_X2`DA&EFn0F^F ze=@~F0-i!N1e>4{U+J5s>=Uj-R(+fDsR*`5JnhNsuBZnj(Sx!Vv8V}<<=sAM6cR^f z(*aUNDl8@6=&V@^-p>{!UL-SNFd;b@iFai4#Ko7;g7nf&mtBb;Gh z+~=t5c*QzDtZC^EM&E8c9|QIiI$d}z?ZiM_pkG^G!o7mA|Ec5ehhs~Vm_x&8?vnX} z%T#v~iCw)4+dQXNtt3{9R9E*(7!NT<;Rra0eM!f0Mj!iLtm4J{OhS9!*|E5#_T%rb zeQDm^Qq7K#vJ<_mKGit;!v0n*LL~mf1s@LhR&j}Ys=L{%=Uowu-YICP>XB>`2if~S zamb7RY71}Gb!PGH*o$AxPYOHECpg2^|DW|WTnO4^wQ!{Cp9{VN1!+fc$H36g`-~hO zm?%|42XMAQbhh}~2+Qi6?SahPO3|32*;ea=?*yfyC6OFfSXBiUBpJ~WNct3oU2ZAR zUhGi|(BR?ouuJ#*%2)5SqUJnDcE$qjawuJ~$`;n~G$?qv1i*y}hAx*v0{~jTot6dR zvk`>P0FqH)eBKA=P?wS)n}oVH%J2~aVt7{5_bsw)|1F~=!T661NQvV8-uN-%2zK*g zqReXA^I0*ns+1hKg@O8h9m46Ox#@s3;KDwjvR};Na!9peQ!#E0B~-zSv!7 zZOEpv{@kkmQr3#CySKq)AL8RcbTmzg{h=~KVZJEl$=3!A&~l?;nghA{$(hD%`*98n zJzVeYXHn){BFQ#fUHz(W3T(VdAKG~8+ON+wc2=&VEjJK0l4slPwpRp4AP4&pFf|S; zCpT6-e=9$6UeeTrlt{=)7xp=*z_x}dpFFH#CwAAbZ-oWjI03nN-c!STUfip1f7Ian z5LqzjZ3U~}A5dC3+41esj-3(_7^R^0;cGs|-d!;Tvj5rHi>v;dhb5kyb)WplLpceu zibyaV-uv$l&ofb}KyUl+EKJy(jK?BO^v@uEx?TXakY7vkv@wo2Xt54t4zl5ch{ z{4|U1U=OW~0!L^`F%vnCM6`MUb^xGw_+jrZtlV9tCtBtOFa<4dKE_;{U1h+X1~K87 z2LZ^XR-#wln(&%opNE12(rxSLb1YXE_3}FfU*j=t4;E|A*F9nE$;YhuqL?-3GELJE zR~=20+{L_LTCorbjT)_fq+y~A7hdbqrhK$fh`^)X1tecN=Ut20UqUYRhGqp5^wKjo z_fV}U^>$tm>^?ojA-zBg9m;Oozbu&NR!M$88mn<|d~FdcvwxpagtW2&ieReGZnYg@ z#XMf)ovz6>2k@{3lg|g-h%sQv%Tyek^CAoY3<#p4GnD_P)nF2!R%cDw)a zAy|5)>gEi%3(Ak-occqIapN2_>1jOwf>&y-EV`JWkV=X`}%p1M90u) zlp+JIAn!Z_R2J$=0Ei-IP28h)KLw-Q)(-g@4H7kK_=uhqW%Vmfb+nb5&uJa!ARufM zo4+@=qW%>(6%o#lqGby&oHao`4$ddz_}F{ubI+7jJqFAN=usCe={(+FWn$g22s}kj z(<;z$T0|FRVZw&vA$D-@m?ogm9J!#WO$nSBp7`B^lhvcG#TS+v{?;a>=YCk$Cg0wZ zw}0l{p(SqOuSFpgr2cJC?AQ-k8%yQe*NOJ`ic~}*h;pVVcC+ngA0&QzVwQy%BWpFcJ-Y8)~YvFL>#qb zQOuxnLsWM0UOelobfM=JqO2vI7{ zQIWe7|EqS8{Ch&rQ>)x`Tf+PAtTD`SJd>vpUS=3GeQi4l77Dzr_vtR#tEeA+*X`W9 zsYlcvHo9-EV(hG>VASrxni}JfJV~x4!IJc$o`hoqd;0J!a>tfJB zGf##|2O2cOZ2~~^U74tD+m@G}<_Sm0RIf;BRqR706ka#z1{DU(u+-hCiXf3Nbm0k@ z>Ofg1Y1X3pVr{?C5IasxVBV=?fkH$ueczcPc6s1!8s1VB_ME6tPQu9?ErK>~U20ik zH*X>!O&`%Bis(MjDC`)0B<#I=$u$qP0H%eTUxVu5*{>wZ0^VT{-@2%P4R|YB9=>s_ ztBOOZuT-V?sxJ-4^n2`^^nIQEXZLL2#Av$^YKf=vLuLc_4a?ml^C8X@(_l+8Hgg$X z!$Dci_=nAHyV5D|bwNqJ4Y9O65Elvn!D3iBmAQ_WZwjFY%6Nz7?W~Ez*pHlkcbJLZW@i{>b@u>nYrHq!w%yL| z2t{7Cqgdtg+ZG!6{bKinF%0+TxOV^5x!dOoW-&HK9`gG1$prAf_4f*dmX;QM9#qz9 zxS=%ly(&w0G7kCbdV((mnfV*3W-18%cy zvMc6Vkl)1UBCkrF(6) z^hQ84#BC<_J;Urnkzk1S6o<#*Hng}AR^d+6sPeH(dHZodp?tAKs?M`peDDp&S`HKo z=pgudETlkBOxV>&+^klh{CEl1KOUbCn7{s9{?zgnPg%T|1s+8^<_O7c<5R;%-2Iia z9{nJ^r}@$Kf!K$?r~F*>UVa7ASdl_xPvsX#so`8U#Z<}$-V&1lO`nKs&!7dx(O){_ zGw3@yG1PWc=UgnV8uK751Z)nY4^zA1?CHlge|au5)%}e!L{~@SLig9^U``J}eeR%7 zfjci7^zffpQ(Kz>6BF~|*!0EVpRQ*bmTFWF3Kj~o*i_}Y{l6~re_r=iIr#m-^dT^-M zoS)xJF1G3h!^KYuvmuHdQKg@X2!$mhj)&s1s!uq=vr0>0^`4D)c@49t9BQ~Ul`E~0 zm_le5AvV?kM8fw!)NG^n=C&(QrWOqC$l}Ep=WVi&B5~SjM(Upyi`f|eq9%4NbVTf=WA4i-dQ9znZ1I%B@pSmL&{Vo7LnXT zM&dO17W(wjMQsFPqo5Ii1H@2nU11 z<2*U9lfwtH1xH<(QirzTdwPWEQ&TqF!ph>mD}BGO?#-XyxLk$f9+)!ob^$zSYdbCD zpc{10Ss|AkC}#F8_jh~%=_3JgX8BswEwS@2cQw2bR^D0s)Oj2MR86+1W<)ry$Z~G& z=~l=7GYlJkBY{78q8RsMxg3unwMzFAq^j90C(@@`cSU48_UYqU!Y2Q0tjyw{kboyo zzj^N9)-yI075{ZTD8J7J)9ECagXv)tEAye>e=0*<2=ghcrBV}Q*)Lzc|1E;^5tEBV z3l*3TeEu<>Mam68)m4iKpA$-+LlpGb4@?4#HMNerW{yQERzQ#;oBc{%4^B9PRkJGR z!tU>hV%UVda~N8w7?u!D*Gf`VU*INwvYe91VFqA z9dNut^0dloHoaeb`WXt4GH+UmMMQ6-7zW7ZA!2^^5H|fB$1UhE#LP@BX$q5U01Z>& zXv3m_v+O*mpc4uc%jxe2Y~~Ywv}cs(C``uNYdYIRrFhKF^a-@JwIyy=JTI96vE7q~ zQVf4Nl~Aq5`W^pv3o6#wDWpRnYs6#{t0Md9-RzeeIkoy2Jc~DawQrB-E)bjy&51qe z5jON(S#HP4A`gCv0oBpMOZy%CH+J-#H)!I$k=ed&(MtFDZvnE@dplf73oydC1|` zxzHk$pJM$T0;s9xxo7_8l~QhJCHwJl{uzl@=cps_-7eljH)rm%()`yayZnV!7gFBH2nQ5M5o{IRjp=H^X&zg}ZotsZCLMN|tFIkPo{~<7} zSNYGLn{4^02(}PPC`xaTki|^@J2o!3kKc743IC6E9A2GfG9YkWf;Sz6xYXfWnPRE( z;mBiq>xMbG+A23fH+vX|9HeH_1{tpRTbhV_!~B9Wes z(Ch8nKjx1F?+JQBU;R)(0ka5|vme1vMk^WwI-suA-UZkgf&qK?Y(5i_I#>URz)7Yd zs-D8d9fR(xllNM0l-EMy@Hl$kO$n_<7>LWk^CM?6MJSF*8`<`pedLoO4H;FHK++wgati5g4 z0#n`HXGK9cm})TqIZ^feBpTUj@7Zl*TgURFZO$ezs?u9LxijG-N3u8{*gO}~YF-@3 z?6$F_*=Ih$B^t}7ZPJQfC#W(9NrwR@MeilpxUAEe4w(ig$N#pgqaa0)mnI${$Fd2&ev@Smul0AG>N=e}XdqQipC&azFA?s^qdGI(lR zqrq_E*(BfP%yF{x`z>#&WmdJ72jkUd5?*Hz+@Lj6CxAKM-gAoQfdfhqfXaB^b@4b^ z$9{ZvWW-R`H0Ph)Rjeh$@C?L4PJQ@Jd~CJ*&N(zbl#sU~Yo{v32F z?v;z8c`pHn8M?3NnGc2jA6ccfma#Dhd}Z<*cnGyS!XPk66G0xPvU5Juab$c_NMdd* z)Hqt6i~3aN(d@IakIqC&C=RsiWAogMn+@{rr;zUVFfxfC4{Y?|Ux!9DQ?#;3G|Lqo zIOD09ZV%k}Vi0l?8&|>xNYfA)BQL4+Y{~sQZSwdq)!UB6gL}j9c8U;`JvKz$2E-b0 zhZ`bd7`t)L79X~|n@OPxZ`5-F*L>dgD%z$*V23%z&wNz*Jf0j7&Aok8E-zE6gCtK6 zCV}Ed+%X~#?wT;CY9Iu*T&yvLxjG!Cxo&*;`Z_^S8oZU_K9>B~v5C+jlE^e~Q}^-X z)Gi)R>wWiMcd{=G$W|=cx^av=rg)xQ41hGp^^=5eq@P1s7(yL|^WE68-eW;WmJSrA z2zgKyAqxiKYoll$SLJI{PSlCcT`DLxPQ%lZ2bLW`7%<~!6lPhV!vCQz9OVt075|u z1KI8hapoXPhW^_v8> zP!xR>W5U5UL)4=kC)qj|t@vu09QgeCeTm<#{oN!p^^eH_rNThyh6gqN^wqhzJGA(n z%JiR(@jjKZW>cW9>hPFUP>2(9G(?`F=R$8%sLl zL2bkW^(jWy#5F{pKg8bT1YIv*T(|YE_n`iMxg~BJtC8r`h*viHwcfLTFARSWsAq=5 zUG4A_MDy!^=ShC^r|X>)q;ldyJ>TP1_ChW2qebFbKRaE4fE*s=+sst~BY*^8yvOWB zxi)QXhfz^Sgjg({oROyUUvVL^t?E?6u{X}w+z5J$T@(GgDE*yo(}}K={o0;LMo0ko zMlHQGL?7@XN+3Y;N(|TBmx$jGAOx@tdlQ{fnNmyE@%2=M_UVd+`kla|%hObM6Ec%p z$ePQEE|MEvR3Puv(u``9TPH`4GK$BLeno?cZ8fD~ntL!nP-+j}lN|=sA7;Q5R8H{s zE(LlFzN~nxX+emklt{Uxlsxy`zKOwfsX9QvLE}=1BFN*T?H(gk#vEP1w)uDO;j5hmnvWc5)JO_Ib z{qyYjrsxZ(cl(;+SzE7I%4rG6B!#RC!%uhq4_9Xy)@HYL>jZZzQrw;55}YEXK#{g+ z2^4n;1S#53oZ{|o#hu_3in~(??ogx!io?mf_x|=d-+6vK`JL-Z=9+8HG47!sHOQU@ z9RC%F?MFUT>T**xQ3x5Y>;D#CvCyow9(g{VE;7=iyLJ{Lmgvv?XXj3`P^sTXi=OlX z5)_al(L>s!@ z{M{H;v4TwO>A~}tZehKCp#|)X*sO&jX6BLh=tLNaj1G91ba@bM#UDDPU4(-{xKRuB z-IUbOo@qE=SsY1720MUE1yPdCqMh6j^cQsX70iKoB=u`r1_HXM6Fp+t`siKsJo4Af ztD41rma8}%0E46bhVO$S4t@yMKM;I@jd&lzV zDsLL2^<8d^%hEkJVRG}@4s-wr`9tGfYTBW{1MXG_XELa<+?^gziwF+f_Vf$m4#w?O z84YBM$hpttx1^KWH$MslhVKfZgNQK*I25{H;DiD&#G5LOOGDB*`(f6Y8x3A_@63S& zE;GPui1(66{RU;nF)XFq!xjC|ohB(|;OIH~=`-v60QEg1bNJZsWgt*Fi!i8L&_Baz zPCV}@vUY0~SR&hqw-r9G*KBp$mG6T=L?t% znOIPY9G}K@efqkpsVd{py0ZH^aYkeJO99D?Xw~itGAvGD5l@_Tv|a9~eP_gv>t`!K z9DZT#b5=IZmpyYx~oE4i4U7HPkf90y-DIuTxU}2^w z4Y^##oMygkC*61*GQ_scjYoLZ!a|7&c;O_gF>O*GQ{MzF;o zFlEk41nuC;^iNlxPZCyqE*_9&AMg)C@P8idS1(??5VRa7RU^ke zqC8rNPGb2oOkZ2b;+b0Q7j%l`wV*m+)#qW!S;!WTPq3#bYjuoJbh~3vGKwbA&4FF< zZLEmsgAd(rl@%8+ciM)CKwSf&w~lVHFdYE?iisqR6io)}I%*#?1k<%LM4e=;tGgD>^_-Q6KEt=CqkI4C9_U zc=D{6@~A$OEm5MU*XMJZ{S=P0E0wFBdLB*-Iu&neTl-XJy1Tr5ZWCQ`duZL9=+A{c zsRHM!D$MMR08qo()08hb$G^2_x?w@e9;~55>u;kk+6g?F_I9agCemNye8Q_al4c@S zLW6aJW``Zrv8$WpX<-HJXYaa=v&Nw`F5UL?KiYK^?gB&rZwd}~uhTZM#4ELpLRotJ zuotbyQPW{Ys1YnnUAp=2*Eoo;R5{982%jC1(Xv!$j1LKT^Nn`Vz(pB))DHBjl;M1H z?^wrVtk~<(?gDIOnlp4>MYO$IBnnVk& zNpQCt+EMcQbMzo#9AC}7{1ZI4#z)8ipB7btBj z1pCd&5PMGiKLIaw&=O;@e`bll-}C*u1^DMZ=sK_w+e@}EHO2UhT_bVTSiVEsA;M)W zHWZIyjRx4&yZ+?Kl7kPJ(;N&P5WCO&AKtOwntjdZ7<*^``1 zvc(-hc*epB<~zo34XyrT+M%6qfhuDMK7i3o>A}&kdo5@%WpZyuft-3eRd!COg!YjLFT-;J->E7{*5@K8=j+W!=GSZh( zy9`m}#_zmqS$Y(Jz1`!<$L~Z=5x;zTS=H!Nj_IM^NlAY>kLdS7E>#~XVAlM4 zY)@-P1J+qQcK(NOwFE+R$ZPVk7jD}%*)yRU%TQao8-WoiS)KZH`dGqthrH3}dv`~& zPv^3hNTS&zW%PSw^31sqvM>DaWI3@BC77%H-#x-a^dO^{`=K^c6PfUPYd{T|Yxhzj z!71WS?7qi&AAl}bT>(aNK~n$$$Q3-%1QYNMz|K-){k}TmQ+XnYV}ZQp+W`AJO!>Y% z8@L{%V|G6zwMGD}!OBi3egF&G6&+qe+ZrxVHM;|bL*`} z@!KZA2lXmH!waDRY7h)4=p>|=`||bTj_ctOTefq1S>pRrQ zQlb7+8lH9K!_JcA47F&%3eZ#jz?$x!jtLcyNY#WdK7W=OujJJUu|jSI*3l^Ryy*Zz zfCV^x0Hjy>=FAEybAd?zq03@Vw#QpcVU&yAAv32v^xcyg6GBy~@Z^x*;Qwq}qQQ|lwji>S573FnZXIfy;3n9Y&J*Kx(uNKZEDVm4> z6n!nS8nyY^>DPw%v=vq7ar}Xr`)Xb6;%Kcx9fR0w9Jz+V{9jwiNPvr^$FG{x<>h5d zBz|@vLc&c{O)-@&L+Otw&^ZE3-8*oNLUhi@)0Or^9gPSj!ktcdU#yS|8Poj5bJboW zF$}EX(Brb^&|xH2$$jzhzPImyP5gs@qf@>bW9EwE{0SI>k=c`^cp{9jci62*kqyi(lW5TsZ$0UklDlwde3_iZ7Ubb?9Coe;lu%<+oDw*$8n zm~TcrXa@^qs&!R%X)26(h{b0GVFkJAQ3yv~>KT=I>z@}3 zx5^)Oq(66DP`+%Tc3ylT=I@uFXwDY##vq#&O1=jY}bj#RT;hS@C{ zpNqt+X>$4SKLqgVCa%8}DB(oM=7Jb7&L`0z@?Mlpi&Q(-Z4wuqSzDaBR)QQck;YQK zK%)auetPUn36f=d&4^ zUobnpyKO98a(&m32KIQ6aah|`1WN_AOxGAN^@lZ<4-j{rx-M}^E!)taw6~kbn;iq+ zUACB?boF>`S?btc`fVXqC!S#UWFCVxn|^e z48NXV(QJ6`*11kkbWpv1VWX^io?;brxPw(10&`75=_+(;|EB8Xdxm$K_(mZ&2yvTp z=aQR>&W{8llvO;(+EOK3%ICKrgT7#*N%ji#;lUMdJWdJ|NOg&TKO9xsLA3Q36_@*I z*8Sba6nkGGmzIFAZRUc_y+oy@Xxh!P5Zu1kc%^K8x1~O_2>n(_y}WJ%d7PkKgwo zTXut5l-+xV>(O?b#oWEw%i(*=s>GfznBS_EZ<|*R_GpjTj{M_$bktIthvzZQ1qe;v zh9}EY2E|XaOP=z*RCZLrqr1F~p4974`puN`(HY&eE%JMSdu#t~U#-k1zMBoRN#!-b z9s6jVyQRI}US#k>ao;(f7%fVb4nIaTAvWO4UvLkn{-ZQ;vWs0MH_W#9lPfLU^bCB>ssW_%%^!xiVhh9 zkBt5jiB*Um>k=Pwd%rhWq)qBSUviq43e5YGjMWh-Vd!pNP3@A4tpVx=FTE|!a8O&) z_{3g=a;?}|IrWSsJukx#EDhr^p`|wPpO1RMU=iEK{w+C+uHoR-a+%O>P`L!MShzpE z#|b^(a6z)l8&z(W@wi)SPF19hmxY^j^Di(X9JZTRO>2HM-8d8n2$GAY7x*9R^#caf zFJI^UTIpK;`uLsrHQXHUbL)pb5gQ-t%wKmeUaX_G)GcPB8Z@rupAblflHr$X>CDB= zYK#-otA9OvZ-P+nay=CK;(9f2#38nVoE1ARwBS36r4WAzch@ zA_vhQ@X@@v5b935$(q7opn)#Jv@}B%lND;Zi5F*17M?>s>{V3O@@(KZ&bhEPP!H%G zIYDI!kV>d^4=6%OuH02iijyY3fZgZHaN*^erwTttZciR2f>QczOcu-ASBq7_y7dHZ z#!B2(L#I#raPUwYg`_yPGA(ISHW3lhZ8l%x5woNL9cRm9_Zy-z_uc1{fAzKJm$^WH zMbV+D1fN?+)*tWFTua`|nd&0QHf4$G?D9??JGzq@Q7Y+i$#vg$aOV>AyHIb?5n&3$ zx&4pDcl%CW{7!(Rnp;-A!5ZwDov{UDZtKjAf$e!ir#NLgZ#e>Yo6q}FkU|U-2ZK{7 z?!YhEmPu)s|1-5fer`u*@PAi8&2){5iqh?vkQa5y0k&X;j$(Da8Gd^YBog*-(iHv3 zva-JUju|sSdi}brb~1`L!&Sa*PzM<{4b^dx;&r zfc-Dj->k}Zz);#KnZ2ws53AvCsqDvFU&p7;wM#|B==pnz`A@24#FXvW-I9&Jy-{}* zsoR}r`+0qxH|_k6sru(*|82lRjr2QO359f)Xwxs^WpT?@TdS>M!$L-cmD4`&5XTb;U=LmB2RK(}ym@!wc8 z=-NfJC0;1oz=u?^?cABpniis7yKMAh2@k_lB1|mI_WIrFb3;qUlNH+4tc8Ljk<&-> z+7K^e$SDnO>PYNP^^7=9L{qHBvGbop6-OK`dT|GSZ@KM&5ifE)62Dw~A*K{MdR{=E zS?cfs_Cnw9(4)qw&>tVLKF_BT8*7+SfLp;`nb&e(CT+74Kt{CYn5BFqlN8GIuvF2g z9M*r*PLZG?Rzc@gDRIOUXIJYUqgT6icBsz^{M1cqL~0=Li$>zVvP}cZry+CyIeM%$ zhiF{8#a#ytoR~7%;6~T)#TGC+a1gu>KMHhRO{4x~{AQ{>u$*~AjFP*Ss*eWY{rL1$px`h90NZ^Uh&(V>lvdv+zLo*53<%*H5@z&j5@E%m|l< zj(19|bI= zAGXV3o8S?Y-bx=gql4N}%v_x!v#3+A*)=_%0#7v(a=Ncg@7@3*#Ya6fZb9lo>)smaFyi$6?8 zUvI%fhFdBE^oMlhB@5yD&f&h1p{4cbDbQ_ z+>1bnMdv=Wx9569Wx}4Z6lT#gr`CFVSiY10wSDXFf}zBA0BUdHZvZ;mi716x;uaPG zj>OczR^_aP1|oUGcKgz#_JFgcLMD)vBK%iL*&udM;G zQT%(e3%(~ccslqqPzNG}dNf#Hx$Ru+$cKLB&Un{!;X5sftz>?Cto-asm80ao*k2B2 zi+LQa^$_M+d>`RA^D>TrfmU_H!oOZR0xMra$;fq5J~w zTtnp~uJCGzr{4@RnwBa(;8>s-Z%p!Fasq^5Z;fyXteF{vILFax*eGc8sz=qbV$yW9 z%x#yE>A3z1(23ulidp4_EvLo9bw> z$#@x1gEAr$>UPZjhx3ri1#~jHBBAkdrZ#_qi)dVR9yI6XQVKN2ES#WfcCG};y9He6 z!WBMhf^;x{fY)1ebdDD+TLjiy`W|Zf-PJ#&3PrcL_Sk+khalXZe0go>%5+@&$n*w> zlemlSY;q8P2d%uWPd=*5&g|e0ZSU;i;z)cSzRCD^9?ZXIB)Z6CWLBUuXd8(hV3U@X z)>Z6|Kp{#WC~n4j<#u9}p0mPow0p8K8#5S~hIzBu~8f@Y|051Em6MA@v7T zrPh}s6j&1Nnl$4yor~8WfT6e#H&~c`X@cJEga;$^S4~UeYzE{Z2?h7o|^J*@oid>Xx2HV=LdA7KU8%X`3Y|R zO5dPYbiZ}Jx@26JrG~YsafssoYWz(4MECnT_=6 z@?)S*TgNx`xvCvXMI?j$9i(6(-MYXUl;7@^zh>Oqw}*f2fjvW;98+>)0868HDq+?O z{U5L0M-isH66u_MdPDH|S8R6z4i`xggPCa~JnTnieGSmDwV?EU!VlQ|!-K9AUL-0bKDd)_UHK z#>`kpuxK%K~$-FW>@mTe%f_*I89ZOYExSp3q^QZ|ld%eLq$Px6fF z-ooK|%%IO>1lVMt zd&+6T>n zT*{5^Ag?V4^cqWfsg7@cnqCW38X6G{fGx_lARbxfVEX5%*@kjM5xWi9^m5}=%`^cc z4@-*MLo@b2C$_9U=$Dh(b&sWNR0w}sEAzv*LUEVgn3)CgPtp!|1S2 z1syybZKnb0)*<5!+P8nd`qye1%k#Vdi=d-^%5qtH$kiTWJWXtJSwKy$A11alKv8cL zs>^*HUBP9Q1a2_%IiT2a-}3ycw&j0}+MUwGpw zwM(nkOPMqp1b!VPv?)O)I=rW^MqwLPH1NUI z8==8s$-ZZ#3g7zl8I7NjPyd`Cd{8AR#7d?1_rm$D58bz`4_rayltzT;Uuin9B*MibISH=wcF5O-We`8>2k@Ki3SozZ`z81d}-a1sRmErM>r1Xja zl=q<1yM1|@c{iGeC~!vfEFJSi?AcLBkzOvL@CqEzAJ;eH0^z8aW zxW1l|`tCa@KqS*yg=2R4ILjA=R(_G{=y`2deIOF@^_lXEqsW_&+XRXgMYQ%(VF>?b zOydi~5RUClz*)EF32y4Q)33#qJhU5@!Df(HK^ZymT`O@HdeEhZ?B?hBy?C{Tl{o7< z;|08~ft}WKf5tUdCDRbBupvy;dt1gfbZ8ArU`My_EyZGn`)UK=0wmRvl_1 zo!nC3vwg2-%vP@FbM-50d1)sgl&HedCCnowsi0Z>J z(j@Q?<3Buwd$yuhyyd?@!CC<1XrVgAwD%sPtE_Bz9Xvt2lKWwmC28m7G`^L_rxLe@ z{g7MUt~fL&BKZ%6O@1Ve4l`Yd2_A9HWPA(&R%nQmb|nedP23_R-py~x)x}{cAlQLv z$em1b6rj%1j|nM+g@#v+OpEMoR`g*;3+O`>+ zPmmTy>t}`i5(;*uZjOp`mbvY6zjx=|f(&O=zrLI8DJnTkO;&Ryv^loBgarQ{hDZY| z5N84;QCUs{lDS62v1SCKN8pAV>Gw}GmFEoTKPTfv57^s%4&UL1(?TwamhomW5-&Y| z`qp^GH)7Nkp3`!ep9tqteP$~!nU0ad1?+Fv^=@EGsa{pfFe9>+rSyN~>7gkSJMqYa z-H#R;AA1Y5U1=4kdtkV>B`Lv%+h z9Ig_a9J&AJh{`%dE`Yqwcaa_>#eFV0r$y5hz}7WmB+kA_6QC|GCCc|z>)WPHl${?| zRDkcrotk1(3GNDM<6?cgR0~*)=`LS97>2ilWoW7$t2O_O-@$@|GJsX3Xp*-62P~XG z)e0Q@N=3QAc7$Wrm~QYa196_o-FyV=)Sk3Ktn%l*!yLgy^zE-!6*M@k;%pwp8|}>2 zq}@!_b!qC!-cSEv1r%tds#Qw*wS81K=hc*)_c zN2tYbVvV?ip7iN)?W$rVfz4KYXwKHUq(N`-{_9fvg+~7)V^QwyIOHQ?YK40MwR*q z3x(;DnXI~^|M{*uxI*iO@(+Aq5*K_)JFpdt`&j_(U-=DLHadEG8Rll&uTR6ib1ooe zOP}Ja{xXy{59}$J*Qb>Q1_1q`pYlIia*(<>P!4FWltJN`?~w@_y1~eb?m) zvWA&@U6DKQ2bkW+NNHUt%V+lX9Nb>Wu#X9?Q@o8L2c@vX`kLDC<=4j}IGo~;V~mG% zW`Pz)%o-pe3=EiPScC}`2hl{QZT8aOUy}yuB@;9D5nOE|pcZ|UTQMU>o-_USg6ADB z(Q|t0aXV^lYF*#JV$$y6i0j@jSGHa0N0FOY+eAEHMB)4aq@$Y0%&3k6_mN6E?>k=| zw!mYm0!d!@8OZ2!RMwaTQLwRy%T&LBghXU!=Kj|6^GQ6SDRrPPFsGT73`T^?& zy)*Q9PJ;%*hY7$KYa*LSjMZPF?utP@d)499ihU- z5!U(yfQ_f;X+kPd2ID7KU76#Zt7lU>OO?m#88|!i3^Tg*=Jf>;;02eb0Q^m>9LFoP zPtCQ%IKl26y4w9Ty}I|zdw~IkFf)KSxK7&<-8-2$n7bl^douB;@Z99Eo(%=BzQ6Hw zyuvm%B?}slN3ZMXv@c>mKln^jidTM$iY6VV09bkJ=cIMhTKZg7YtrR^!M{;9LNY|` zlXs#Nl%r|l!nX!gkRc}ehiohIjf=Uv;(DWL1sMu}57ka5=Vh_U+lv=<-*TW$6Gp(>`svG_ADRCkbD%(Wqe0jZ-n7`rn|sPHT6RY|TbJox%{G6pRi^ z5(kB_f-EA3cgBvSY|!~DVzHum9%)!;2~ASz6jFK4=hxYwO!y}l+fs1gr@;H!_uL{z$czp*^&E7c1t@@ zj{Fd>fvV1fDIBm0^BA#B1>z_4jLp}r>OLIi zn)I`;sO0VBop?^uK3dI#X{9wO^uN@J=uFlKq%hSI0qP>AK_U)*t=8&u)0lpp23Os{3d`xtKuJTmya436I;V7 zL1qo^-lKfcvh)aY>cQ`}mGqEhkSFbl&9qQfTT4t~O=1tK(#B4N%xnR@?dgVwb{2jz zH8TGl_Tg<&vMbTszgFEx`Xa3r#Jf2ei-QiQ{-PLgl#O#E|M*1cxpakt@_80esLIRSK=SK{J}-7JvCv2yT#v-Pl%+N1`hJ@U#s2-q z@Ci!j;}C$s8=i8no@sYo(IwMcTq7#Yp^t=yGia} z=`7tk6D0{`96{y(!Qx5w_ysGRoSClJlp)nCe$yav1YFtExAh1WK^kl<;@lW3T`oWT zs%r3epB3$M`OZR1zGko%arn=f6G_n{xi2?+KI{Z0L`ZY9H{2NZ%qM3S+WuyuWWii$ z%qla=b^O($yimaB%$RenpF#@B=2ec{@mC0j1ugk*3L0w|e=bWbdvBJa zvDhtDn2mT_>8h&WU!D?m6{iVvrsKP@8|zrX+MA}%jJm;2j6Z(Bd(o$1q&5{BD0*P^ zd4S3Vrj{AHMBnse9T|Y7Vu?`5P8W6hO(Y0>q4)9qP1nl&y;+xz3N1@6YjlYb;p^ie z?wx|CwfLWGN=m+RpW|V*0a%@sPDeo=QSd7 zrr{2!DIXw|i!+G>QI-@$xSe!M$l?KN=!|keihEfle1*CAUW1T~Is&$%OaP5;*mhrPGaz~+v2%U;hvqOkPzD`D}>9I^-=oF1K=El zyDLNp%R9#OAiy{ta~@Ok7WuVKnS?f?3(JHw zgb|-A_>KcdBW5x~%Ua|}sPjmnQ&R=>lYmCOfSm_Ki@CYh|I0>+ zqbO5|ib*ioU@K!m5Q_MF88fn2(E3tgCS|XimTY|#!5ZrL?6CI)M>G-idj4tD*~vXY zy-{AxEc*)+xoYqhx=j#nNR;EbZn$py^b`21)Jc%tKu0ami!`bGM(N#yh5MlX(qouM zo$10D-$`7%?kiHa#e4fx{(_G7n6j@1jKN`@j0cj8ZA-;AzbzHS8oC>b$4KxOn%*9` zug#FW%@ZhBHRln%#-|?j+a*}|Ix4Q_+=zAx!4h@&v(YSMP|^Smi#YNVOq0M&5Jo0zOXvm!GiOK&kM+&M*juD^PYPq zG|7Wi)giEFl;OR!F8)Ne;pk1EJH}GJLCM!;NWEgWq`xfM(*DG#w_l(c zzbD}laOA#P=aGO;Pvponu*@r++#aL=4x%(u*CI~R0y9X%Uf@R8 zb-Ekln!;fge}1@B3t_g|;bUx`q43!GWbOo%127@}T$Edr^>%&XH+@vIjdrEOmBS`Uys zhUPEhFIfK&?oK9jJno+`BsR@#9!V-mi?MMHgXRqJaz7+*;q$dglBv5Ca@z>w(hvB5 zZc80KjUq@ehpnSyW6l_(SfehLq<4pX!Qa9>A||9=Z#;9ASw_*$HH~H0q5DcEFJq7j zN#I8UhQ3B>2LA<4T*Q=?_c?>6#zi(E$WZO9C_Yo;F-g@V;er5BEU%eGFhLxh!fRFr zV2%9#UMh_>X-%P3nIb$Gpe}iObyM)?7Esz#oOQGt{2fK~Z}l@VkK$8QnwJR__C7e7 z9CG9H60|w~;TIq%Es!NPc+c_7>DzNT6heTz!$|;z)sbr00uaznXrqs`U?wj=i)Ej4 zhF5ZtiNiU}VzIVRGhfIG5j=2Li!=)-c5-7+D#d-#$ike_)t7~6PDwRT z+jv}f@x>&nK&V#@H5yw>#eI^t!$`Ilj<+F4VTFGS2 zwyR)Jxb>sGN8S45+s;BFOy#gg;%`;uI0faRcZRb)iCqzTx8tfE!^Aov!9c?n9_=b0 z!6#fqTHWMCT9Mx2&iif(PwKqFpm*_mk&_du$f8h-;b9OEo6gxH0 zsf*5~nU=!aR4wJ$kt(T8x~8?Qg}LI7-W+e>c2qd!fB?}omlfa&hkp0XK}t~OOUYAJ z;Q`abOYnv-vvuJkrL8QX+{^idaarVE^gG}jCV)C_9qxjTh4L54??hox&Y-Q)SuodD zA;!u!kn_%dYcN46$3CH&ozbYq%CxWww_WwpvzsW>Dc|12)g6lb_P)^RW8nQ^Hm2pk zF8-r<$T?rt2U^m9U%US+mI?qUZVklHm)5Dy=`a{QgrT=OkB4a0@}v-t6ZM=!DoA&> z%zEv-X5D&yr*(E?YiVqd`GzZ65;P1tI&_i0LvGpeyA4F%g1L<_-DjlTP2Ss8Q8MHJ zTk+oYvQbkIYy>3#GOA8PC-iA8>^j+q$F<4CB8pM>;*xTb^VS62(3o0#8;uAg<9R87 zsXgiE1otZAv1;UPN_GZb?(~rTIMGgG2p~O-^U{4d$BjbmTYv=~KIBanS%5rxB`dAs}^mq0(Gn9yUj0@EtYlu7J%u zlpNZ`K}yO0A)Rkmcm$V^js9m9ru2ScO(1RgxnP!c6xX+H*+8vLE!xjC1T6*1EKFDV z;=TRp&xBRU%>giAu%>@jXaRKm!k+(yk)AGpu(&#MmCRrE00YT`)7Ib)0o$WFJR59t z)nV;n2+4I~F}5=)@{>gkqfn3>5G>dGydo)X=h=^7%*eX?m?H6tho6Kz4f424uK=Kh zO#eFI5+lqb{lJX_Bov`+#}7-iDVZJhKaLVr{#JDBtikXdv)>T2NBH3G9x%)`hY zi!^20qvgaNm%e0aF{$lZ)%3qN|5;&ocX^)Cki@kpl3vKw?|e}kM+PiY#z)bQzjoC;K0%N(kvG}|x}7^{{kK4QEf z)(QC5i{BZ~ewJUo;M_iR6;yyRfYlNY5c5Lf{ifqYYx4G4s~SsoWJ}iQ z=CkVAEJH=FUI4^}MNEqtg5l>_D55Z4< zlX~WIm9=a?UuadvXS0ykAQL}aJztmr42wwI^o%*j6^Fye{(L89oPPI|hzSoG6J(!` z#iSrJM{8gtq~hh;btB%NX`xP&)UH;y5k6J_dIT{pG~aT2q}CeZ;`tI7=@PZ4y$T+i z?ksUwS-f$9@lyWkW*%JzTNiDT6NC+dO12wvAPFb|Jne0nfBmS zQ&j_P+sV~Lpv#P}kNKs|9n!l!0bE3ZSi+A(RPQdrvSWOcJwArtsO6kV0Wi)@QP18i zm{>JhW(P+Z;zt-FBZ;mDHUrTa*d|`Ce_$PdmF4VoN9E{|^Y>@p65{*Oi)nv%ANnf- z>FlHBlO_c0Z=SMmg-j?P$T2)q8k#zq2~zz_4`O(FNa~8a9XFMcHPIy)|EJ?s)iu@n z2Ox6m@i1V8j-#XdZ{~cq^hU&2TGxHpo48^xy`LDudVZ~OEPT`%y-R(oac@~f=PTWl z3CC#ITLYR@gFs60D5M8gBKbI6klbc9uwh52W~*rv;=OVkOT>z4cgqT)MIinUfy)@x zZEwF+6XOlcq~PO?(F~AgOy#qMJU^6*;gJ#d?HV$@8d1etnR5M95`yP6pbqKe^YM+s z?_-#wL(iyv!Ee1|qN9WvKh-AGT$Ki26hGU0=K9LjH&l{iM_VDeojy$9N-B_g_gdVQ zL-L~XJQqp%O<4*PAkgoX^auk~zH2X$c+d+jBflPDqX{phPks>~NyszUiK)JoX<}6rHNtXYl_1ig>>cMPG&NS3#CFR+&JyR+E(Zpub{!K3(prf1e{YH}epyQOv<`E^_ zS0lD1KA&!LJgZVr$110VWcC6h{{M^7u+4O#3Nk3THuf9#v*B(L#S0m5*nMpeZ9<3hiUBZhQ0^2Ti8EQcZt%|N9T$%+{GM&6%TN#v1*F^oON`*0dTZ! zS9zmlMyQ&lWA?B2LvkLg6`A`#>BkjpxeOV&guXr{yP8ZL+JsM_bUgmT+;JcI{Py;n ztBAzI~_+> zHb}FvlpLdeHxD*DzrRx1fJ@~Bp>lU1D$#dsK8bu7ac-)D${w=Y z=YpcnGmUMU6%aM@!nKlz(mJpuv(WCxcjWQLr$$v5K#hjR>@Y?(XEQfcudX$;i*e3?NGzfeIS9 z-dY)bqpZ|D<)t{TOV#(^dKiNO)%sm>Dh$*cBPvL)FF!Q&JQ^Gbzl06Bto3o}n09O< z-fu?=jVDqHS-rN`%ehxRcNI@vuSE`A{uS2T(XHe1HdIx{_CE)V_bUmv{n(33+U17I zk6p&zJ|o?!$wo4^pbdkO>c3iSdadFZh3ba9+6+HBUh410g4MFdWLiM6U&gvR$3z^6 z#OyK^9hQEc9lnz35tsFjSev9fkY+-$8eG|H@%a~g065y7M^s*^U56Q6db>2V;R>ZHe9|53epH4ewp36PU}2QZH8u%1 z&2sg0&Rz7F#pk1NU4NTVz2fT^8^q=r2Wpy=Xa3;b8a`# zUC!G#Zz{i)sv?RFeY@USpo-C+(Z0?|71O(6tSzFe_s zr!^V=4&eHK@5Gi3uf;6q<_5X}RpBdbo+dlf_qZk$$zoWy!XXGV`ml>@A*uR-;E`=-%P`G6f zE+N+bOx>8|6c({10bv@ZM0Vy#=6eakmaa}G!qIniL=N(CF5Ca8Pm;!EAVZlLB_Jy>oku7jE@zU968aQWKvI?-qQ+_f=civi zy7#PXJ08|m5ygIL?5YG{?d3kl+Z%J|VEZ94)s%`GZ!M3qX~5z9wdyki%@(f1P9ThR ziNcnG=Y}o-JW9Eggu^F2~zymt_t5 z%Qi}jLljVPn`!Q7tVSI=}UH#{|9*b--mK;Zf@; zL&MI<`24;52;*DnCvk^FLLKHjDeRy1@&|)6ieWS@M>Yj?&+s)JEr_*ni5eex*ZO5T zc&SZrlmSG@-_3UFrZiR!dZJ2iYC)@k7{w&$V`9E#D5&S+dN`@6=uxF(B5u`4IWFWm zIGHAhJeg{5VXi3+6|&??|0Nxr88Qk8WaAU$I8ZR7W|6pQTw)Ilpg?D?IAo>vH&I|! zRp`L0?5uOuZ`yr~n|5<+3YcPIpdhZoQ=IcDHv*~acA18M@7f~kW5G}mKR!jJ=J7O8 z46E1SRlnqher>@HE1F2vlgp}*a;}Bh19A&!G0a1PXqn{buh0QzkH=oxh(y*$X_XfL zz$TB1@ilO$O|p&TiM)x)@w+4I-3b^HS=YV>AVde2;vC^I6b~3we^nqD$XIO)Zb&B9 z34cNJsfQ=S8bk8`Q1#YtQHAgN_6!3FCou`2(cp3kY}p-N{I;gWDC}x;c?wi3A^M z&)?h2W|D8sLY!FW6S{UUi44o8sK?1A{nCMo2w}SOLZa3U&qO)Xs~(xlK&hYc)P=nB z>WM@3q1V+-e)TuD893Ja*@*k_aPI%+7ztSZzv%NLG!Zqqt*vcNn{{U-zPVx1Y*F@j zu-2^p2QT$r;{4#ZFvY1#+KMR92$0^Ri%sz(Wc{^?&veSuiIXnF4^xd z0*Z@OSj8qGz)k%n4u+1#YhUP12mksE*_|?tp$R}7@?;ZaNJd1qE@-GD^xPf#z(^AlDY?3LsR@fH!c~u8k$``%qsG6k-Im^FHY zAIH$W?(4h46`JwAw}BqQGD7b=nTr~xq#@d+mvu3hpaE>IrZy8HOo*@iq6s+*Ns*bb z@&1t`Shhq`Qj#w0B$7Tv2ZO<8cWkFK=|~uw(li3F2kd{CuYC=-Tf!P<|JIxV=mV(W zU*`p;yjB>%i#rEmILorjIYjYrnhHgKi4)Qs_39?&AMf$pC=O0xHxB!hpagwR6kZXv zPn{rPK7V8O)42Q4a23IYaMA9b+8?}&PoRgrLC%yt6(0>4FCQPe*trr({(Jf2vH67< z7vSgo3#xY2eZ1+Gq9VNiW-6;IG&_yG-=_K>5W>|&i|co>Y}tFG)5fRD30bfBvkl!K zZB=OYBPJ^9tIpH0j>046+dn%VRfl_vgv=o|DzA9I6fMaX=YE^-vBpH;)9)mZxtsi6JgAxSGqhO#{bp%c~(2w!~W=F3*7;?kzRG!)~#aCr|%= z=NvsDzsKvI#sh4T$6z5l!V$C~PZ<1|)P#{4J@_#^6>pzXFe*ttPvomoA*fJ=ff1usBt!b+IyFSF_l(#57CZ-P3xl?sahyM)OQa``RjwLnGuehiWS55imSeR>y z%ToPt1nWi1#CW`OMvOS>Hrr zzA@lQb6zj=D{&5&#B2fMv9IUn$NPrneM$be!8qd!s+=2OjGT`xCh2JNu%L`?G<$@a z@}Rq=|75RRN9cr?)uK26x!0q2SQ^5KT;2QZViL#%<-&j;s5A6Y)?mH78I`n87*l&`X8fp`>m$c>A^B_0J8S0Q zLHkc|tmqvBMoJ3L{A#KK>z!N(m8siHxWLxG9_3xe`fgpPk$}wY#P{e#Pyp?Ph@RAmJxm-joBO;yqvoe zm?Ef!Nlt#LHTnufmw@GL(h-8H!SLCN^%QQ>(V8$^Fe z$tck$|BmUUMQgml0t=7X0-A8*5ZW2317Q-|mau8UBw&prHu?q*J?-qO&<3)se@jU! zka;^hX80$`TyIW*DLegyO8fJe^_t25PD$;{sFDWSMo)f@4ajmG>4MKFA)03FTVD27InLcJ_9DYI<(5Bp-`FCv)LhhLD(s#VvVOZP{gU=4H)~%P6IW<>|?rZ~UJ6o%+ z)?crf0oE{LVDjYHgBTHBkKRX~(m!*2+wcCU)$s$Kz2TW3aQyZ+H?&D>T!(CH$VOuh zCj5lKuuk*w1V3u)N2~F^twk!2s|Z}-zM%LCn&?J2sZOoq4?B1JuMUP{rvnjpjtH`GE!{mTyh@65zg@7Qiwvm`|< ziI~3HOm72}q=Zb|wWD8&Bh%;aHn1A*v-0X$)Pb}G>X2_KH4v=nXWU~=S}>h1J7J!F z3`N`rEQW0>UYbWE{a3yp=nNCDHf0|e7+76-rUiSnBc0RtT?xk3211;$xB)3rkqnm{ z=A+pG3+ryv{SN(D;AI0M{~Oz`~q zvxEPu{GpAf6;?7aF#$7pMiMiNRVWY~qznjIjb4q0DOgk$v)youoshaot$B82`^pyO zhHTDkP8I{H)@PLPLu@r8LKz9~Hgp|$(v4RXFvws~vqCf9QM}TK-FNA&iMuCV*?yxl zEk<2o2y?4+vX#F(flq5lW>R->8eCMdSf_9vj);V?w`$ldjgo^SQ-PgUYld4U-c4 zS}{U1@h>PHUFYi`gltc7y}kiob+>3=cU5aI{;PdW&-@~d@V=$?s#e4u3B6IH9K8~@ zR5?zQW)eLa>92rRm?9DdzwwgHuh=}`JmY9txxQ9yIhey>DcM2%9nc&Orq|2Oe=)V` zh^tRH-#8#D6;jp_CuxnsBEeZ3_X^p=J+IwwRU62c+JLp#bcc0Qr~yBrdUi_5@BCCw z1??p#E0?(Sd`_>uGeQgN9e&IQ9(#4y0a+m?R2s+tt8}f&hjta#U(CLncWRXVmLWg_ z^~;SdoN<3U!gQv@W@5o_m$vW~gskX_5h zO~6JBJK>cJ#)h{D>x0a{NMT=b;HpgY;@xLU%#2ly4e!t@xOmA zC!d5VB`|QIjmx4HYb=e~YnM^e^`C<9{j}t1Qr}3pE<3RB=7=b-onlXh+0qZ#_|pT> za6Uq^WpL)Do_We;^DNeeP6uqV>Eqquqi0||1L~DjvqA#j8b2EIee%FmRCc*EY-L@W zJBQ9L-#L9~p49vpG>p-(r8fAa)l__mO>0`kPWzOvx>E9F|b5Uwb^|D~i0Kf8(k;iw0G@ zalO15(afw;*PE$>DDq223P*l5SZ8edJE5v8ElX@hxCr_Du{28nj$vjqsBBt%FCPFW zLtE!AP*p*EGpd)wt45N)sD+WbQ_{Jy5SILL0|o2-9)nW&Ao`9J^9&H~93AlZ*nG9;o}eA_EL1x`BIFT~Ld_+eV$ReKrq zxXQ4ryE@Kx?HH{syYv~cl` zp$$xrW|sX==BS}BJI^D<@Sh`lA;+3W$FA<|Lf9D!-ApfJW3?=6TmCCb25MaDTMF-F z&8GjbeOvnR%>=YH9)=rw9z)K)1fw>xFM0_YO-(dypUwj4gEXp>KbXc@rbszRq=~4+ zdHU~0VI063q89XY@0Zqd==F1-G4=h{1;N169!J31UziIR;B7XL&1-UknQdI^e4ygo zu|MCfLshvVQGpSnT=T5DKhI@WUzP(X-7lS#MEtxnbkj5t2jil^*N|QS``pNh{hS02 z>&D4sJdBFVMglM(@?E?$5nV>4hec+$?>|ZKLrDCk-j}%qrS5xkKXGo^9F)uRETzW~ zpp8?cM!g;0F_CQ74&6Gc=lDU5@89ma;*0I)9b(EkCR7C{QV`nkZWBe?|B0KsZbd^x z0MGFL=w&fil)mqjYA1b-^=zDBhuh|~w)xQEo5Gh4hL8{S-sUJKURZLc6{BtmQBi2G z#jRZmYr(g*LaB_|=RM#hdN&;w*T@2O$NjX}TveC8y{MLLroFm(#*N;>VFmv_g! z`bqoh?s?D(wWg?pL>QE>Hpp0Q;j8t@^YYRTYFX>1Vx=d@eqmf{7YjYQ0;mL|r^e9* zAA8OVV+qw99;jXGKW{N3P)%p6_)2{hbJx2;Z~(Gik%9G+tI-&bxrK+i)^bByPe9t!cVyP2}vIv(qnFiP~Kd?Y1x}23%K^}RG6@^sB z<^9{cRdhy76rI0a1H)$l{krT`dYB?l&xa?0AJnCF$nx~YRU=f7)Qlm{{lC66PCn7~ zbXyaUP_M*Ngyj$(=(QHi!S&DVZ^-UM=Sh2%fNyrCh*^7>{ zCdHrgScY-=g%nnGvOIH7JMG|%aO_A;+-0eEJ|bPLe=_!hm)4a0zP|qx`{hLG$jLzH za(?0~p<2s7gLZJ!`Mb2M{fffm+Ipvqw|`%I;_)LdV;@};%Di>Ei49ZaqlQGKc;Q0v zFYOGnOH#BdY}EzCJ#;I%=4~r4qQag+m2?uv&s4^O=dShMGaojx>MGkGNFHPyMti@h zrjPngL}Ju|4P7wc@f_yONAV*`hIQeoqN8*en>W4(4}5|ZmHn@nPb+y_yDy3qc-%cu zqQpkFSPsWX=#<&6nS&WLY-emv={vm{!WKYPpZ^8AQ?Go3UngnFx%0XM{M@R3+XHjA zQM|c$1>;s|9B8c`yPuQEaZTMk5D+szqZ@Sn@4@<~DngRufx>XB{5zW!lbYJ}O3^ft z)Y%bTB7a~tD1dhOW(%HF*8Iz?b*gFtw{A9$m0?6;+n?xySMDl=bjfcoKwn2kh+x;3 zS&B>gmN|7N@x5N*U@n`OAevjVt$+Tu8%>tLm-oph*EX&#_{OR7pS1h&$@R^RNyVaw zZTeN&XeuXt8a-7)+LY2hf40(C6}V4g36C;*F>$an{8jY@tg~}sYfpMiNC~eUzFWfRuBvT5AJdMy4c10@2-7Fb<<&5tWsMI;FGoYVFWK1 zxvJuW5!Twmqqht^hol_Sx1=82sOH!Mulnt3EP@Pt`1wq24$b!38 zPt^XYx0l#emc-}Byca(<7_doNqK&YKxPXU$+QL;n1p<)5a(MSq<)f$bdOGbL&R$dRN0)=2C)bbUtg zHr-`PG53NDrWqS=X`q(Ha@MYW_Itj26WL96TiyZVVm-`@CBz$?hy;elo+RHkBD_GM z|2J!JV3^Dj8kDNlmFB0^Wa8!#E&|z)jw0AOAe<)&X+5-WMg^b>PTX2FYjW!R867)$ z&{|-6)6vNctZ6)EO*%6YJb`^md1SCf(ZoV=OVv78nO+8L>D2H@0#-BuowzX;ccj_C z;O*jUF+`c?pE+yOo(`-)P0aO<1gR;NmhG;;fS}5^XRqET2HD@}%5oI(AZR}f)*MFl z3$7`7_JFrA7fM;Ea7kVpl%G9GN+4__kdB&S^yTU{v&RDiq9vyMH7#ym&6#;tT(_vU z{N!9qyxFMLX-@zVRq|TG6>%V?PkFTzoesCsf`qD)6rD7>Mld+{Yw7Czz?iv}N}_%& zgtu!?gfiLUF-H#n(irF0o3yuiYXLo&{~WXb`l;N$$_!W+2-Qcn5Jh&zt5Dk=dny4X zWjq|=8TxM^%cZJyOe;n?S%pc?Qybr&#gR=mbVde!-$Bud# z176n~B4aEHYx|>}JRqNlf`72k5#keg*&+oJ)MUjpRU9$^MbEMGiRo9M$2{iZ-lle) z85GDGs9n(O{qa-xb?0ACIEr#FFxsBmFUZdOxF7y7Zmicjn{%Gs$G>OATHH}BWZzpD zmc{=teHx*st@_m_7Wy;Ai-?AeQD)y5Vp7{l<5>(uaukQTG42pW19~Q0H=4&&J8`qA zZ))YBO40Vu`4#Ef4$f-q>>uRB-Bx_Y{k<4MIF=*nN&`{1r1|e;YqP`^Eo3iCHRj$0 z1R^a0PO~}78r2FTW%ST~>C*qV8bqfou_NZT_Uz$-PJ+|P!67LEThv2yalIzYyLQpA z$!f2(!oLJsCVi!*2^ zImeW#AH;=1DM}05=OlLki~!)=Zm_cPI4<>scK(UeU(ZQJ>w7B&Iy=r&Ia!X=XLX`L zo+@G2;^K_FXy?J~A^!>E?bG@Xm7~K+wJA#SIsRz@`+7`&L}jx6O1s8Yw5e<~IUnT5ardX-e^QbcV=-uqR|~=EbeN_mUs~&ZXR!PT&tr=u zJ}O`qhY&=B~%HAeUzxb$pHPP7)1f^4xLIT z>_9*C;VQaA20u3cEy0moz5XDE$YJ9Y6r#r?T>k$9!|jpYW!qBW>|3f3*aj=P^s3f=I_V zhxwl+D6@33bpt-WHdNja_Ss^g!e}5J_9qc$D1hMGE-1dH%Y+Ra^^0x^ei%3{^r%J97H14K^MlOiCCq}`)x(!;p(Z;Q}}zC2%FCHD1e`v;k`FT8yF19 zrv~lO*QKudty?=*VwI@ zK`E3v#4cg=Ou3R#yk$Ngp(80bTB)%$cTz4Prgsu`rg@>{-X6o8zUO^zf19ik&6>zi z1*A=Zq=bDHkK@dosdyYI^vixrS8C1Rg+k6fZAfC+VfDy_b6t(&$An=sbL)kWD@Jr1 zBTIa(MkW_lDzhIf5&epiWL)^;b%reT;g*+hGLI~3&}3`LVam8T)fv`$o$S#~Z0WNPU@*G#OdR3?iY<-jl6 zxg_MDoCe{50V-TrG11^Vm<)ptW;$k3YI%&0F(w=E1}Dw);PtL7ag$?`i(84Ro>`^= zU~JCtP(a25Y*YlMLX7YYbV`U_7saqd79iK0zqSR&Mz}~$CI9|Sl&Liy0wDAc;bKuv zO8Ab&0#drfpT_Ui1LAkIqbtSY5;h_@$i_Gz>B=XJy@J^vwO^<9 z!ifs_e@}a^_ZTJX;>m!(2dyc4xs*hm)bnfa?t9{KNfs|OkOoz0nt5sV#GQYN@okd< z@)P}|2!cAAv-eTK|+7tMez#Su0DBc&<&>W&B7D{u zo}|-4MI}?lH9?X3CU2L#F)X!@xTX`9=&IjKs{LgW7dm%4asH6wEi}o4UbMK`fR!WO zv%EnA|4?;ZW@0toZhMap@Bgjj{KLfRG5Rk`xi_#n;Zg8EwRm%q;-cGuk95l%#dT{N zJwc*ki<=bt6a8nX*e^CX%ZflB7Ug7s&O%(V7KLRPJcUA-#X=0{*fsOuN|@h)P35OM z0~B-5pwwKkh=6Ti7Fc@ZMu}QIL>8+L3js7Jz9L*B=yCS*3&ZiEr0V-S!H3`&mBF9R zYy72rdr_-;LM*@z1))DO4xr;rCKzw&Z9(ANqSKgqn5N>`Mja^m)Y9)8Z5FX^4G%!pf)c;xZzDg;YPd%LWt<^R9+8z!N;nrP8j}@6Bh;uK@Lqc z&FG_c^G2e$q#kM%s@rL^*d`6VLqn*)tY2<)v(E{|dz+i)zbp`vcx-~=r-A)m7*YkEfTWMDAyF_GBL|@1RMBiKz|M?FBkogN38~a52%gv2% zwp>V;x36!Ej|k&IGh`KSb-t0@UabH}-&D&apB41PThwKFA0y-imUbT#>l^Y0MGuWt z8qrjoxLOb^L=9vduF0Z8CXzB|Y&5}iix*Gr(Vp~tC3LArT$!}WtiuI>59>|UmiU&+ zxhBflmOJ=uZud*QN7!GQ;fy=GKF*&6mNrBMWc+ky@^{pmGj-Hxv)wxlfFiy)?F6k3 zn^2PV;HH)od2ZwC^|njS2vnA*15rICHZ1Dw?4o7x9&VMEV?lfU-mgll-MkpU-$izY6t6f7_h-9 zrit?HLE*+plUXwp9}4-5PNW8ydfjO>63O8CMD=T#r>`K$4@1k_aBKIiGzM*$*W6ry z+pegQqm&b&(eWR}Bd(;^S0=*zCgeU(rRmtgdA|s@vN1Pzd`fOQ5@aD%$`$`Yx8Sq^ z--~J;w1R_kBR;Bale!?$}lz}{J=Ljx|Ndxo;%mWxP4+w)q zHfy}=^5q#sDkf>|KCWFVz~h?1hIEG?W5uEu)5eq0arRZ`s=axbe_x$0x0$erAw0PR zX{#k{afW-VMesGd5hC!TUlp~Ktz1G<|D>bBnHz@Xq0pdV!sSLuI9B4t80*4`$f@xD zeO&;vhf}_VJkvGt9QI&jc&rIMtJw6+UzjYeJ6ron#{9jmzVNIL*E8>tp7gKq;{s?T z;Dg>Q5>oGCVv-pw-0OR+4N#HEigOP0HXoMwboG0-D|elNI$G%6`k_e_tf~f~1JJi+ zQ9H9g(%5HR==|JkqCh>xdYv5exN*cSb;gktwY03t?BN79DR>V0f>} z!w_GU^Pm&&9>!L1vQs?12*%aXYU8SdaaL?ey0djb*OketckR6!k3tUHeNnw$aXJ!3 zJOX^z^{J*aHo;Xxjkiv7txggqRSvDLMU{#1@9kQhHaSx@3<-x(?6mN|({eg9I_#Ov zr}{n8Q-QD{@P0oObmo4Pe!D77m?+H*|?KWp4J@q4ioO-!l6Y%kkj@f-e5 zCV5X&{GDv50$tA|!OjXK|HbJ?p?41ePTKD^;Oo%JAJNj;`!Kn2YxUe~CvC67j;u^` z+x2E(#f$b9rE<;c24Z_6W;x#P?e5wZ3=|?l>HbIPo#cm(H_Bmq|9J=Dzr4P_ZVLYM zYgd|+PBu?6)^rybondjhrUfH`>u5n-F}4Bz9yOcbe)(6fZDod%fHXV=9zO|#u)z!T z4VkAQ?3T1emorYJ|5ufP%8xnzFkm1bRos5`50J!Q<=-?pSnJU-3g`ki_q7s3LeuoT@XUQ4dlZn7emoxG3gQKAV? zT`$VeOYB{uO7SvFnVh=ilZ4=fcLgywmI)60;d;|fKWlqdI)BVL+Y7WUsAwQw&&70p zqD0bpFqDXeFg8%LeCvtZ*VxGx8j`DNdvHd523RTO$JdSG@xRFtI6nq#+nFa#j7u_N z7m0c#*(VboOB~4x2u+ivl@C6>0i3FgIOr)^jQnA|IwWfn+&~+6Q(`r{%0V&en1R?g$rHd82^Z)&$o6A-I7)c>j_p# z_N|pIp7wG!6AC;tGM713KSOls70R+emn_)(e(Sk6^RN9EF9X3eFNzj8vHmxCWgPN( z{6FMU;`MQ^JNt0I&$k}DaqxwZjE`*^13YGn3g23r^ACFMf+?6 zTVNdNzc8k8tO{QbKZ@C*wFK8q>VX47$cZGmz~vNx+s+1Be)dX8JgbK*+CT|BlKp3NDnW=6fCJGAxI3lj&u!PO~i#jdXvdzT0a@o;wZpN zI#xH45W(ndb0-s>D0c)A+aHf9CxNjprPXy;ejCl^Jo-FKn$ZeAw-rFiF=o^WLCew2 z+NQ2)71OlCf_wZZ5a#@YZBc3?ANvSZJEI`9af%u}DCxwv3^c31Pagr*sL$ydS3`Xs zZH9#_Yd1Q3YLtpkb8%~C{Zr&({lx&4osZtkG@DEI49u7{D|Se_LVq)x(Xv3s4d^Rd zW;MXR>O%pJnI0{itt?Ge)fIkGnmJ$!{k zCromx(8AiGz;#mOX}_6ewA1V5*UVm7lz(B9!mSY1a-+FHObnsnA6g6 zhE%mlcZE9bOwF9GBQP#}X)J6bv* zfFwZi8hC&f2@#<3J3DFrRdOT)ChPCpdqseJGp9fdMzov3n4m*=Mq1{0a3b^-s=mNy3=`eMcz+vvtGzAm%EnhdA` zptNWV(mN`8`UZMw>aAfFefu6ENzmC#VF6(4sMpiZa>mAf^Ywr=I@=T!e|N9N_zF(_wCmApJrz%yWJRDbQmnajKAJ}H61Tl z5*N{zbGtQ|CRc+h1xVlf04CYNV$Figp-=s>7X@uciF&uI5gb?ct}V)r$3Q*)or+=e z0YjwzE&W`opHzApYyEw_3odWGOEO7*o;}r9!z1ga&}9XdFv*vNJP%p|#GXPe`56Y45Y6je-7(>3SR_>*Hqo%Ba0=Wdn)ek^%}W*F+X;+jGHReh~z>Ou^u}XU}PCoA20c|;YIV> z-CCg%+c>KZtAe(lhC0Nb$9SSzoEj>D&p!)k@#!M067tJiNHw;ZFvv(T=gb>xG$Ql~ zGcHT_eH<%ed6Ptnu#L_Y`J_UTK^DayQRc$f;T{aySgjXUbIiD*=uoyuV7h9({MH=~ zgD@^D=JWMQ!Z_y+09msmNXbm5bpbsbFa%&@%jhfXN~ZT?oX&0+^Y*U!^Hbu^7ORod z;0UI-2s%MAylpl@Y*t3?z1lxnpzzYx9B+do-|_G<&m#3=9Zg0LW8f-4RwCu^%gezS z+bHKODfPDXMgwl@#4|Cq)`!u&i)kGD*9yr&EP7llG51kHi0om1_b$zvXb7GQ$)!BC zmJ|7uDf>loB;)eMno5bt%+psQ&X&Y8t&}r+X!o6WaDp7K(Ej#q7uEKLSTeimRb~ky zAB?@%vb}GHQjiMbh(X=1+;Q*;S-s!tnAl(@#C~>Ff1A;D;IbBc7}z9Yvq_}M8FQpk zzAYgTjDTmCeE@M)>16G5Tc3$Ac_u|S+MR5=T=nmCz9LJl!_TUpbDmOFW-j^1pNSFE z9e?G&ksFhf1`y7x$xCds{DHxc-CfhcEJr~zV~-D;br;iN$tj!JTHZYGm{O9p4~md; zFKD}_)T`hJX}j{xVJaat^=nZIiOxiwg!SXV{NxkQASSOwP9~^%*uz6s_=qC4DILFg zSd~t633O}Qsq3IIwB}*ogB**9YCmNtV^39)XdItqNC@NwJ6hz?6jO zrvgVZJhmP0an^uJ9T2qOPTgbd^=|Nd?yq$k%xRbyghsRyMjdR;OvnvI{vnF1XJjbGsAa zbS$2}eG0i75-Cctx!7nTrE%7s-6iHSkOn{lzUl>JSGRN2t0>Stsbd>4nofK=x>x)H z=-e>^kmyx+VjZAWj1hS4eUq~7IV`Kl_hRquzW;Yu@<$S1#H;mDLoBI_tO7&CM$S{4 z%~XLU3JKuadaJ3FnFATbp4yW z!=%GVMI@iNCJ;vLMEoOADQT`*Y&46CFsvVB=)C*8?PKgvRlHQRxILJU-7yvM(Ccrp zaC8s2_EuyvOjggft)Z&%Jni6py_Y@O`+1ZQrQeqT{8;1jUaJya#5&)?*~bn|6?2_N z#?ctcF>FZ=3Ipr~cD`JSp=Ef+Z7$iJ6|;tqhmWbM(+?#>(+{zy`A<*jCOnO;60v%$ z{<}hs^(E;))?Dv*xXNp2j=1eo4d%Z}yEhssCy}PMzsv{^RA!}rur%#9?Y2wKA%`@T z*-b8;s2Ru>E@bPZ06I$ObZ&wU_b;j-Gm9k^eHSh-2Qq2V5+>}Z{+ycpI1chtUfN2* zizHk($F&5$ql0bp(}So;eA00^aP@&49WqO6rS+4Z^+T^-?vG~$y(54{n0?Q>^SslA zGXh9Fl+3whLscX5$_@{iEtTCP72@9F;U_%886<@uPqB*fnr|d~9uETx|3KL0Q1J&@ zxM>S4l1oVCg~XgzZ;>Hj%S9L88O2e!(4)c33suq<5p~F9TC{Yd#v1;idnv?eQ`@Al zZ0pX-EUY3=8T9CXhq2;ony$}ZKm(BRD}PIL?4sU#IrR7Wqf|!5sTtc|i!y>HO7-*m zrLZ!qKvqTc{z4I0`SVn4SXrK^Any_$pgOoq{Y{I{PF44cIVYn^_I)aPtX{7ZFRr_# zfpTp1EUsIQB|9vH@vqr+j5Xy;jF0i=FXlNeM1r1yi~;YB8#A=z4o6-hzUdYrbV_fP zQVG@~*Gwk@Vs+`WLFUL~L){v}(m4V2%m$cd#e-5lvD}lbtgb5{qWE@Zh&M_egWdBV(XOk_Y_oU%j3w=2Pj}k z@(g2lJi-h@&maQh#`{D5^}aRd_1nyDIT+ThVhMO|QZ0^piVFXOYJV9yUjnlw{p}pm z)m*g1<%q=^M*m6V?UC2ds&|D$dCVkHJJs!aRz)*1#00vL_#Uku`S>%mXTx+xUgVn{4jk2+o<@r(&dC{blFuI64?8tBwpFTwNygOQa`?0#c0?dW%vku+3-3=2 zZm3BN5n)$I3aLcS>O`C&D*@o9-j?r>qjHYKe%T=q;uJG=mbL$>Ao5Qs)7Do?vSzy` z1b5P6{?MOqD9%mpmV3#Ppj6VVzA;@DW!zs0XU^7KXrm-7LSTX z(5>zmDTu&QW1PoK?faT75dm2oIa__NknqNxaENB`kt3Js<7)7XvJ+E2ud3fXs=>No zW^+Byoylmv=!M%0XV`4sM~J@D4 zM(LZQIcse_I%kHFUaYI3(<`&BD6(PrNL4c%$4P^}6X!XF(Z^KHeXfGOk+7;7qr!|O zeeG0E4nK&;rDyIvPDM_;9lt9DBjo=m!ULc_4;(EcW1hVx^anBgL1mn&rVptqF?L*VsP6kkSwkmF z?>PANzjO9hj(&=r&cV4dj&Y=6N@fE-Pl zMd|xV3D5&_O@ifL<|TGO@Erlzm|i^`@W?U+%G%Qd6no1GSfY)uTYHm zMYq3f&8v4I<>aK9&qwNWktII&k$l!u?4t;Kn1NCW9DTZ@@pD2XzdV-5BA-&2!>W3L z1rQ?P+DkH(=x=$0nMTjP^u+Sxl|r?=f#5$JBc%{obKwj(jn%?46;^g)1j$aq_u6)K z8>MtpY()$$P&truLRb_l#L(0*b*O_REUdZO7Kdcu&*dJa$2ZZ2f1G&5x{XAt&Ngqi z=6>mlO+LXBECtj0>~);xdF!k9?@0vy5UW!}Nu^sry^pcGKJhnRV_h|Y*(Fh2awWG* z-#Ho+oC$W{{X6i_J4uL*O%Q^Q4)-(&Ja=wWxquW(zqstU!fO{_cVFw+PTDnw)44A1 z@5R`M-L5s%bpiBSbPM%X9`xDd95%BtF$e!hYy^=Vs8HLQ;#-?#1x~68W8KdTI)TL0 zHKb}D%}PU`P8$ORJhF&+VfX)(QVe_ZFyz)uLAy%Tv^) z`wAGp{=nIuJyVv{{`Wr>I!3}#!=38D-^|7T`>oTcwdgUSqf`1vFDpVZo)?hrb(H)* zLn3E)Q&s*o?u?)^)nOSN5026QuQ=9he?cGQE#cbISMpQUQv1ttODCDV8LbdWom*yv zI_6eKuS$s;e3AyZ8j3tF9(}jkd5EaJ-MfFFlxaL-g;Sf zL+?=#A|ykc3_WQqv_Jf+J55|cv$^P}ilLbeGV`T`<~57g^A`)C6RO^>`YPKj?DA%e zyDd!cQp%p}o^i>}Yy%=MC&TLdy4`vA1fU9g_+ViS8h`zg^Bs))aPS}Mx8R3;s)X(s zD}x!~LTGtz9iY1nHKiA^)5X7$omoq7EIu{B$=R9$;Q5QpS>`40qu zZjQDYquA9yBvexjQ-UoC>~P>evLH0SV~kv>Iap8=oX+!NT<0UpRsYu6%sZScWjs%< z^7HS4j=srvH`Cn_^36cCGiAh-)R3LLrNIOz?B#yH?q}hyoriJGwKX82xZmdA(!;I5 zVqeC(N(|#1?wL4|w?(|?l>WP~$j#y^3O%_dy%X}=$KrGSCQC~9#o;AThu4@Sd-#^3 zovdN7z&-g=`Z2TBmVV$i4sqVM+C3^J%!d+gwn4 zPQ*UZcj!t1`k|tsXBdQ!0U1mBEexCIBPvp_d@KC&Qfk%Lf6F$WeOM6pQ=JZz zy5R2{^y$evtdfYw_dhE&SY;a<77<=6BSfh-Doh~6d{QPybd2|3v-14bg2~u^>gS6f4S=CLs1w5 zyD%!CKQ48$JWCxZ(tJ9A@YnUVqow8;=YG{U$V#3qgPnq2QE@bPW(l)1tKpKLoRS4g{w~IO&Hr^pqKJkCHp@>7+^OrHTydgrC#FoA8+ihov?P->SdJm+^b5!t zh9{Yz)a`egEY53G0_~o8U@duk4aHspx-pNW^H;JD^y4^`B1zx4H{NDT3)T;EqpH3R z)S=VMvHK51xr$ayciyt+743uaf{`IgL(Wr-K2@v2)Q77f{gSQAZ{-9VS?{F`YC>+v zJnUJYpO@YP5aehD(M~6Xu%WSCC4D4Bbr8=owQs~&U1I3d9bZo%fyhEeRPO)9QXk|5tKCEnLFP23(pVi|ewV9fn#O zF}e-Vj{P3l>k-$aT?vg25+rU&&^czQr~?Lt+!64ypC(_hh-QntKg(9A9nVtY3qF9G zAQ~&3gX2t-u0PHvK({TVOKw$#BZaIp7JfR*9I!B3GF224pKHGI8eMZUmh=0~ln=kGQ?XwBStVpxdlUT$%#8bDPvuSeA7tB|_M10v(s_*<;9W;$M@KH1j-H7G zTT5eM2IU)&Ov5AA6o#m0G8sI87MXPViJllq59}-u$DsPnqColoQS}#o zO@ROUKfZv0q%@2a36T;386%YjNs*FLN;<}*VTjTx(j%lh1O!G1ii~a;EhRMs>DKSw z=X}oZch3Dc+>iTy#dSR|Aes8w8tdN6oE!zuq&QkE@$Pf0mpa^t4ZXAq^~=jh`iGrU zJFMAP2?4w__Aciw!MVQ+okGRqS$eqMlbI6cQ(2R);0GRZ0L}$(QwLhEotXj=;W$(_ zL9Xt)-AkJ81>s+EUi3W1&x;0_JhCukGrL(;OV+7vKJ-XBkSYuElk5PfEMWVvlylIA zffi2Zy$6q166+hD%T>qm<}r~PG+65U#1yIZD2iAQU|uX-eSRf`N*;nm8ucYsdphqV z)f~?XZ=YT#+tKs3Z~4F z(1!F5#aB*(zz~m7fUMc^CgaBhqGpM+6W$==!d%YUS>%BULoSmriKT7Ovy&)m6x`xl~n zE1eZTg=w0o=?Ccm@tzIwNeJ(!-c$mAhuiJhwF?zL1P|Z=PY4a?9ktsD0H-9#&LHpO zuYYsk-kcYPjiFL#XV~hOMI*bAj_a*y8Y$M=1PMLV+O;Ir()ukXc0En(q9{l1eYp{3 z6=7+VmiIM@kbOwB?Tm6x7lqA2S`>3;J`I^BhCcOfo zc6_ZxVW=ipw*RZ8z$1j?=gY)|n^*CgZ056kkm6p&q)-*Ma>a64E^{6>Ge!RC^J1yE zH%6yu9}l)s5&)cYmf);fnupGUZ= z>hSE}6{o6ndDz>}WP*3^ZGoO!Y<530sX&N>pbe ziKV>^Ps|*TJaNn@K47Hc;b3r-k)w6SZ|`VCv^}s;4Y(KnVc$W-`+a|Mrd6Sb+3l!# z{2#E$6q(7gPp7gH7^*J6y`az*?iSZs)YkBDL3PtP`)<5K;R^8bQ2CE;Vtg3Hy7tlU zj&!@bb)}Cc;V4RtI8pM3TYp38I%^vs(B=G>xg0(j%FmAQ z=cZMkB^F~>s)MHE>KQ(dz-&CkL3dNFe#hVH20dBk04+@Yrbh@J?u#1yeJuhs$uy;&g5jZ^9@!>xTwzNR?yb{zw|S@7hkzZmFv1#ZWoPCmTH*~97E*I^Tn zWbXlZ{8WjU*xR~`VFbwfxARV))V_ZAEjVv4rQxY@qsojOprJB2w)ifs#WiCX zdMy0KBHQ^ZH|OJyvL+2WcDab4#KdIU5fT<}GLCdvi>0e-pRKzZXU#i;Ru|C?U&0%v z@&bQd;~xJ1^U+Gxv!vWP7_5=r-X;<4si~>!{5hAcwy*c4cp-n6`wdJV`~1CaXpc8? zyiHMAo4<0c1IGI9TZou+FQ!B`DB-E#0a1uSz<4x(9JqUcHRm@*(VjFP)<=Mg zfl&P`D(?kK6N|$)7B>8p@473$6M0c+eT_?ytvt)$7mFz62+1G6`iyZfrwbS(iLZ2J z3sL;?Spzc?ztz$5!@|m_5^t-ZHZ}R3)oOY&Y_I!p`=1-5d9V{GH4!3E+p9V^{k$}i{YL4U0 zR7jQcEL5YGI(kEa0gz2^&F1BJwtCPV!GKoV9B}fCe;bUs?e86j4*b@_;>VZtB=-Bq zpq&_<0Zh&s;?jK8QUiCgLy`&jvKuljfAwB6_~7>=zJhKg&IN!*6+cWB+@ewWac!Fh~7tN3KJ|Z;;Fpa_yNRji_|~W?NkkkMh9r zgrbX5S55&SiZFqV5Ia~g43L%QU2 z1X1+yJOE_@66#^uw{GTI<{`fzBoyiw-BrZQ8W#7_6I|2c)dV_bIY;Q{Az&OcV`bf( z4?Qx0ap&9t3sm>qrSXXasDiu-tv`JEv)#m6*wyA{R3HGVFtKs@r(vtOos<>BkcaqF?UWYmtpw_bWwD-)x$O9nb{y_}t!z z@>|aUZmqWHJH_!o^eq_?MeLhFee8v6n@WYT%%JH(%B#1e0fP}~g`alXUceuoNB~d# z_H=vRx2%Ez=4gHnai)eG$6fO}9mmo7Lx=!=KQUvXxL?xQJg66gf&1;XY!O1EVsP=*2(jgrrpjm;`0q$U)4xdssaB z&88$-CN9##!H{q=B5Tk)9x51E`|nLs52>~0r!B&h5+~L%Le`8c$EOr?CkuK%#qoVj zkDN(UQ<=jr1nKEgpQk&ioC-o3E zd&NOEMUIu=sT-R=8FhkL++!FVrZFvAP6cBdk`P=lLUEd5g%?$8Ru;B+o?thuU@Z>P ztpDfDo~iW_abRwSNM6d^RJ5h?7++Ndd+Z=0UHbd)6TT%>E8?XsGXO&Uo>*SEtO5K8V@ReB#le z-wKfv#LO`CB5RTNCCd$GyU~US^4pzh_z;ac?^F<(%jY>1yeH{r%X1tms2O$Fea`#^ zf6LIT!0ndG>R*~cd>=v0WzC{F8A@OgVg|0;$}wxb!FEN6{)^HXf5sS4>}|;Zr%qBdSu2Ckm9k630kmr zX?7|<+XI-%Wvj(+0XCJwsf)&eW;Z#iYN^db7OzoC2g{rQ-b`DO%t(~6m0DGqIWGG? z{Ia$}EF4S?P;}yCr;VBX^!U%g@6=*)UkM+!Gt%n9~f&i**$E9=XiuNTo zb+Im~A7>+bIOYzkeM#}^t@8pZ%i;1jU9h!O_&*OY`^3+Y7ux{(S|VeLGJn6(hj$T- z$X2NF2H9t-I_WjC(g%9^XLZM9a;|kU!@x4IziHTK*Q2rZh&B9jnWnVQGy-l%91Hrh zbqNJMBFG`tO-H+7;Fntuw6I#!Po`98fqbD=D*3@&am*eL2Ur7YxjGWm^GU%8xtAUf zM*MotlQG(hFevpo6~^FUXMxT1*gdg;mt(wrqG;}MX~*iWoR?qqr4o@_xnYv;WXO8I zLr3-wWLM-T@bUeEYliY;|IXLzX2}nv-@)+GtTb+M)~b#A4*kQSXdk`?gtyYw=ZANA4fm`4@y|n z^Z7)z%zu~rTWWlm^8B408i1tFp80HhKocaE<#ni#ioVL&pUEiV$k(H}q8-Ys655nA zO4eE)y3nHgASj>^`<$+B6qT%xd-wAh)LR_p1+((28A!`B57MnbL)@Rwa{)>fy zDgg1fw(V}#uNv&Lz?P=KG=LBNRf5E_+-0Jc>j3$qP#M&ZM<|o`tO>GGnyO*~7>N)7 z(Uw?Mo?KZ>EX~ZgJtY@9>G*j9*QxQb==d)W;6Nao z?Hubd4!j#`EFKzKk^J-HhrMl%G`M@&L~Nh$s%aQ&0yQ_PCI>b1h4BIf?j^m3#IIH! z+p>GI2_^c2l0AdJ>P)4J0Kc9bH%xsG2?A(Ws}UXfzyVCZ+3wZ_-1; zlUF5o-$a>fu1&ItEKl0}Xk+RHr1zl;NIfE66t&J8;Dt`a`2Q#yk;HmeOAqiqJexuo zKqC8{I}}k1Kg+t-?PziGqDlMtTExu2%oXSzU#zFvgIypUUE}=Lbd=KQUciT<`;25* z8m@O&RUO}o7*_os6LrV(Vl}aGp82J+%UmUpv?#HKkOVEn+Ibv2I2-WpKJ_Zaw(oY3 zaK|L_b+>0hXlv*lL-`@l@n@~Q+JHF8KaUuS`s|76UF7XUl8v&mrX!wdY^L(Dd%tWv zZZ^oDkqz;#1lZ3nJvjI{)Y=hfHY~YbGGdC;=wbKa`4efV9paL4CN2u|C0myJTiOk~ z6;zw_+^UH*kL31`1Cyql`2my|UIiC9Tv^?xDrH2D;}=!`Sjeaqlam|dJ@x{rBWq&B zV^O^E#CA_ZjF>OEI9vbekc5GK=%%*XvAYEpwjQWIqE{1o?8F+;CYMN~w_yGOpzOr5 zs%Y*h`PEajmkj0DNF&v%dUx`@jqat0tN~A&#itUHzrr4` z{WgAb`7(>r0LTN!qr~PISM77`hMz5aFtQ4u8G2V6bk*F}d zYO&-hg_^_V-*Dx}@||BsOV)j~76bn66D7K7Avd@Xazm{M*kS3aj#H&UJq@|?9{ch0g)Qn#0XO-BRK;hmZDS0$bCi2h{BQN!t$Zo6P zG_12AF8c0STF%7G1jlO9o$(!>L!~a@?FfrsSI|1y&Dz4_nv0w5 zcV0y1`1d1=i7P>p+ok;rD=KyzcObC@PiRufP_TtRuNFDjV7(lv?xD321Wu6@M*?+D&> zA7{X+1eEe-y4#9e)=!|poCd_kTO>BNO&#NmH^k3OkEc8ba1 zni(%{qVedXgV7sWV3S|=KlARo`SLXh*N&nTvuIbcg?do;;qEF+=~@`wgh5tN;xMyG z|L5v7LZnTpF4jpeSCo7jFG(>Ma+gtL5>a|yyOH6LlT@#}_^Ue20Wm6Q`F|g`le4pd z@uIudQNtCJsWRSMdWUqB+@4G;t6emYb{~u@e!%Fb;8j7sZ{0yVcd0S{c9HfF6b+Z! zBa1{p@}<_K@q9oUo*SkDR#8Zy0w(Fm?kz)ZlS+|qS3^MJRCFmt-m6|2@;{3rLHn-@ z6A=sPliJllhoSB4YA*S+M1HjI%_3wP#b!{3Tg6%T-zzqnQcNR0g=7I}h`zy$JS2hq zl=mJolC**7y>a&Uggm{E^|Kv?>3oc+c5uP!)e&WCx$6~$F*Lwyap+Qp8hY9QW2%wn z5TsDoCWWl-{{HPTf@z~iSp7bs1-2Xd#lu@6DRQ{iw?ijPHYcGQgrC%UZ^X`c9xhst zTJSH{CSk2vu1?9SB;a|CfCTctIkp%NWFK#uiSd+6$rOPJvc28c z%;A9sc2;@>J(2f#1hn+6rKqz!DMFPxd=EaKY*M*dJ8ql47h?x22t9ijtCloG`7U zqLaWE=^F98cdeuVaAoI(GJij<$bG@j1RI%&L1|D@JPqKz*mpTqKyH~2L()TOKTQxH z`OcOnB@w>)MuICLE57w$U~=vusZx~?Ayrv|J9-_lxS=!Ih2QrY^%~egV8~=4#>0T4UqSf*hqzm*a>#g);tP7r-t6kT|mX!^dG)_v26cbp$b&zhi|E z9U!)fZkil9;iXv8#k~=cX@RP55kx<$B86lmm-e7j*b<5%Vkg6&xli;G80wa`yXOO+ zVFkX0*QUlFO_ploH8#~J&SuUnUS!9SwGHrZKO%rlJ&h~vk z)luc}`)Yv=BsX_E6sCPCqBv%~`fWXprOw{FT`fjrOmM75CX3=yZ(pRMIk*Ps#me64 zGmXsR-%F@l{SLaBA1^6MXzrk3Ud34W#O%#VpI+BqY_|PfI1B}eXeufwM&HO&Q4r14 z{o{t`Z%o}j{;_|uw06|!-=56-g%6g|Vjt|$`Ov8HtH>hLt`_{;MyS_m?UGO6q1f4A zK4TNfxi5!WVdL6g;%`*P8bpD7NE!T~l5864sPNjWV=jAmQPanXfphY@Tlf0iQh4hK z`+NwO1C;`Qb_`iw;HaR^O9lcTqWk%flEVKq0_6nxMa#uTmKxHG5G+!IoTy(WKMR9| zGkSws3;?QsNYc5r<8U;~j(U!b&7^KX#p~EhI}|8y#sg4Z!w;Cs8;6TNYUBER=#RKu zkK+1(ua$VT)9$#;rkzoYJuzrFhF4bbJ(eQAlr(wd@dSkzlvc=oaqG$27ibg{Ak4f| zT2m?Pq2W<1F~0DG&!SpYF7K(Z`w zSzXtbjj{60^6x=;DN$61a$&RS?}t0qK-r5-33IKmsiPBQ^W=}BW=M&8;PFeu8X&a? z77>_qit`@_6d-L+@SpAgIJ4zE-46WOLO3MY8S$#vai@T?*Lz7z~VLvheQJ`%9pHr7@d(rEVT&^^<9%q~n}$k7Qnpd!7?4-M!HghM4E8%HJ|n zT^|}iL*JU-&bPu&(%U4g6yN<_OTT_ngum}PX{~+lGZ#~*2K-b=u6XH1;GY19D>vHM zCNI~L?x^U3e6H+`#93;0Ms{3%$3K2IwDc!P_a27iza^Aw<6}r0Wgx z%lwD@PJ}|kB@oM|4O_1&elpb?vAp<~-sfKjkAX9Z9rcKrCg0a&F%Q1@Wu!$#NkP?j z69Bc1?2(qvli5ls`49Bye~x8gu}=1Vaz-KMlrNf2m_YZddH6)rr7sI7k@me_Lb|fgxR1Vm(p19oe5=S zbCTXO(AwvKHb6fB_$$QvGKZWLaSA6(GlG?Aj+e516(?y^dS8{<65!EoxtoLpon3wm zDZV5A;`U405#B|7YW2<#!#=Sl{$RBlQGK=LYYjz?Sv z@0UBj#eyd%3zl;B^t(gIO9i6~;8O~6NTcCYytwQ=_5ZdKmHz*%L@O2L<(lJ$Jd-ms zuR~s(O+C|P_U%fMBy#~0sax^9e)?<~O5O5N$ee>{T9K!Mr6`o$sss?RJc_o73W!~! zC1pghE=RZc*o%IiQ=L@lN7ez-Q4bUa;q(SPOFR0%CjAR~m_v#OJtTW1N*jA1e&hH@ zn~Oi(C%#gvw_U0R=zj7?E}+7jlaARACZ)MIcqW%m*Vp{NLaiOJ24Mj^=@~~NC6@Hu zRTAIENE(2etMM-fg-(Q7jL}B0n@nWe^uiVwMPqB}9SFd>EsILVm_d<-GzpUxoo8yK zSiPh}qKzt>ygnkH{G9ok=)8Q>_ z3O&N$;LPIjl`lygYky4)39A(V@XR|}xK_!@(x1X&W#7Gz8XLE6>GjsX+l1gUe1xnP z6qXVF-e4oh^9es|VQ_q!i|4SeyxwxhjA+KO8=a0s&f`jBl<-y5SuB6ff0$wom*Hba zRy@!yiY){=mLq`r9R1w59?=f+Y?+2HrUA|t4xA7VEWb9WGBjHpZKNPcJ#tNpY$}da zju;XA{d8_0z4_bKNfZvAHK|ONw_{Xz?82JgSr9X z%{grin#%1$Gb;qL7vrHfwc>c}_R$F82q#wz+zCo4_UH~kQ)vmsGZwV+^yJrK; zOMhgQufOct+o`CWHpu;8+Q|82Rj3y7W$VD^t;d2`86ZLtgm#QXc*=P23P75Bp@#R+b;832c66k))|j*2JNTyuja0TW2pl{V65XYegyx zP1ktp+w<^TYl;#{uPUzw(B-lJduEgKGYXRdQ<8!ram99prIHa&=iv{22~#dSlJu`-1Io1KyX*QRNIK3vQ2wbf zUq4klY@Hq^M@QCvc{uM}d4n<%qG+3NuC0{*U8miCQ6@>!VRUV!eElLRcqWM6S*+JH)Z4*7U2mU5(BIubRZ)1|C*pH5%Xjn ze^Wvj+0UFku5tO_BI;w#(Tk%^%KoB!)LGfHlHG(UfxE<#c%iP8uvV8mHSjKvod)vxF_DanshMYTf7NLT+Qbn@(gZK@!pl zoYNnuRfpYne1*ct`&$7-@{Elt1r|xf;+t8>&217+ns&_27Ca-b9NJKGgTH(q2r&di zef(vUfbknUVJ_JoiK_JbmN*RV9L>wE7BqM50F+F6OiDA0tNQKir+%6k(HMlj>M%*` z+-@_RaWiI0Dkd|+CpPv48B7Q>xXCM`_r$^i36iLd+Z|51h!Ao2%j?L9(637odop2p z-dyavgtDqR{+o35-1(N$C4JP1Z>zbP>#%c=Ixe;4xnD;eHL7*(p8P?xWlVK0F@8aQ zIC>LWHV+#&0n4^F7ZW>UJB(6>TOa=w5Rb@hDk#J;Cxc>G-*iFKPW#2fHzW8pAu|Z% zc7+SIN&Db)3^hzmwYjv(ZSlVIG^|z{2D=xxnQ4m?F$O=}N~!uUuB76W{)?Ay%TKH3 z|3@)KEBxZiQ$kE^m8zbRa76An*JYvBT0h22B9f$-c}8P}9tGx~y-uNZwsr+Q)z1>n z(un{(qMs`{;>kmC$?^Y@&_{=i+met&{1?PLzpvBNmJFkbPl>ijzB*9JY7w5+JdGVe zs^nn=go2W2J<4R>T;4wpiUMQEtYVIrgj7E8f#}oc&nc(t;mo$G~V5}gc03U$C zq|87P1CpNpuDb#vfhpCyWvEb8>UzulDzBd?o zYgnm*VjhOcF>crDlN~gx?o@a#%wlv&G_ZxHZ}%7$Y)w7o_eh$AuEK9r+FK3^*En(~ zoR_?_!hF#cA5kA9sK<_G*v{RoEousJSp$g<xG!cylZF8gozS6PfH%N&meCX-9Wl9fiM& z;D6K=|8xH3ZROz>7qbKT54-7fdq<P=qtGony$=F!8A-PYpFO?Sc~HrD(8UMZBSTDXQOoCH`z^^ z_M2?U`XPabbEo0g7=J%_?NOVA{9n}L2Tp0G?K0?y;NK6}rL-PTH>!cD!elx>(27WE z#dQncx*or%rMD5KXyk*mg`0W9c#v+cIkHkEx0)%?rxTV~Iz5QTw-XO@fb*Mwqqou} zw7JMfW9iKRpQw3FnFd)-rqd^A&)lN9U)Y@fLObC;rP<5`h$jvaF$ZWS)C43+mW+T9 z!v06rd(ZMXs+DqXZTk!JRwp+O=S;P8j1h4YF919Zln4^CoYiK4nRUfi2;{i2airyj zq5*W7wh0KdDje8Z$RMZfmCP|Aft@mk>?O#3WZ+Z?9T9KE9m62p zh@AJQE5vzI3$-y8POzFIgD3(?1oS)ja*zbQnse;kSCrPjdw3^93~4JY zcfK5U8mcoY_~L(0RBuR>?~hLzTM28W3TXs$KP<>!011PkIR#+=shzP-%0J;1x1?wj zwZn#)VJI`_V@X$|Ca0%CpW_imE^_iGg@|qd>~QA|Fpf%LnN9Hs*Q`_0NeuE-cwGWv zO;iqZ)8ciJUcuboAU=~Y%j>+3b{>4p033-%>l2N*BDo72K4|tdE(Z%H7GaT+S}dW+ zBeAsmBo88yvFgdh^7iJi>6=6X-^F-Ck&+)Oz-;)*jdhKv*EAr8RFR8aip`k*ZHdvW z1iLO~(Ll66Q~q@+k#ECsuZo*a2J84uvnZ$G`M4NSwHd)(JhEW!SIo6wRLHx^3|h6f zUSSr4pzd0;N%jDq5$hCarwt|c`?dG^tT|(=RlbO<{k07HK!X}*LXMhyC|<7aLk^aKdgiDp?fYR2K+=m9>W|;+VnHZfzCVhX<0;4rp9I9$-W<*WTbNSgkU^HbBY8G&V)n~v;v*TItF{Bs# z!gKaR^sXGaODw=&7V8o0=F6^t{3^uDR*ym=CgZ?j&!;29sf9d^C zV0RQd)xFKG#})xpFdYQpqamK^hL5iGe;A<9TqTWDS31FERNs7R_rZ%l-?YlrH{w7w zQg$8#tI0|+C!bHo7faUATYIhhZ+=m}wfrx|;TFh{9ZAktx|2ayI(z%Swfe`oA_hrt zINbL49F525(yTDMYt{G{+luaIY9-Pt%{qjJkc&9~^=+5!1ZZzkxRXE?(WerL(c_qZ zXJ_h@)m;+R4CYp_7i8#{h2m!X8gJDXq?_Xytya)rBANucQY|Tx_`^982!w-r2Ajn;7|9Z3rpt4!MNUB@^4Rl zWY+%UMx>&f-A?3D=Q)vWKty%hLP$XSyp3brw@QF}^NfjT*iE0b$QzsFq{oDfV+~34 zuW7!)dqH0SMWOu*0dF_~?=^@w+TeqQ{fB5TZMlad6g{AH9PXvHNIozMc;I;o8X;Q5 zZhYfK2FR|E*;c=P_#Httn!4y-s8dgM3AdPo*U@nb{c*8NxLVDKDo8YR?x`=`U|;L^ z^Bq25vwOPbjh7>kd{bKPoIrI1abv zG*HZbay0Afcn-;0w8Py$w@F0K_V*Fvrt{uEYjaOBHAWmp)SRsfq>|hC7_OjcBG$P< z&(=pL>bi>rWl20APRlxuP-$gzHbRa~`~AD*uooWehiy|1=UXD9ccZ;`Wk#C%k%DUD zwj()mg8xAfUi!CJ=NVT<|Epl8r$4rNMsRqr|4+oXg5_f1(GYY$K{=F~{rAUIN5SNM z+Lha%^nyZ~5MQ|{?QO>OL|Yb#n^LJ}_Xt4&BFGvI;%1huFE|r2cGSI*TW{xBd3sEr zESH5o5U5THktJHb^M_ZZ+AFMMzp`7gPIi>&b{=9k)0p6|6)bZhrjpY-a*_MZ=I8k# z|9O8G*aU30{AKlT>58P%&x*%2l3jp7p|3rU0o^8a5}S+9?)PNr6gHP`RYw;Pmq3S` zgp`4_9-@<{tA9s0K9HV0h1TZIhG!%Pkd? zVw`4sxlmvqS*dqmM6j5xPTq&I5Ohp+kubj<{s$ewJotCro5Vu6eY%zEW_tX>~zLJ@wO*vam4u(oA!ZWv`xq zO=oeO2bgtgCne(ptM-)Qz$X727@Ff_akcD%DlgrGBDp6WS7yq|?%skJ#mR$$v z;D!pRbni@yk7-erYJWWP>(t%VwQ6^%{YALHjNR6sFn^09Z#U#mvpN62nBnMl^$99G z*RGU9FWm{pSqQFYq*`+RrP2Fm>1N@D^vQ2or?xPK0+i0*A__0tk+uYWxksVnQ%gFs zJk|iu3D?V+aWTg!ydCwqb^0bP65tswvcMzeyxF}r?1vSfVp33=IUc`FF>Vrlp;+$DaEk8Tx`Twx9WkxYIQl1B z<}R&u-DU^g*6z6yp3*Vi*_XH{$+r!t9G-8ddkD8?lZ#V7p%C<sC5R7Qh8&aRF8oF8`DsZLJrke^Cr!{nNvQ z1HLPu6Yy}{x4?*;1PKg2wN;E0BWC;{KV-?NW`s?oDk%Ic9&Z%#a5mY_pRmuJnqNp? zOYP+VR3DQ+hLgejP!6` zQI?{d0NWyLOz3;rfOB>c>xFFDCRr)F`{q@4$^Gk@TGN_VA%}O~?-2OU^*R+`@LdIR ze>;Ky+dCFN&3N^|t?MmK)6CzStD^k;ClC_xQ2ux*!OzE{Whb0`-WztA1__5*pzI}e z%@(=)Jbxu}JJj%MM_bpGLTKG6F&}8rPI(+F9(PU#obvsaiI(5d+3&EC@Symc37m|E zS3VYn*W3HA$VS%Sf@IxQ6YiARpsgse`JhljR_bg@b;u9uA;{~}##u>zM zL@TB=c_0wL`C2=oliTO^wjruRCF?{FN;>h2PAa}dO11Tg`dFb`YIg2k1_Q!e`+*g> z^P9u*?`J$4%utHW4k{Ww+ChX10Ne7NR`?HSr;_3c+e0<9^gSyBT>#+Uv4-+v!$0;S zA0zQE+tjUigFbw0Bn;uax8*X#!vhBC_Jnsrfx>0=5M|jva#DPXwaWDNB`=B|%UEx= z+^ueX1w~E3-hL%W+d4Ts^d~=w3Ffg-J?x2*#%ip`ICs(XNfvG=6j>7|q7DE{2bXNc ziDabq>?$X|645iKs$V%?)V*PAHy=JZ?=;5#=~bdK5xWn&e}Wf72@9evCQtMCn01tw zlQ!c&4;OoT{|F_mln>C$KaonX_zBN}z@&$Foi;O%*}bLVh>h6mLlSu|tMgV-euX|7 zc5BL4_-2ug?v~zTIOW#mHyT_m&WRh!%&FV_z&Qu0^Kh9BdHkA4k&ea+)>4XmWQsGr z@CF-v&a}Umu}Qi{vJ6&F+87S}_a+$gPW>Y#+?zh1l{VwHyDR-XAuCOB1AXe8cs95`)@Sp#dUsw8OLD zvu3%@lOu|W6WSrGmCVKS)nGt+U}PuyS9|zojeLcRxu4q>Vj5ZnSd?XHc0iX(_K8)! z#6EWmKI)d-sh2VHt7`Ch(-$YT^zr&hND)5spAkTQ%`Cg%=BMWo$8og&er--MChG529 zOVWI!2@-ioj~@ojq|=BnO$MC@JBcfqcWx711B1Pm9}@|6zW=s=uROOHf5B~WJSZPk z@-!{du#N$T*^BYxZdT}6%>KHa4i1G)M86BDx@fK#>v6v2jq8}>QVu-yOd_tZ&_AI! zr1W;K4bJU8GL}{}DkOwOoe&Hv7%|Y}LD!E!%fdhU)UJI+PlklR-i2DL_TX!=M-m@R z0?RCn+xB0;BU1d)w@~SiDTjf9&D@@cz~@2w;)z^n#iem~Y$z*=*kFI7#`B~+nk~9~ ztJ`MS?wz>7rq8_VbAuKW+$=#RCg1)gR_J--NnwS`BfH{mHBJG_wc9p&SFuYt^C%5> zdu`w0Z=_PZ)|nr57VmDFnf*eX90COZj_jCw`(f@*X?6CdbSl*&hKiY$ILlaa&9ykKBIg`M?WfIv9FQK zUikk}b=Cn*_5a)77$qr6j+E{mj0U9;bX{P54Y_dnNF_d|yYj6{}^r2gvaig$$h zrHj!?TDzZVmP^A@V!;w6Hs~clqi7{3s0U}4!9GfD_ea&|U}iJ5U01cB)u{YNOORvs zn<8zXww4T^D7m0`w7^(H$*?!h7|^=K`Z(JgJGaH#EpAJ~zU9Rh$=Fgx_@jwn=E2D& z11=`RlA4M@tpdobVw}v1rx@rZoNMd-v^x2=Q<_UF4nbZL!+tl;ajLS*{YJ`Pdg7uu;g}*(HoYPjxggF>M z3N5Qg?+2j0O~E-7H^|nel+%v)`8jB;x6YEe6WCsVy=I*y;N|kOhpx$<#4K@)8uSw< zDizgKZN)PeDVc_;uuAF0C8kCT@5Z|(8$cYzmEA30r&*?U7Zc;n%CqCo-8USqyVdP$ z&B52r>#!RC9O=7@RTtu1sR60CGFf_cAEy1g@2|TBEbp&S$$2r9)l&jNN741xzX(vR zsdd;c%Z*s!%OyW=Qz&c@xy*08&<3}Gz!WVUE07Bs_Q`ZyvbP=;((AjcaIP>ASVuX# zTTG<#c{3>5I8>B#R7ixgDJ7h=cq#Udgh{F4{U1N#j&xYscNQzb19=Pa&N0|E&I{di zEhHAxd7O90k4~||!>$o-#{1@+u|K6Jy6Q1B+X!hV`z=9>FXB6ICt&U~3c+XEXTBMg zzM%!Qi&k1y*n#*mp^ggxdY!VA@2LF8(>+7{Y zT$YsKS>N+1n*8n>LpU9xAG?-wMkGv3@Km>aH=8Iw+n=?Ir8ha-4u0&$g++EEOZ~vl z_+L-v3)sywj{oY**gj)KkNqpZqA>)#M8NHG1mo8{Qm37_T z>NG@ftbsqJ?SU-~)e#uW8m#FLJWWhHMBrnSIywO+>PlF!E{`D`X@=@hyAjhd? zbz}F*>3rSpO=<%hr#~>k zJ{k{>53!|CR5Ok3s;=_@$cnmpCW0EgUeYODv(4PF6E;TFWO-RgvaN`M{sK2Q_|qfn zn5jzu()60+U<&{yLk>?e@WpDhP{sJ_s45nco~v3`nq><&(|y?QFtOGD_z;P`RH5OR zPSyybAb5X9ts3$yPBKVdKfiD%?pz?RR)d7v+iEjXgQUy>hTW>w^B&^pF!~Echv8Z` zcD4|q1EH-QP0rhSX;^0Lc-}Hxi?gV;pxmv?&AjxyJIrmBgX=gAL!7M_&6SAQ50X++ z#67qBi+9e)$z+3>2K>QyrNQ>G1Y*u(ojY5rxNX0JT z=6BQ8UR+x7%oeyS|j822504F+b|MFG4)I z#7MKY%%h5k-e3O%*4a(_cT#Tjb>x*EHUgq;`s!>>E4-Yu+T!#1Pe@XU(v^b+AHSk} zv}bHwnJA~dtWdx`rD7>67ig8%)8_<#7xN}}YvZ>skg;ewX{R^i_4qLOEW?u*%P--p z-4GSMO&2QvlU7>MmWi{t)hpB3k@Cr6^)vueq!5T(u*Pd(9eQ^`O58Wn<=X1Io{fv8 zf%tglry=y!iQT-KoM^`pBA%l_JNKHVGh>5f_Hb|lWAAjC=N+U#RU&cWwLLf2>cyUR zf*IE!Q4z{6sgJFAGdr2M1nGG-iJ!)Mswuz(0T-lq`WDmevvEp%)deT@cyi~h!@X2p zf5X-|SZ3O+KT7|N^6qyHzWBlNm(HrdhGKYB=#9Wv@huoiwNd#zv}WOiBu0am%%u&} ztUF|43o_6Xy991ZJb?{T&wUoDi))yyImz*=)Q}VbMfG{n!J`JAac#FCo21Ogf%#HR zR1Gh_G)?Jpvp5!SJ5_2iAs$<0M>a0R-wnC;iR9hCx%}f?_-fSd{;FoZ4#}X=)lcR| zNJSG1JqE)ru(H{jgl%Lw5p3y+RV-)Xa(HGY-nR6^I9J)f{TXVt+%}KIY$fn_T zTV^^cZwv3N>JVCVVBz`e=SVYiu~n9z!gou+zQqb6r(XAksbA+7w} zEyBjbWz(BuLP&gTz4-qZI^GE=5sc9;Ui7RNaf_s+DfSkq&TR{+IK$ZdViz*2OYx+fW1}_ z4bk?dk6_7>L{&!C?b)K7GD7#jP9BAKz$X7Zv1MV1 z-SZZx&fJE$ibKW}Jdt7NFD*8dw9{7>C}{z6co{xx@yWg!8sAM5rD2Cwm8kX_9A=#^7_ism+OPazbsp{y6!^wJkYq_F>!Hm%UVsX)|I|f zOE-NQ5$8Bo8f}VMrfCwroYv;!LQ`#fJ9V==FbyKr#%1(XKV9RuPVa2k>QDdUDPj`i zJ|JKlIPG=Y#Ljy)!+XJ|lp)ifX*+lvLk;$b6Z2e*OD*Fc-TKc@PLksMVn zhYDbll{>y0Dvd;opF^2oqNBJ)1-oJ7s3 zswYLdX<*S=kI5}78?<*owc%F2o85ckBDdDkNCa*ezQ{!XW;mXAmDX_E0$u>*5eCBw zX&*_kzPc{*2cJd+v$|eRbRJK22N(q%x^}Z!PD`-jkur`qRSr|kMVnFOKR~esC%b4F z+APxGKCGVSqUaY$^fr?=XSlxFT)Rko_Ac)2vn(OWfbIi3dc3o5J}$DUld`P8UZM27GT^W|Tkujv}`z?(9g)6EFi`CTvCp|EXf5WH0WkF2@WK5Xb$BuJEJ zY}#Gg!1=4KU}b8?Ws_E=#CAQxlP(=HytRw|gGH_nT)_w>!*v*^8eyb;QCFV2mL)a) z{ubDsZ~sy1{?9dXUkvc5FsQ1>CB?`4>D_fg|4Fo$5TLgBW%f8SN_4E=v&S}rmpiX7bK2aIg(zfO3 z`+%~Ltpu9wI--*83a-ZJA}Z!=iNuC^|W zzJE&VYtzRPFXK~kv?0NcRD*%^6Z&v5m?}(eGbHZH0H9_L5-U}*?f`nkkfYB%n10b8 zS|$cSy8fZkj`=8VhQq`ItJ{Oy!sGPhNZj7UVpEG$r^7y(i^q`iDu>kN%*GZn#kOLjm}}iw`(A}Txw3mWQ6&DLaWN!+fDB_?{D(z-}F=d6C1J~e}8;( zJm0B#oTHMProG^)8-#uw%wuTjpL4Ttc$?eUyenHcWxexg68596>ea_?TX(YhQXkv_ zbN1wPORkEk>gJQbmHo*QOj2%@xnrH4VX@~e);SG^c7{^5hoK79-V0yWK7GEXgoj`A zAO7h*iG=htB-_!Q0T+!_$L@E;#imPK*I&t@J3Q^*g4F)9hHAv%KgxtK#pHp|903)QmQ8DP$}17`*^#Rx_O8_%Iz1Rmf&?9`B)eJ*fw=< zcX>dY-V2_}`vWOnyV((^t#C!L!-$z%b z2eCU@?9(Yq)VdnM@y*QSt*d{z4gudnTk~LmG z8fRWl)_`~KSd_>k=xRVlu^b!J4@Dc)t*4y!hgRA=H%9!v!8He^(rp zwT2Lqr*WFmt{T?)K$w2L(TYnhz!QE_vOp50YWOQk%%NVxbMW^RBo-s&md)OB6!NiU z7g?fjtC7~7)|A-2<*eZ8)l~VtwD=GS(bKHjN z);Hgq zS+NeN|BjwK4vF6C#Kjg9sF(3m_Oy!SHtATULA3s)I9*bQd zwbG!S(#p^3l=8sUyMx0!t?G_|=!#{fTcstDxZiuzb!WiudZoK&0`ApHRxS*0$IfYQ zfU5raoQ4Q!r(DJ2?^bsYV4HNLt@S)syh8>sd#zI*Mqm00*z9GQfJ^wWP$G1{K@p0* zczfX8pX0so>E?An;H~LmI%&WWSvf@~`X{~){V?Z& z%hx&%SZ6K2rGcc@GZjXm1j$6xs+HGE0se2NXOLWn})lAPp3E@F+ytyL1mQbl)8J z7nhdWrG#cy&)uK7-WzN|iTr%I2mXs##(Z~2g5Q@t5qDjX<`VEmcY?v-HOxFgoYQU$ zF*wE&LIHqc^D?DAuvZkRO{v?rNx7-3eSp2u0RR$TVdwY}z48NQ_lJYV>|V?%t!nvZtREYa<0M_fS{JN| zuLk*We4tlo+Y_kI1%%~s(%QpAY8U)-wjsDXJZHjvkvA|3`!uExvp zA7b$T$`aTdUk(qP67SJXhrMtMr#X`fVnri4@+K|iR8Oa8k85_R{%>IRB%fUfj?4)FDrG zazj5@9&>Oe`aN~)OHJtHkRY71ew4t>V+RV!a2pVW>T z1s&O^V=(aKL#jn=v8#c3L&Sd#a9NWq^*#QpZRzAfC3FAK!Fku!y*g{C;SstqasYQL z7QnW9N-*79Qs;-|p(L7?AI|U>!1N&7Bn_yV#_gvZUmPNeuFrVPlw6!rt~w}nRyLW_ zAo}v4^HqGP`{Ql+Z(p@`n?2&WHNXI-$ypv+X;N!@{n<}yfP$?vXJ|XwFqD^KNDA!x zR~&t<4(|$!F74~V!Am;qLB(BVnah0p7G#)QlLF@k7@G5l@0T^3>L6D zW6rPn=Ma}bbrbxl8C^4O6WdI3YT|C}VUg{P*X@dIMDI>2Hn=}APd!!LAkG-P@Ov>Z zR;fmda!T~LrRPFi1^Aqfs#LvOs5Wm;GK`zbYUWLezwc{bUp<^=Jq)--7w)7LUwum+ z?)}6vEHz?}UY$GX#}2UOcTXBJdwnn-$zLUHbLx%3yy%*mW_3VW5bu6i1lE9hg<;Z> zAres}m*ebc*s^`sP9vL(a#^SiCPW=INnxavJl-zEkb1UcCI18#N4 zy}Ew!=wYwO)Y-0==N}U)+qpLB(m>$sFv{dHc?I50PxjPCKQUYT33hsGVp~ZN`;%cUroR@x!SH61=84-mmgl3cgJWIQh}sd)Rf}blhH3krsS=d@n3c zKgdw;=-@nB6<5*V&HEPzkUQm%5~|B|la8M1n1Mgy`bA|KQ1^De?Iq^%GWbss6P{0x zM!>eb4uxv=x^=Cq;TBK|Sax|TR9$9Y*lSDnHiseF4g=A1bP_i3bt3bo8#bMKa-9H6 zD?Ol$+R01L7%Fe^y8QbyKX`+t5Xpffh5P%MSFw`*?4a?z$w$ERTqXHeaht7qm$l(u zlMpB6MUJ6ij9s2~G2bx!_}+=~|53qD3&`0*XdqR(`?Jl%?*#}AhEb-O$xf7ly>rhf zYaI~O6j12aogI*|Y5XJnVY#U$cmNCGMuYZl6RqsaHgN*a(LzD;%S6V$Io}$ER<7{j zA+IrU65D3Qx?&i=oz=T~3#U)>g)rwq!j#bj+%q_fnID3M3A>gQ`VF=l_!By<8(D~i zpuqfMamEklOw|`LdE+pT0D9L@+VYc+=fG{sZFjf;6nju%a&t}(^VmXdmb zu`+4QI{blpH|z8B$~M>RlcLr1i=9%B_%cB40tAO3Z?Ddti6^J@&x;2- z($+h$5+|S7p}5QIhA&kg^{Tfm^2Zp&q}%kvgkF~|{R;L#MSD-?_b1IaV36lVfzAFK z6nIs>Q~1mqYfP$tgiL+Bg(HQ|)HT^)_wqPXmW< zvPHdY^4s|x&mS;p29*{N4W2wJ0u_;adqwy2R&5a46Mp(~&aWud4#`ci`xp^HnAT|y zIC37|l8l|UY_Yindpl4v&3ZnoAvRLumOWSEmXoh8OJn%^Xk?(_VPyIVZ^zx$ZgHz| zeDO**8COvu$0O3E5La&hW>Sy;LF@={WTsr?wRz`4G#taNAjfAqls!O6o zhNW#n_{!rcrK?-Cf**f6A&#V4SAZ){RDUdARz?mn;}?9ZoD9YURl4W3?u6q)S}etS z_HA6U(~_^eJBwRahlY~;jRlKZEzo~P-*A9%G{DXC-nNxnWm$I_kWJ?yo zY7&@S%x{8l;VOKFyMtfPCnG`uk7#q5iV~9}PHU9J_%vR^**C`2fhyc{4hW5%3ZN=A zFL7g)t>LBDx&M26t3-(QNUJ0|CGHmYHnX;TDd^E3>V%+5Pc!T%Zhwr-CF3GID>;d2 zmREKT6R02RSR{Id(9=$r*05vldw)`m6TH1GX{ITX1LE z3Q3mP{K(zmbXznn=`PfNNNY&b6Mv_tuB5!F1leHwq^nSOkt+FJ*?Hq>QdPaJvqhC4 z$Jlp0CKs%a!Y-ne`Efa|L&E%A8`M4z^haTWjpr^=k2$54li7E{m1M?Eusz5|c~E>c zPL7R5KdhF+t>r4=L1LTc7jY5=r!Tb@){CE!LIATO8*hllA0^jRj&}!%H9_c#UP5KX z2158;j1h|2p-toKRsyLyk)r0=1Yh$UbF+m^{b4$<38!9!A8W}*VKdT3^2sVQ%PpmS zZ`)Lp>Uiv6mP(ug%5>}`$9neOz2V?ZuK8Y-J2^^DfK2N<&B>sUG<#sH5>olRP(je_ zecP~gPodTQ&nrKt6a~JvH-_8(o@e}?gCd14=@p}w-<#3CpNA!^JPhWmzNYb|ruIld zDg33(+A8xFveonQ$Tltg!dhum_Cpj!?1mD=yYHILAiK?NZ6@i~Z(%CWW_JGlApd9J z{7)^&@qnq>aq`RZj64MeMH;&;f6Wil789iwcKnCs>&kX&AU=sP`4LA7U<;>@B~!&d z&eo6Rr;?_+PF%PJzE~5+b?!T#HK*W#XDe&sg%rSN;4>*huppVYYHl(K8MR)-AeclE z?638%sqCYoIuAM>%6?FWv&&n{7Wp+CAO0nVR-gokvu%y5EnFTzlc+^C3QQtb>!Bu!9Z&*IVUFZjXPCKT%vfju$RQAk`IwVZ(QsIV8qJxSk_p6 zXsDOueiZjw*5Yk$>v(D?0P>mKq>1IKCL5xf^B#Wr(++Zl|9O*NRq?%Fk0 z6>r>N+vj?7e7#;D7OMNzcGifgx6>^U!HIa{Z%~s`f{ijq;t{g^gDQov16oW$ls`{g zq(Q*z52ScQ+Y6`@l?l25_4BV1a>QbKtFB*u%8Sl*D#7U00-a^H&B|o0G>T8OSE<@d z;~KuY42EpBFW5UOcoJm4TOZ#CkvbLFFfy-23jK7@paB9b6q;8f zN?>M3D<`GX5Kmv`3>ixfvh5&pt@v{DM$6Y%b8`ow?$NkO2w{Z5BxV@Lwaz&OUjT~& zp7=?Ls&;+L;nBYG2h%JSh)g$ZYvN9SB+m=NV7Pxx>ipnS0pV2;!Yn>uU0}D-{8g^1 z$q+R_C}U9sB<`r^aI}4v#LM+;{JA}i1@R$Xjda2V3cJ4mzG-Rpe2{O`(Rx?*oSDv3 zK5PI@{^h7vfr6GNTS0kC7`&JM`57q`fGtWZfRoC6>?3e3o!a&f!A;F zdZ+AiCDTo2wD#Gdi0oz2TQe`_%k_(yqrJJciU1n7qKs|}SJ5|Vk(PN0Ddtl=HUrc; zb}?F?dTSc2Z-3d5^ckLe_1~WuS~7z2>#sJ%yScm<1DmyM>XnU?D}ft>)lVAU0SBB* z*{~Rdn*p>NA9|Q$Yz(fXDj4zPEjl5WuO0|>i2_FVvlQ5&;!ENC@;20kNaqPWcTy8ztz`!|15%}RbmHa z#|V4!XL0Wh!|IRY+M9?au){SpcH1Ddg0?oTt&!TKI}L_*k`ZoAFP=uN;-8~JM47Kk8s79Lz38^*; zKICGQ^zG^RnTQ$pXo>hvH{#^;7Cra0HdNbvAhJM&;$D;C2$N$=Hua= z{6yO{3Z*k&nUUwAqxh&7xj#OfAA!vbp;G{VI0K_#@%PsE8ZNa+tHNS?ieku$*_gZx zJ8`^LYy_hhto%iivI8;YSU$B67AuJ1Dr`XyD9E{_1&>LNnD}$26>3Blm#!#;_;~vJ zC&X@$#n!-B&_xm7?g`i1qN5eB6~7H$@1c%@YqhZG2$vKDtwv!#4NqL~@q^G;Q!g9J zm;$*E=+mj(MkJRv5E1%Ce}S|PM1oR_i6Xq&dIRIuoi!ya_0G3lYgDVdh=m{t)C(el z6%jnvk{{JW#xV`aeu2iLT#efqKh@G-$Tv(D^}Fk1h25hQWsW}|HmdpCc^{8k2d+HM zOHg5O&w;2li9#!P#jN-0;Xd}iC7x9ESo0qBB4KUpt*5q(su=i_{t^wLb9^k1#c=of z_Cq2!nWK!K6B7Mdb}}3eIbXkKJf=&YXgxWnfsq2ETUsbxl00)lJ#H?J*3z|V{O5Pq zKJp~Fd~azmLXPtg`>8-@>;F={=ncZn-)-QOMK}Ho&~|iDo{QKgyOqRBJ0V)}O|kDy zV)NK8ZVP{;qfy;uf$XT6jRpG0qqpMAIhO37dmHDPdw!X}8~&Xs)3_xP2l?KRU`M@c ztMjep3+BIcZcv}bJj}SGg*DB@uan<$esL6sB0~dUg8b$@_bl{jTtSS7IzSS`Ne+dG$$sN9Ai8+Hw%Cz!iovS0L z*v2Tz%Rl_U<L@HhiOg~fi16S;a3o+Bbt9sqnQ?2LJG)d{#{;wWiHQ_QyM90q=eIOuhLSx;^36^wi6{xf&Hcm(hJ^T_Rk)}(F{_-HR&DSNGC1WQp&#S=&{M$Y_<%K* z`rt#CCzF$suXdyrE1I|4`swoGzE$d3J-Gg0;#qk(q4_Csl7Qv5;VF{hw^%MN!5>i&})gO@Sj;@ql3H+ zy^VziU(b45ywNkviX3+J9NGm)O2g{<6&rfcDXcMmHpT0rV#Vg7oX@%o8K(xp73UlD zBS;z3Ftu3=`PDnCvbaDlrZmo#KjDO$o16tSL~epCx_?(2@aU-xX*f%JShz0l+7uA( z0GaE&4MC;vun3VyBe;8Ok~el#tD$-?^J>n_^6!@21H;pHduwr!UdF|17NVa z?*_v%DKovp`N8}d`U8%%6uJ@TN7|KvKFsyMeK3x))rN$I3x`o zg?Io@n~c&J!V%m#{CX<&?TvoQm2ysP+om}p8xEnui)Jxscus;j%k7UOGw>T>_5j--is9!*+GVCGTx&A>Dspt+5c@rIqNpDD)+QIQNvU1+R z2HemL_}E|Vu}cSZC7oN9PaKMcz=0O^$XmPTCJ|&UM9`|PfY)>{F>hK5dRL{C^>Du8 z#PlTPAmZdvVp85o01exjU)6!@(l(JfmBFs-sY$J*D<(jO=m6@-w(@--O8^_&S$gS= zT5Cdj+l;2MAsj3zHi0k;NK`cD;B{idannFA7%xu9t>vok)m=&f^nD}#UJGDynOP$5wMF80`M)_8uRHJ1HR>!?UO&79EWt@1_)T7onX9 z2P+MQV8W#UvH{)F2fvdg%Ty1U*OSO)7H`GmxgB%5sw@kl7rCpGx2Lyc)yL|si6^R9 zxLy=;)~;V&&9E_SiHOIyMtWo`v*%+61DN2=SC|lnjwy2vu5f4tfF}7-DG59TVRFb( zK$1a9t(Oz1VBJZgky@mqWLia73B)f~rTB#t=0x}xumxgZtETlNa2N0k@*KbzB9?v9 zxp!i1a{Ee6u3k0n^sJ!9=>SXx$oPFp4>PawjLaf_G-{KZ&6<0{+K>WD~im=Y34 z5Mb|^D{S-%eN^%s1$)6K-UVyb=jV5q$@MVz*rcUHSlKpMDrK)m1c6Hop~++IE@oLHJG^~SPHZERmJImOtK2N3z)h+&D z8h>QBKV&JfvZfK1m0t2lx6*SPT#$G`rCf$aVd={(~l!LVI^pdfp1qGRg zWv?p(7Z+>%*)h7(|0VNF#zalBxd!fWnm5d2lsVn}SuhZYNi!XryoAFUejOeT_hgGp%36k{F?@mP?O z%ZonBCrQUW`4P(xSMWO!B^E0A;dJtV%uEkKn60@!&T3LtBY+iB4kaZitu`?HDN|Fy z3i)0pgeN$`FnZb`S-{yl9IKdKYIlM@b19J0q zUhHTfdjC9Ta4Rx|BaNi$q)8vS=ve;-fLtpd+HYKjRrBzk$W_dQ3t;aKmL zg2P4XFI#4LDy4$w`n>ksRefyL{|}nRdWo;sZVk zBuKW#KbC$x_kmeq-i#W7@2UdcKEObf69Li1_8dNm#Ii#4~yfB_R3SzIqzHV=KlBV}l8T#cm_ z->Ld_yc9~BsmH&y{-1ZxqJUug%fC)us%ke0GvD>p4Q7RjM1Ra?XMguW`FaY^Z<4xn;#VpAp6U{8>xm9P%w(M?F(JAFS3G65qM>q zc+ zVK$?R<{J-bOVN7haqV?xn=d@_5%WG2H+v+5IV3I2u`02pVHBa&n`thOg|NBw+FX*n zDr+Sjzn*<(I{Creqo^{@qgO~y9#_6Vfr6e;U{YN6@`EBmLq4aPEUS6lkXY(!S|sm! zZgY*$^5T79p5sYL>~RIgR3vQEV5AuaW`FhX~xWwQEdm+<6>h5|L3Jn_)EWikKtbrM8+5kA>wKuvL2pO z`SXG3h~pRoe};Hk&Ba`{$x+hobz|nY$yBkC{0)b9t@qr+9c~kjpL%nNLn0;GlUrQ>|!q; zvW(rj9>|Q@)2PTZRx8L3a7u~|Q-amqs$z_n@W|J`%1aSwH@j++sF{KAZ$3mXhuZE>%)!AyW`p0_}6j z{6}leIq$gMOc3>B)*D4!kG!)JF?3sc`7d4HfpXQIF3lA$(@Wa1aKL9fNA9Cl;Bc|7 zN)qw}ZDik$HQ7>gb_z6WrFYn?vd^t}`RyyS^8Th}n4jjlSlm-8wXqW)%|Ea4DpX&A z1Y=9P_!CQ3-|dq%?H*&h#h_(Fq!2i|uc8$LWe{Yw_#*_;d~CWee1|h>ktH{8en~PD z`>mr%@L>=&B1Fc%>>5swa~m_w{evw8e|A>6SC?Zhj33JMrS;&{u6#uyYO7<$=l9^_ z?M}GVl(ld(^!--K&Tic7qF4`E+N7rVJZtxvQ+HZ`c){7ilgsJFn~Gx365(@>?WOd& zp#Z=WkqS`%IEEFEiAEGLIo>*vEE5|Ut((u zuaU(HmSX5pIR8fkbo0WGpwntb54B;X4Os zz!OZ5*~b2z?A;X&hz>(Q?RwVdmf)sLeD^?WKT{ak8bUx^TO}{M*+)jqt*X;RK7vVN zY|IeW*fRRmH#Q^+Xg0Byq?!VfjR1(Sgim26FZico6p)Xpp2y>!N#ahudPnyQt~RG7 zAKl^p#sYc|k0Wzq&w84{5qSF$C1QgiS3jVHr7Oux-GZh+zoR)xK1Sd?RI-qZ#cThaFP|A5j^klPFDK+nBG$ zf!46}j4ivOiJ{LVxd0Tk$?sQ~mrHgWL=3?Q2=0qri`sLnz`&!cub2?4-nQWqDfwN6 zI@z3hM(GCAg_C&Xo3WZZd6%2@?xes7GXl0j^1GYi`?)dNz@~Ge-}kN8KwmUtfa#au zJJ)q{xmyd`S#xdY^tc|A97Y*Z$SI)SOeC(R5`d()L%YsQFGR-Q#P zIjNX^-p`r$_<~WTyw!D_XO<7hlKlZcXc23GFp{}Ndzmw+@6o{LMkDA%haaPm5#*wU zOSvD-nh+2(uRRI?-!Old7UFO1j`ucf+vJTUi&+!&?BkihD$Y+S{}(I0daV3AKfheh z>i)Wh9d1GSEWf^;eiD&G zRV7gDJ#6fy`ykNMt#9d6BQ&VM%|d$|=i}k^d8iK`*PFT7w=z@txEDpaE4gY`@Zv2G z?W-o(2_}S^$XmQ!R6!A``QF<je0j7M2g<`XEn30asPGT=R?`e8XX9iv4rV=)Jte5!} ztmhe%GTBG`bg)rqq~N@x!m#I7kB|tDxjd=&VuhjeWJqd%x6;CMzGCf5g^X1S%b4-~ z66u}%flqR^f_9OIZhCdYdZohKjhXCH0K*jD0jFyW5a!h%Q!Z!ph4N3W*8p6ar#j6i z>A+ob2kY8nnRvS`;zL}!b0>2t=|R#yQgZE|RNI^Fyu0#_+kMw`!_J+T!mz0T%!@bA zV;Q*jq0F^(FMqpm)#?;9%+BM)=&}DkCadpd?@~7J~?f#v` zi?ojG%^DI}O+0BUBLkORxwb97AthYS20ysX=dFoyy+OA0m-OOFnVUY= z^E!t*_iQeJGe< z!}xcR@NV|o;`yAXwi-44>6qbv^1XCk4)Y#-{clwH>8hctYfZ=HpsQBbW1gAYwPbDf zMGE}C6FwvFbqFcTeK+vFly#eii)O^SyO9Mvl27`g_Hai^=3!Vr`Wyj|6m64sC(724 z|Jnmu1#w~ZyI{7|6`;oDwq7Z5EcHZY6+uEM%ZQ~{6yb4*JMALVsFxv6KQ^ZXx(IiN zYS;gC+IK8{?3HMynCYQIP9S~q7_N`T*y)}<+TVQCFQ4Xo+-m^qEW;i2(|&{=!&gKf z0^W7xx>P`SJ|1vTFp);k9|(Aots_L@EKeGNpxrb{3r%Pbo+?7d?a)_Hn8Ky|Gtd)z zOsDb1Gryc7!ttC(e|-%Wkr$W0w$U)t8q{uf{(p4#MvFXT#6lZY@3#BlB;D*;)hK*G z54DI&PORU-<(0|i9WM`0!;Ep)fzLI4D|-1@F*!o}ZpMFYCe_C2t4{iXr{zV#Y2JwM zh;RKH+gKR`N%3^?9x~59aCXD<9#Qabo#%ZbP1`Mbf1-<>7k`XNJE!i=beb{*UAzL> z{YO+|7_@FU0EDfZ23fG*_lyf4Zg%nV$Ofvr_|5vS%N+W~EBtCdXw!IiF!zbhx6vo) zW<}txfKE1Gx(ja(DEuF7L?zAmzTN8f>t_uC`-=xjme(tR_2~01Hcu+PWX&wGKTYmA zc4yLGPJ9QZQbp}U%^mVqZkiu2a%Ij~-U~9{M4we+a(9hKe#!pQiI$4L z3LIrkcNu7KTV_A^x16wLsUpWSNz|iS*8jytfT$jK?`i7Aqxf^Gn_CEgj%{5g05j(2 zcQ8vke*He6muL&A?)0XY=h?55kWF$%tm(iS(ex*b6TD_EFDQA9n3|fJaF+od6Ddwk z{Uzaeopa>>zX60)0o!;Y=|^u;P+pZ?Do?g@kqpofe?gZjT>yZrQ=v0sF)AMC91@Vc zUN15(F@H|nLtgw!7fxqqpcP&^_Dx&r94BbumW7XV{g5=j_s2Lk})? zC7dHuB|$8s>Qb?f--SBU=yLl*IUo|iHO69>5cE#D2t#hEFSnL|^imP^lFkjg9~-4n z;|9rfn|zo(zMRCwV5i^zfXYm--9=i+7RdmsDbBJbk!}bl1sLSxy7U~4S-Io5&jS=R zcKIH11tLr>G-hnbIORcpc}VZbB}J^5oSJm|A&;n=#_!OyS%EG~ZaazzzJbwirNh4; zmN(Gb(fza@)D7mP7)kPjL)Y8_gq8h>z3{#s>CLtvNh8?3@KQepUdPL3=P@L|KWT zn-|<4sY2vJg(tJZD*q=k~@br<}H2JQd z#HQ|val6e_>m5V7ef!-v*n`)FVo&1C={$U$u*{;z0o48h*qYfeHa9ykSq?5%7SOZmEQzPC? zN8frWAK~W#gI&cC`ThCVocLae-AT+(v6f1ARrCWJ)YD6(%mR2BQOXf(u0Udcf){$bc1w=QUXJF zcb9ZOb6(ed|F-RZ_BY2raBO>g*IJ*2r769^;LP!%UU-=0WAGzAmCdn9BXj9bc4p7U zin2F!XZ9&wHSQYn2Kk0psj+`dyut$4eQq}hT)y5kKYEoF0eD%8nddqssBP9j=zEZ9 zBm%fv&(`yEi7kxaXu&SF-Qn@kHJE*3gcSN6sse;0;}HUfl?@j&u?Ny`ffo}P^;jVVv;!8sDP3C540p2i#nyYUZL`<}LedJ9BSP27+-QqxScX8YDIAD65WS`J4 z$^6(V;&=RB)Rk=}nizk^;&1o(jp;ZUc3Ay-y=k=%6cQ@LhFzj$ef%^`Qx;Q;fOP$X z3)t{s_*s4kL658%5sGLzIJlg zRdgql2-Ak%+gM5d43_nTgt$IcT@gUwK@ji)tIUF4gVW6)D}F1xpmGB)Bc>p*P%)Sn zMrK6wlCvvBBM7?}0Ad8~#L;fOyp|38qEBzmRgOD@%jfDA^Sz+sn>C}QYyEO676kCf zwSNugzEv1%kKTf(5)h{lFbL)*0L76=9BW6Q!h7H52_3tz3>Co)^8h-pOfvWY+g4-( z?gK8&ShJs7OXslmU6+s4;B&zwnbNAW@0G;WEQ}vpbPS1{rbbofAf6+yq*Hy(DzrlwjCaTQO=%De$3~C2cgm`ev-fGbx>WuJns2DGPMkC_( z+|M?UY@Qudz^@(4!?W8Auh>4p)mX7pwVQoIaZ|<(#V_MI%9KGnPYlg4wAoYdVp}Bv z)g`rPq9HZg3eAUT4P(7SjVLk?6h-K&Dd1gX+B`ZSaX}6eV1gLkkgzI{i$u(cX9h?q zEG^En>m&$w0eY|sOP-n@-{psD${vhZ6~Yn>ccYZ>kZN<{;?q?c?b2B6A4%YGdUNEV zCK^Ub##yCQ1s54Hg@7>RV5ccV0f1p^YAtWknCz~w+U5kt7yC!T%aUSjUaDNI-LCLw zu6jNO+zoI@U*NQr6ce=%^oklw?h9o1ohKLK0O*8?e?egEZ2y0rhE#BYD%YAqv=D%R(rm$RpgHhmwuBtVCb^I<2{WV1S7zogq_zcgX z-$he5<+Xi3%LY?0&uXxm`@LhJw0ODf<$Y#MoBty2wEx9JblD7z&7x(i`Tb^jtG1tN zRKf?xmeUcnb<6wZu)n5trAfUf2u)zjbfAH0rO}v-X^j>3sZ86$*K{evnb)*uJE)u{ zuE}tz1oy*|t?*aDwiD!o9TRjRAK7^t#XSS^TZw&JP;M2A4W?lVb=GJpmxO}@WzNf5Y{>Uf5pNMsXN8Oiawo4iZ}#;Nga)GuIMc#S``XXv@8cxCNYmuWXIgX|A|jN9 zd0$y0%T)~bcMsxoEN@u1-@Szo+Btg17Ck+!`VZpjzo#VT=Tp!=y){4dO7c|~gYIap z<8!2lFbsjUK`>0?;Pw~%F@PDsGaILv*NQQ_2@JrSiY4NU_@|TnIDpByDVrT9Hw)N( zDdUf{S40xUY&^Ddlv@8ZRFv*Mpf@2>qmkXf{cOVO#doOG05)7*TRt+rhR25)kr-dK z?mo$bd^5*dmLei1vB^X%a2L~{p)({eBTMv#NN1&}GJ7|IeD%8;Olez?M}!g*On{T5 zf8}nt_)a>QK_k^I7=ilUF!tIK^6Q6W2-dsn8O&Vqgjvr(U6~E{Gl1$z5=)GUnj{}* zT?r`5CI)Hc#i)HoU5A3UrB(Nrxx^!BbE|-!90`5^P5p`VN+f24^>Xg;N4esycduDGFN_@+<~NYh|>L7k-g6dIMI_rkp}{13%aw16(bG zHAJB1lQxAe{>SJX3~C5%=GZO^a>%@-xXOR<3X;Cei~1w);b)AxT{T_r7n9@L+<_6j zTGnA*AG+T{5X&5?(B3ZA^$jhysC;R?lNxdVVR6uMVR3cYE$2KyD|wP=!``qv zS)Nq7s|+BG-nj5PyjaT)>ypG{-H`yYA?ArQy#9#%GlY=lX%`+0*y+p5_KAIma@UbP zvh*{!$D}o*7{uZ2Wlk3-QtSE7t*_X}wRg2A7k_%syCG|K$yZW-I4*28Nc |J9Ft zvtc~Rht_6r{6YP~Tm3L_Op_t1EU@OluvqG9CwA~z;7N6n>Y<>c3-Ek{XM9ym9K1Ci z<;Hnm>vf?1qYl1V8O#c<+T6j^oDG-2lI)=gtx;{hmF0ztJ;8k9CU2j`6y)T{|2zGo zWnhSBl={$9Yc7d5AT_bG$CT*vdUhO- z>-5TE3JQ+o`1n5Ad>Vi2_G|`TOki*_wzw+!J=S7&oF)5bTR<|)@)n?Zz+}sezdjR+ z1A>U|h?6?xAL5m4odFNB8@wKHLIXUnIe_?R)7O*o04DnvkKSZ4V~JzEI0~+OC!KY1 zj@u%(+4${%5@%^(ID3+msa_f6KIcsV5NXeIQ+|eOfU-c4{8sS@AzrsE3PZw(XQ8>1 zj@#8vk_KaI-1;zLu*a5P3z|8^z=D6`a}LBHe4*XG*1|0b){KGv$}4OvG|HhZSX@2Q z-eo-S7Mckp-+u6M@^}7*-p})LN~r{GU@GwFWTzy*$u8WEmvtqPtRY|IK3PpS^9piK zUvZxo1pb&fcn|RkC_7nO*lNDM8uYhVxQLwHyU~lolgxY5t2A99%Ve{n;e7$KWb?m! zxDWcb;$BBrSBP-pssF9()xt%qeYXhmoMN&^)3WZBbL%~q=RmP&uRej7&2nR(Z2*e? z!YH-OdB<4<5}Fo$dgO4ot2E)qHBvN7Z}Y3;{neivu|G`yM;U*&HT~w&eS~9rVDDd} zi>K9yCX^dLSW8mdrw0G#_%QWR_ZNwwV@Y}KSu~EB8AXP=XC%P;tajMU*L>IwJS@B& zlP9Dkm;Vt>rD_>!J#vtCrc>rE-b9VGu!k>Ntm{m;_F+|Rl)ujsRW_iA)brL+R5?Ra zWNAj(Mm+mCaLfd)IjtJDZih{A3-=8Bc0OevpJk|Rf9F5&eWhVKckqR;I(9VL*L<%m z?(XMFl)WL##G^80Rfc|)jA<)oG}WhX81sei@6rheLdEjC+hzT@FLpC-i_gFB;~|{f zknhF+C3oPoxGUg~#ImW`jDA-?zeCA*^Heag5#16RI6zbaKG1H}(J5iTO*;X@Y%fxC zeiq{Pecr5}H8U6HH|lm$0z`)GXV+2T#UrI0o5_rTk@c-CVvn$vr$OkHiACF^Uu7bi z^{*d&64|Sebj=OtYw8G4NH?LJsDp?hdbT_RY~t9}r0pA;h%K+Hzj|p1lLO}9GLZbj z>iNpKFok+1fccDT<-KQ!x8$kUnSD$osA6kv^-TmTDWB9%zjhBJQ~(8V5VwcUX2gS{ z;2_}S29Mj>_;aYGD&z-i)RX!uz4>O!DLwHov3f=$TS^DB6dD=mYT_Q=xg{i_$c|{U zbN{W>s~87^um<#eO0NVMVCg5H zG~?3d{gym*bl;`#j>}_^8V)*DV`^5EJ*hVA{j;uSyPCTGm*%h;I^oo);CF4m04o#H zdFhX_o+=---Z&TDY;f2tGA)8F?<^nW?`K_Ze<0e;Fn4u_ibTifg-y^nstn6O3Bbz@ zNz)`AeV3+yH%Orh&WSU*u8`i#;kTamlE$qyCVmg{ZQzHy9Hwem|Gv0d9H1-FSKM&Y zBnLgeQ5U|4K;wKKKT$*)nTs)W(^cB!d5>&Zp>^s|Td8V>3+cSc`niY3GUnZ2*2bVn z&#pX7sL8NhS4SCZgO>K0%cMx3EY1%P(S|M_chdn1SURHE+77{?(l$t8txQ1)W+Ijb zGnKtw^5H_UwfEr^Gk#wEg@>v;4^aAd0HDh9H(y3RNEU0$yFq2fWV4f1GA1^%r*vs=juIi+MBKx&mCG7udfacLN zKb+EVevUozI-j;*52CSn!dL+eMl*iEx#N6KY$njNg7X2}E!Tv|ogPrZL?)mU_&9n) zo&o5p(}u(rM~99GUtZo&a1xhzTKg+17N zkcrM!VPQaetOY@I^%r8CH@7>ONA)j8+HqMJnvaLiHjx) zzGLfN=7!oUXY`Fq%$^&6cDzH+hN^6LJV*)Si~0+f0Z=fc(q@S=FGphk*>T;!oIabH zenw?(zb5a}sGz|x$BlPz%k4R^UhITYskbDSV zeQj7|6%!FB#WLPyYHRU$6a7{TqJy&syJIIV=rxkb8%Dh?~%OdpZ{Xa-)rYiW< zoY!tC?(%o_G4jreY%nr(qc1iymu4$e%xE z!>)_RpWxq?=7yG}_}&`;ehQQRIPe#D+JYEiPm!VpAeJuq4F-fyNb5I3DD~3~>$3r5 z*L5weKB-vMRbeiZU!SdZj7-wkRQ|K8_$}0e`vO}y=SUK)bT~RfIVvn;Wqx;32A0ua z>!PfGeZWaH6Tm((AiQd3eS6j{NSrF|p{q3UEXTP{fo`c=ty@&N;>4IvAR3Bu`+TQ4 zITY5hE-z_bcx*VF-Z9aYZu{n}0~2o%ENlRXFR`@;DUps!E3*nvLuMwKF^2I_kwhcc zQp`0rR^70InBzO6RI>!A0_$`B00Kb0r8MJ?x;f@p|*Oqs_>{k%(XYW6jR9rwB2 z1$7o72kTO-@LME}))byj!Cm;cSQzzABRbcIn)Be@2hP?^1mG zsua=DA2VBBC09JAMduUy?agr3n;JbXE>fa;ballT-s4=PE=Qa_k9q#&A{W_eJdSmH z^Tw*qk8M#8-Z8y3d3?v6^-`M8H_0t%3@S!#VK@0Eah2G8rPaAS z7gYT18?$G()WU1hG7JxAXJ^M|Q^T=|jit2OrxApegb|M|?o83lD+HwOTdialMht0E zUs%qkQxysej=#haD!*Ej%GP-crf0fDJtb++!!&g7hJpbvrC-|C;bs8{%xv>?3hEVz z3QE7dghe!Q0OuuJJb-T*UH~fekl>LIo4ibn1@@hHOEx(|JExv}PrBIZc}9u;?)imm zmbx+!i*jP0x#>(c##c{td!|2qZaUj=3MjD+k?nmFv&}i-3I{P z5=mK;4&1t8aR-^whc8C_wpvkAGv|>Z(;%j;^3D^uqmEjc(=K)vn6fL3M$X}rU~iw9 zSVwo#G^GZXVAv|*s?+CPKzp4?;=Okm;A+bOeb)0VqfM!z8SuuA^?{+;s$XV8tLXP- zTmc&=jr=8@j=aa0*s?okN+p5)HvwSxdJ%ZY?jGfKlw`N(i4u_M?-^;L)?9^ zcP%xg={+nh?4AxJFJEwk&5Z~bi|(xc`i4|y^40r+>CbCB9oFoVlhfvCd&p~A50Oz0 z;%jro?0kxnC6UwdRm>@}PS2d^>xBiPL2R_35j9$&jHu*>KOMR#MP3fX^_Mw3;<3?R zBB8sLS;m2RTd`l%OoS_nq4_BI;2;)boIxX}X7#4BfgoaiN>hB(ov_q^z3^}>frorh z6{WmqKH_*aOS2n87aZOoA>Q4%4^=rhJQM>P*1`k!eC>kucGxsV>ZCo3OyAH=P>utL zyn6racl>V;8|KTD`g}^=YtE^zVdXDnh#W!{G@zHT%Z8C9uQyB4m6hk?S9~n#uW#q@ zt6)Rw?V(|TCVH~iLrW8l#XtqP4<&*Ln{;SCcFFG=IB8x1wT&}>`GII`b;BBW3TYH1 zd0nwfUHr0EA`n0WsJw0|69jb*=wjKz@vxjro?5i_XLO4n(a9u^Cv|8Wq2`!gUNq#8 zYd<{3%itP;MR=Q->k>3QZCMn$Ne?960z3yFefKk2sJ{Wuxu+*QDF7`U1?h&w8(83( z8F@9_S76()K;-Vy10ETBI{p0xbbW_Z>f{NTSj@f{V0Xwk3!B`ppS11hl2Ds7e1X!1@ZUnPJ{oH=aw zgfp!|8wF3cIB~Op&T!LhRLI|*HSIW!$=5Zf_%NLn$qyRMgI@fCB3x&5ZgfAEo;PDU--&EmE9{e+om8p`35iu*+FF$_el3Tpy<@^@ zY5qTgT@(aEl@_D<9nYz|)*b-DUBhr^;}#v?)o-w?u?bO$>#jt)VdmBj)8o`yQcFXe zWFp^gYlf?O=}KH^c78MfTEO*P>+&a9pL8R2|HQ~IO`~CFbLZE**5P$wMnBfK6Z zE&LVrOd@H72qwly3?s8=o&gS*8D0 zG=%Y#)|gH*10oR72)n|P2}XdD|5K;jo3{Zu!c@rJem_(1`uQ)=wBN>^Mw-FN^;gD2n`A>RlJ}p;~&w}lwNk+W4j5{ z)29=-Yc(M;Rj}{~;0t-m*SjZOX#kI2 z@mlvO;beH98)V-t%$;5;9fg=*LWiGN3602*iZw5_ZqUYoHo3XDY|!Zv6MzDLD`@MD zPhj)L`#PEr8MLu%rWQ_?crDGsXn!Zn2-`2dXq6)8agmo@h=0ldq=(JnMI|M|nEY@; zv77s(xd&~!x3;77^WzaiiAma@&#b}#6q_lB{aGo1G69Tp%REQH{pU0F!B5sp<`#Fw zde~Ws9kpFqaT0+T$^zDYNVnO^W3!J`ZsxxHbAt7w&ygr~k6JGnT>)Q1O?`n}*)s+n z^=@-s$tF|_3;m)1q1Kyw861I}U7HH&V z_6{@g_TJ2muxA0 zY^g9VwY{0|Gei_isha8RhL-n>+SOfAQZSI!4Bc6CJw-49oGQP;j|~O z0ld}UPbGjg+02TsKzK{89%1)J-PHx63GzkGJr5}%J4`asKbo2j30smc9SCFAY5mE@UDv5Ed7AOP((Qa~F(r9-%WdYE=q-COoEpxn@IV zYh3B1)P>@{543GdXUGoLsE=ygk9vO3K#$7ad0dZGX0U6Fh^wssPPCbxDfInD9eM+d z#(o3@QrdaO$Ouu0J$;~Z#FRq(x1|CXqaB=N$M>It zdo1a?^0^sfGwIK9SH*+c;R`ki?F>M7j@G*u(F z1LY?(c597(pDmj_UJKF-Ck~s<#`2?D)5CgFn({lb#mf>yO+`x9e{{bupf@mvMe>z5 z;yQPOumsXS@*(Ndp~jV(sTPFo?&mC~VroGH4H2?m)tnb8_E(~$3*BU;N(41{@2nZ$ zVbZ~X^jyDlkF6OO!Dvah?ba@$LYM;#Z?ET*sFeu1;jGStuDWLTo~@;+;9xn3Vg(C= z)Y!RKXC0(l`ZRa#>N=MhnfFDIGJ^@tk)c=^h6~9Vwd)FSSTPfeSt*8v?!KBVa`0Dw zXRe0DR}k1Vw$~MPmoN7O)vRX$EK|H13FB2;$QM$lI7jF zWi30AZtjK4YG>`^uYZ14bSZ(~DupLiduo?=He~I>44N0*l$uA~{s^fJR!2Ns^WzRl zC^nv_SF1TK@0kikkvIQb_@$3u@|*L|)4pFqJ6bF0*8W>wDQYp6TyXY22-6_7A7`v| zoJ`xh9)c%*Hmm6)CQth(+Kk z_7CH%(H@8;r6s#@4^I_{r}FfhvZE!H62D5CLns`7Zu?3sF)VQ-+_W|EFH--M_SBEe zLOYz+l5j?vfdm5k4z}W$*J}&F-WK5j9S`jZzzTVFnb0lM4ACwqowad>m_oP8 z0VAnW_k?tXDh_mam((9q-u2HSXztIi+VJMGHoT`3Tj_DJMZ23@z?9P2VC1t#cHC@u zjj?ZQVPR~O3w~KqN>8d(`tWWfk;wp$W3zFRF2vB!AFCK(TI=@d7w>9Ks(~=C#ErpJ zTJZ->=YNpik#@Lq7ii6$&mZs7SHFEQ@>_fng`{9`q(4ZWenNK$M@q&KiQnV z;t_85cdVJ0cQ@Jf>K^R;Ho36105zW<2ZC+;7UqHYhAbCe2QqGuYrhuJO(J{aRLM|^ zaJN6V6a2zYlqo1ivUMGxUI+YlBZlj8_jkdz)1P_)qT^z1SL*+vqAot%`18~7@Ay8; z_Abs4krA3F@K9Awiu|UEF#uBHuB8z0s?cb5-T|gO`2;rN2I;qiwanf9j4aQI-2NDg zJ~0Jn;4P(&m#l>|dGUykS9wDw(dl)NmuRYrC^y{n)fD{??5-+0+~neAgMl4hsn(5r z6I8~XCs`e(bK~P|m?JY|Y->~IP9yHNga1CZzqmYMV&X*dBFW~XQ8x`jpA*mschpsaT*nr|WM9=ch;vk5p!#9LC|y+S}+ zl^pD7tpaz#%f%Lv{3zD-?=V}ObD<>a7)9+GHet)4t|9%CzjJ(4OL?;=ojbhAE)lI# z_YtBrQUiEoyDSPR!cWgzLBUUkAz9B`bPmVk*n7=@vs^$p#f9H>Er4=^_c6@0U~K{J zivjn0n8l0|U~wYVxa=8OT0SyB(k^B$*tbWnqR$DwX0aRX&n@{8R=;3Ql{&Kje!XB# z@Y|_XDx3!Lxa2uq`GNML>k9~pq^%z*mOVnoiC>$8&)YXc+5eU{5NyyEJ=S4s`nz;w zuxC(EiyBaEHb{Px^}JM+J6%t>xBjC>dKvu@MbdYK^1v^82zV))FKsWRO43VMW*a63 zR%iT4H{!@Wr#BH(Unhd(Mc%M6_8n*jSBFn+N()WtBIR`yjSW-Z*$8|4K=1ECvo?zl zyEN<7-eHW{!VZ_Ei`Tpj%U|f%GViMW*~?qbQwi&W$7a;36ZxUV1uYm{rthQk<`e3A$xoeCnw*n1Jh?#Jc9&3a3?h<^C9uVPZ+jFyY(Xa zG4IFLn@mgtU3Jj}!}!hle%#CqEpnxRTlL>v?SI$ZXN9_P&y$T_)+p&WmTedzJh4Nv z^wA0&>)RLlj>-D>0A9#fGa5*7H)5qhYqa3`rKXKYMZsIeIxQd~{i!YR2%-D%Hs#I~ z8pPu^iWOzDP`yOs@zuH?f@StkI6V@og$j+=>8jG{PSafP`?F&+@R*N+Xo^v!0bp%F z@#+w-E);hm@*uw66#nx_CLNhu{9RhVFez#2hi`D=eipL+C&&p$O`$e5i8fgXwkT)$|u2lolxpT3I4f0fE}_7tn; zHq9+2sK?CS$7u1Qb+2{zH74V^zxvnP|3TLHN6nK{Q4x{eLkv3g52ME%vs;;`mfhW| zhfS}X-1D{*%X=QrZrkDCcK`Tj+}%bemR;=h=Ott5&dI@gpLp6GpKTkSUDXPeSO)lr z?G_L6Sv|4mIlRT7UPPiv@aTth>6|qz9#x&{Sv}`G+mn}>ohZDT8Jsodjz?FEaJ|0U zUJ9eA-SX_==lG~msj=5GV*h>Nd@6a)byxj`q$K;MsYYK5w|A~RWb>avcCCXg?fGBY zh6#T>Cm16v5&aGE=AUBuh<1hd6vwFFy=ti?rP6f=~ za`tp!DR8k95g|E^-&X7trYK~YY`htT>9|CoV{@lt&~^cCA<_|eU%Y;kdoK!K8iOna8nQqMMV#}2AI#+90F z@iMH-w@rp>qdabv%pevo-i^#8m z!m{-IhS0-orh=6UgEskLLsYLhl1uNLI#%-LpIb3;K1qgGqry6nrv>u93JeKet+$0V zC46SgL$-3exAf7hBGPF^88N$(Y^~0bA0aIBZYO-LB@FF1=Eu7(m5u(m>4-MX_inCj zB@ZL&8!W=@zZvWY#jRmpA`nUQG>Jf`zkPBK#-1k;lWR$S+exuvzVLa(qRw=>8aHc@aJ7`S^!#xgj+1RD zZQXs^P^Hsov)wGYz0>;4g~>Ty>IY91)3-<_k%#OuK1DDM23z&tbw)9UVO;YVt&>DH z9QtfZ(ZLh&-m-scMaMBGm!`S=taI_}9kCgyB%p8eu<^o>VBR^))*;2Is+!a5^={C`S{Q*qo z2D!^OuI^lQ1cn31V{@&~N&4PA=i63IZzL>*OLL4a;RnDalYtgjgne2hdye;n@$0VVfyQrAMO8(wMg zs1&Ng&Pz1XhccIm@e$`Q@jL*bG0{bc+>u;=g2GIm1g{FmkNEL7`*$`$fr9xomZ@y} z9P&HwWc5dWw^p?vppHN0N*AB2Nb!*4+)2;Hobq1K(cv{8-{8nc z39Y!x8FN|tMdGhrzFOkfqF$9K<%ZDV3Y@wps{*>GJK?FDX3k>&C$$sqm z_i(P;XZk)Jp*SRldcQL+Sn?<{ME;B9N2F>7lcRS?Uf2H6WIo20#3;((4`^l)qv4}Z zcPQ|Cxy5C|hU`cY>l`#?_Dj`M$-g*&_YO?#0zcu;*|CEO7&QVY#lPcvxgQGC*Avz* zzi2F2RCc2Yv*t4r%Tfq>dbOi!TnQ)&>-ovi}0 z$J*g5eE$xv5FUrO0K$ZI^P4$*@Pt1aSwQ%!vv9!}H$OacIYP#r1 zhT4CRUe!U}m2tl=pO1L+NZXJ3{PygXUY@Y_rv{=FSOb^$-j~%6V!NxiTW*{US^q@z zcv@TXnK9}pRs(&ooL#@Jh=btlBD2t#=EK&THB7fqoYOT0L97q-TmgQj&C zOdX+9+q>jw**K`6h+y|s3;HSBfM1{aayk$tv1^N%c8~@_HcF2B!mCa#&@@9C_CY8- zdQjW5o==wP@%9Uk2HC)p-ofaW_Imsw`!Zz|4nTH6?3mz7_+=iJebg6bWLK3?*r{xn z_w4$r$c?Q*L|kO6wsFN7af+Brt8=gMMkEZTw)A04Kj+a}cDAg7<93E|()bq~wob+W zo{HIJk4lXy|7pEl=bvqxot<4Tt&8RJv2AqMkd6e?@sqv+nxmN>SyDjl6d|5lu0-U9 zMi?2AH4s7#mXC&(R%hel6v8i;FzzJXd9y;SC-D+(PdFH5UGLK8nZVd^$D`PnVxRoQ z_*V~#GF`IzV)&G}973QCCmbPr@UmpUvw3w%n(IYauE)ktq7%?%)-Wz{S{^-ctuWfR)gnrGjkD}q z34o{G70JoOXVO`cg?R}^d?E9PI$F< z_g&EaTTuaz6!9H04Gu7g7EN~^di?U({&zXp)}W1#JR`(4c%|MX+xwGSN}R+TVA3GW zIS)lPU#^J6s~kK{U1Fq| z^*#3_3{>-BdS~Bkr-D?6k$MDCEl0 z7*fd)ZKpY)gb-L``)Ch34cgnr((j*gU;8(I%u=N#1b!iVc2OH<`5mjam`J1&@EE&^ zD<7*4^oK{i(Z~_0cA*3Qns)_!+c>yYpNMlofRPUv?DbFL@$qQ4edlQ4#Q^HdYL_E_ z`6W4*ZM};(8e>P*f&%5ezVSs@yvGpvEaJ=zyvh)$Kkk=CbCO+}Rk}5%$H*@=%O%N7 z=DMJOeyOwi#CMdIde%<=c)8@rS9vfNqJ>6dA{j?y8&wX=0cA^Cf)*0dz~aV7&O(Brf&pb(M_46b^CH1HS)ANA*-HMFfev46r z*yh|1@BTYmXCs|-x1~RsKIro>1eM6wl3l&!vE05*RO#-z7}M0VsQZYZ_kSP0O-{N^ zO-((2xNCdx@Vs0Owmq2pMCSugF!ODk>@Q87ZQ3BlRt421g8*FfaTHUsij3ELJ8fAf zxo*A5eLMZjfHf1ZMd|qxl*M@x)>qGw3-KKjVAC|KWV!QA_t_>FL)v~L?zN<|>F%jn z?y6?UqXGT`w+|>5;8=ijpsK;%eC{&a0cNKXt!Jz6c9K7K*Ae43 zvlQ>H|6$oEfhA3K=;SE|5iipWrH+gvUp_y!wqC*dD(umYzTKJ_$6h!T z1k@oEaK0quHQVCEOE+2G?ge$8&B7m|?Shl@Gcw0+N{CUuv%>&J2Wc&w*OHMqSplqH zh38*5Y;^zAt%Dps_a+hu7i)cn8nh~_e&c6y)&h8do_eFJ~F(MXnt zW*mCRvCbJ*PEZpjD=ZRkoIAhiUv`KlF|;Flx9p8{8PQjvwVl88Fep)5?fdp+74Gr^ z{g=+~+;dE0%)6S>B|YNmI%+@o40T5P(tv2dXbY^0?>UizTS7N7Xl=RecixR6j%;G# zur>&CDI5$+c7v+QwpSV-zTNGP^H{?c#(6(6 zNT5!Ge68qB;L2+SzCho-N2e5r15ziBf)G!}?SZ6B%9bW+RnXfPzv=q7OpKg8$ycoXpJmtzJ(+3ou9ILQW)KILH~$SKBy<2I8LB&NX+iC^br!db9zj(= zD<$xbq2rjW%=T&?qYcS1dHREDuyn3_;@73PQ-R$%uYcy~h-Ub^N8=Q;2E2vq5o7x% z-htv>FX5_?l5$P1__9T&?)~b|2cf#USM1mo*8SM~ltUcg&0Xvj&pE9Dm!MO@EWA~~ zSS?dRs!Zmv|KxV_UNvB0j!Qfgx{pmBTV$XYF2`?`=J!44N}jBqIqPu9^=-8CJfDg> z4}4htYgVSn(w)?SW~(tc-Kw9humY)&r80fHnk;#e*Z^SUD_r>CS|T_E#%tzTCpHrB zw}s+$G1qQK3K+6gxyyEG3#lDg+?f5H-#*)7s!>%gJ_u+=@6@IfoakeHKKa|o-D0~USV%}Q#xJU%vA7xAgxJt()|V?MZkZOO@^JJd({a%9FQPUPuFLtE@2yN|D?BG;$t6okR+>CXlX3> z?5tKKk)=Pg#d|u9MLFte?ZKS3VH8VrSm^(*Yfgvdj-dAgB9lE|h?wUOW*6^&G;I8> z`gDYicuOP@VSHCe6ZFrmEd3*(6<<33wr4x0Q467D^M zjxe^$cw?iZR@q$m)AezT)?tL6P4L7I-2YwQ!IL;wKL0vIw1 zj5z*$+pHd~PNR-_>%Ro~Z3Ns@UkH#uq#gU&wj=Iu$z0ph8m_&lFldKN+|B~BZXZ`m z&$ml1RzVu6xr{4+isLEX`tk!r&ED7oEoz<)wVhcYN!pXhhwuwx)duLs_(eE!@?>=~ zqgF1*9{N-lcj2AO0-#sG@FEClhqlUfF}j=P;G?O5p3oN+$!1G`KGxmX*+r+fq4%JP zs9yv2eC!j%0*Q=uWe=A({%pj^fdw2dzD2u?w@zpdmBCjhQYw;{J}nv&;lfx6-cs&! z<}CH2=oUt_u`CgJ<)%{b>9yAf@u(8F;oHA56Ttk*Y}~@v>H52nRid&135ElaB-AW^ z#qi;`80KPAJ7n4gVs{t9x{yg#I3m90K3~{tS33re)en*Bu^97QH8WNHKqlOWZ_jY{ z6t>%Gtee_j9q6X2ONDa!VbLh-6ij&Q#Sn(UO709AwTR7SjLmV!wVe)t%_mAU*Pka`ge9xERn7SkJ3hBO237Y?4Z6uiuvZ9E zuqvKB8ol!f!X5L=lFFTZ3t*fxQ#s0{Y2WA}0TBW|58aVZ1*rwOfU|8kjtO!8D)WS>7a4ANVl?>^Fc&^n(#Inc343nu49rGTaxCuCVe+&&L`p zKr79CJ~a?uL#7@QM5hNJegYeA23mYMecCXnKdG_H5R2Bu9r~`W{rfR=haUo}(_WxT zA*+9U5k332Qb1`g768==KUw;$r^;a3sM*gLEEVcq91Vg3MQL5`e5P-#9xLz;wQ|hF z`m?c|kzP<2CXEj0TbSFs@0%cC+a~lq4Lq=D2-ou5`gIVBsqt{fcShR2(|BjNMZH@u zi+IRJa@i{zwDnyou()Es;NwQN!>!MG$|RweO6h^q1oI&fhcELZdp{1`XwZ0Oy++GR zo#Zml`zRG=b9-6+nrL7=xxH)If;Jz-869^5{e{27XE&Ky>8f#xz>F<9+L<54;{cLW zHpg{-xl+F$Op{G*)?(QpIQoMc-i%|dO&ZitY*jUuuEeV@-x1B<7QuceNjxS)hMh6j8m>#Z6T=7A{c$TM5GHb%nAJF6v6Q{yK6lph zDw%d~_wwcMGdG?43AgOr4DaJc45ZQsk;%Ub@uAd@FALqa>gFgg;!CGRPT`|k0@vrY zOhf__lQLtt3%*KomvE>(qPCY{y#p&GjgWLLS$Bsnu^|)6DB~{<`O!H2T61ZkKQwcd z2h{O|z`3*N$|h4Q$|(nxG)x8qF4^tg4@jO)1)C{c0KoGjCU1>msO%4itXBf`f3;i- zl`2%Gq8>yXrUIph2{&5;B9^DmgeZ!}xR?V+A zzcIJtV|?8xyNiz{0Vc0d<~q8iy6!Ld*vh;>B5vMl?udcUuQW%z-=Dx$)Aaq91J=ju zb$2#N^v9SrvY_~%@rOQ&|DBCeQJqb)1B=_P#2&u$Shkv7Uth0b%tn7#nI6PFMSAux zKlhy9u!F-yoB&oaUlM_oK;bzy?D%V!x{d4J02hO6-$pv%W1BvipJ)0?`tbdwTp+_3 z|07bCQvC#)mu!e>sIO^*X?GJJ_7(Q9dO5CG7~=aY>~!#e`&HtSJ69ZTS0bNkj7Jtd zvZ75_`Uv<|%Z0PKz2g+6g6WeY{VZf*rg+O>h5J=`X|NtX7^5T>Vdi3bd1Xrp=ST7* zbw;M(ub01mLwYOnimDa=?#x}qdKX_tbwZ4Unp=+ba|Ne$AP&hkt0>k8GcUONabGDjH8T$he6Ga(t;X}1%{ zF4Oq*g}K4>X!Z>H?qrH~$#2yz+v&~}FuitJ@rTxr#Y|%Q?i*+IEgP#t{R7$->D)3L z^?WM2c?Yywb4WtxY8EWxdP6{z#Ps_^`Yr0H8w4scLB{4L|Cv5HmXAs?Ht??yz{#;U zFH2=GD?bE8JSCG^yFsv_+Lw<2b{MGvgmyhEMaJG0tIkh&UwBy%T`seaZboHn;}7po z(g{~AikDx_gr!>_1WSHE+DJ|SdyPi3Wxly7jN-V_#YPVJu3voM(y6_X`YlM~9&7hB zmePY_yA`jE303U#^aO4(8E%W zFJYeEP-VCCbup)E#PIj;?A)#uj^kX@ZT@ZhzY2=w|6_rG3Xi&v|Boty}QwV{oI$ero)KtRr-PMf8ve;P{Wl=XM(K7a@XfZR2a^EZj*w%iu9mErTFz z2r5SopBNQDumXL_OA&-7k)a+T34mfZV(Ed$>v>dAjE~aA!}p+f zPQJccNwW|&Ov2eiLPtgb6iD8YZaoXROgmg$G30Y3Q>(@%VLpw>egTy}uI`H}VTqQu z4ihsj3o$FPDc-UVW#Va*_{%#|$IYMV%u-VSKdR0%9?rJy_EQ+W6TOG%U35l7^xnIu zQDY3z8Ig*pi5^4=q7%Vrqjw|PkRV#L(M2!WbMNPV-goc$a($nyWLR z5O~{G=$H+!bW^)_pBExI)VBPY%{@!F8!S)onXVpDu~&I?DIG+l(t}{HTL4JnrvTht z7omD;7w+Y9riZWpnR+*@RTwt7{3w)PmQTm{R$JYgGeH$9$O^9q0mx2XUAe0)IoiM@ zGB!XL^-o_w80hrNiGZzTI;DT5P+BHL96U9+GQ}oRH>`oBb#Uhi8HknIDl8QcQTdqo z;ES#j4gvybm{r77O}0H+Xr$E!RwO9Vj4|n10-EDaSd6(v1s9@F5{}8I*m_y6R{x&MPxFVoi2Tw=>0tg+ zaam4Ql`BLoV1KMl`1skp@IL{M#jNzczDLa`Gd8>Q_ootV>fPSO$J0VlrGm!)ygqi( zo*8*pdXE1Q4W{VIPq3I_TxQM%M`fS*@k8Jrnx=|tfpT`s9!Y9T%1S(EO}{I+G=DtY z%F!T6Gm9mGcH7#lDOE^4+0ib>%tFRNk@eBAt!Wz*U+RR$B`@V5i?>Kq@VStVgC5B4 z`ICv?gjLlywhTdU!>@>vqvM!HyvFtO6~={gLp|{ho1T@Ly{_+{AU`1h5QN&5$3Yk- z(MRt@;~eVvi#iYIo;h49=T8K18TRjj4(dKrGg`(H-fETO|9H2R112f)ppH%*m18B) zFOhgn!PHJWAC02PpC2=L50Y~S=x_~I8xrn##F0jt{2D{TItAx0tH$0MXHu~ru|XT4jB%#?$Fg~;n@ z(0CXo{o1idUNuIR>w7Czd)HajDVggjEh3u zY$~Q69&JK_7?m9ch`Z-pbpy2)+D@GzQEK(E4M;~(neZ8N;^)sVBI*gTl%)_fN zpvuoXJ0|^k3zc^F_kLw`QqahtzP>mn+vNY zdRqFx$TF+JHc8*U6naGFMs)kHnfDuNnZe4n`tUok`vsf{d+BrvyxV<78da5*qey>r zuF_8y|0&jYNcsQ&k=mG#msVyXE&*etYJ!?1hCpG) zW0&#|kc`oRFXw9@^$R6x*2Rz|5xs0-%1)szcYUyqrrqm$lFlWm4tk+N2R;);L%${=ItBhppkJn0?FDcYB z-{i01r2gNJMYC4R=lD$dCKykqi&O4Sm_{f+?%tM42geyzZf;uv7{cpv<3-A{c-bcv zYR-dg;IUT(FRHSh*)4$pWx8tg7jF$$$pLE17gWYNaOo-pUeV3>&BtRBcJ&DW-eIIR zS3cN_aOcyrnLdTCK6? z^l4d@($*JqcA-3TLcHcFUjIKDD`YdH96}Jk3E_Z~z;Ais*v=la^=_;c&=;WrWpo^` zdi`ggrFF%=^y%v`lB7OGQ=kY3jaZ6)OK278LoiQ$*t=acJb$?_sgI1bhcRuzIVXGO z?771G0PCz*e(k^*vkA#n-~}{b%*?E<`C4-P2(hI`#NmwQ>a%;w203UJIM?JW5NV}q@}X1bQ+swfl>t&HYPDVP20yy$ zq`8r-&uSN%Td%&SU!INOt~>1$Lz^LT-C5pA_+hrwTRWEf!d$->s6!Ude-W_2q~IvI z(GJ+Kx*cmQR77A~tsu?*Cb5q33+EYg?!UuL(B>cP@d&4dgM(;^L0(!(UZnNq)m5rR zNpeYaG-SDw;DI$mXQ+{CKq}-ts%CF;rSTWLEgM|{xEM$?{}7euv)G9Zjie*%OMeB|;EC&Oq2UC{>J2sAOSis^(h zR}IFq;9OutexAO96aI2E&2lvj+p?ZlQxoLJNe!B6@{PzbX=JsM#{`1&lrmwsl{(lh zuO+-Zc-?2{dK>+{nLdeh6HIQ=Osgf_HY>z-#(lCH@YGVk^Ax$`wGOfDkwZnhp~ShN zA95L)LIFG1wI$#uxo&8X*l6aXOCC(ln9tE^3#@zvAw(jJC;Dpa6rTF6#Hm2A`+NGg-T2fH6E?32B!nje{0 z+Y76ysX^8e0Y(N@U$B>I>@Ea?t$mfrtgq|S^QWAh2%4?7Y!UAs;6F!5Aqw|${Lr^po#`%u& zHG@Z6h@lAwi+?NHD5|OyE`Z4wQ?hP1W1*~=dR)j=`L$yh`m^WJ6DIN#i>Ij3gt(47-61eN{9$VZJXG@ulXsci@#4TQS#q$qR7URb`;nT1w2?#5a z#-c61-|V!#AIJ;sWbuG{+t46kpqH@-0bISkQmqB>MbV4(Vt24b+4LKhi8C<6FraxC z=hX7i=<(?=U`g_LyGSphfuQax)6!Vf+303lBb`6^JzQM^nziw1!v;jLifvf>y)*+@ z8GqQV_&9wyMz+!7%fyG5L!iCQWF@mI)U+m7Ty3*0gmF?L4;LLNo6ZuFRZ(ngQdx|X z{3fuF6X0Z=Hfaqn%5pER)@i)$TmzVbpRkAVA_l+I58Fx*ARSna9loCK@MNuvFmQcwjElxw`L7KmXa23@-Bzo9 z&Pt2BrA-==Y;pfb{x(vnzYL4o-ya=zE)@9&8OH>viYj@FP&_x2Hx4zH)PmumikLRP z{*f#nG>7yOdc(4E!tGW5GBHy~m(2fQ<|!IZepdST=3#^k$OCm3K;BQWM4Giyf6g*si zsbGnj)+8F8p4|XyOMVe91ZkBOJ^FEa zb+1I=Gt*QvS8*yYPmzd0BZVJZig|1yC1t>l22m?NNJ3tDjCAXxKqD@r#QqE$rl=f_=%o-0aq@~1OC90H%IZ5q^=D0-cu9Wg;#0IR_Kb=)>V2ZZ82c{fqmWRQS&BH>K z(t)Yg7V84jBXtmlZ;hMZMwEqEy|^4j&ot!a;2-c~koPJt@V2G`lxN_Mew2J4n5*BO zIVj${yg=D1{I54} znkv~TP%j>wG2zk2qS75dKp9Y`oLF7LH=kxNYaj^Op`nMYcTt(sgZ`bL)N1A~+lzgy zpt&zYSnmlR6p7gIubEiY!V$z#fW)R{zb|v>CwE6rf+DnY@DDGgRedo0hXK!fq)U#) z7hzmQGM{}>?f1zLXo7+Md9ybVx&RR#KqGlZNF&uAyJss9g7_#KeY8JVegb_W1s!@a z9R|#tdI+uoy||N(5?l`{5^X9$xL!6$we!_I+|SD!jDRe~INh47#D#P<6Xus0|9yE^ z*rHowG5hMN(b9I6v|gRl?~(4|2)!VE6$>k1Xr_WA&DP|_k6^@PvV9rw2|$mpmBMeh z#JtXYN)=qNlK(}!TmR)1DQ5E3Pqh*Q1SJPW#(i}pn?~dlFQ<1FO_6Lx+b3(YCXbcn z%4OTlcQoyVDEIr-r*XQ|(XPap)hde^ec9|)#csGA`&eaFb;Pro!(O?zeC$A==0*=c z!B;$T^Ec}vMcx>mmpA*)r{WX5}HEC=Ak81NqZlw8*ux{ zV`O{iOeH6=-;aDh$WaL>$EbrMsZvD)oWXBrQ~7Ff<{+NqV}@j*bLHGKgY%$I!Hb*M z5){{6(J;xXRzI3&_g})hE(D){E3>p$6Dk9dIl+Xy0Zo<-_H@L7 zC*d+YWJ~#Es%cf%2>W!Jts zndcP_60b^@2eog4h|A-OoC9TvwHkQa7~QQuU`c?*2`VLLYn8k|-@A!5*#$<`Ij~~2 zL&Yg!XWi*&5A&%YZoPEu5_GkFXso+*k$Y=8zW%J$Qte#@IHlHVdzYo$!QBgXUb_Ui zPwzv-1>~BTeO^C&40-+79)+3#%Qs$*bTPgmY2JP!o(EOli_3zCZOXFt4Ot((p4$8I z!&)xns7N}*vgKJNi+m9pjT0mPBO6Ukl>AkdQmY?H<6op6qtdRaWK=BHa-`pcPyz!M-&@{SjN%FI%ekMy+< zfhKBpw#_>Ep@Hf{izHI{2qo#hrl8xO6e!EP`3qYXp!fJJpwFc`>aY8+GhkS$HtO}; zwd0jL6@-p;-ab^=xK%=qp$6EptGYGUN8b&hOgYWPHP&ajPKw0xl+kCyiTWaI;bXGYs2rs~Se=`$+H`E-|`?QIB#Afgk zcBj$<->|eaRg{BtX|x%oMBw=4OK~aOpwU_9aQaZzm<9NNk#7rzzvA+<4wF+BIZC!N zOJTJY=?~!8CO8e+viBylvn)sb*{nHNGk9?<7Sxb_~*Ljogv;J=!$Q#B35 zOPfYZ->cZzslkx+J+N@uu9IVV8xJ10zW?eI8%(}&%B7x{Op!*?Yv<}D^VRVkjxkZ5 z;F)Cm5hjZr{FzDH(93Ior~$&=J|GDHtG`>R-V=08Y%_krHcRpk>`6qLefIT=Gwz08 z7qDgQweycrKxQ$x@TR4#Ov}7t{3;PCV0zeb=iejJKMxfxyRhAcJ8!-lRaaM|ZK=>o zXSPS4(IXxc&I$Ayqg=#g>C?ZNnD3X6kl}wekefsup&UHF=67D}bUk9WPGfCXcnhd(k4X;yz=E8EkGt3j58SDxXwS%9q2~RUnCI?Z$^p@Tv1m=J) z5GsyXsXAJ%c^I@Nr=HqyIXmE^Rs+tr6!bJgA;dLwH>^PT0z)bVb$;vY#GiW+(jK7P zwBn~U>hKABY7a11_Z8&8b&X-I<68XX-;r9EIHDuK8-BV+7p{8v2)!o5lRW#g&z)B+1w`Sl-_;L7~OG_x!@gYbM;F&O10;z9p z@-@DIJb2e40A!E;SmMx_zpy(%i#B*!kMGVP-ORvlSS-=1&7>`s2pAL69gMr^dH3iY zQZ9~~(D*3QYr;>wXiEZvU_J#Pgd9}j-z&&#gIxT+e>W{eUC3x5xVMwHa#o)O6mh%v z-cAN`zD%k56jXitslrl@Y)5zMyZqhPXY~8K{B_n5$Zu0q!9U_kcqyZUHA_(;n z*X1*+p{dH_la548z6}ABudadiw%a9xRx4IQNE+x{NbOVVHvNj$@oStZ{3D~Eucrwq zJEU=uJp2q7Jew?ax9pc7x}Rc9%;)lJJMu(|4EVwwf0k<@Rjzei()JPE{+TVO{-D_?ga4}oI z&MP$QthoB5t^h4NU&rR|!8TB95b*cFwx)T-N`qwb`4P%O1_iX9mzq~yeT)_ zw(8BwoXj-F4ye{0`IM_lQ8TrXvk>+9KKFtdtYcF%D5}^HkB2dSHEx2yR(*z)u zN233IRid+Uro%*VG~a~?QrhVsd$f1zAXdil)-o^uoypzR@<2-hVFTKy0)I=6DG)< zjvqi}X{?g&SA`j27PhCCpW8NB+qR3ap!S!XL-+n%uO>{^T5F3Y%t!za$2!R-s;}@Rd5V;bp5*pADe%b(^6pSQgpl; ztm09om?-ORt3c-r;sD=HybsB5%LRLpnp_T(-spPX9FmS7uMQy`Ck2rf0f|-fWgF)E zB|GU1Z)(NNBO)zX+m!OAuR0XXSzs~?0ja9ZCMEiF9UJI8Q6C>4$a=wlUZDT3U{5$F z={wHV;Scifp<~62OAfTh)gJtV(qJmEQGEHuU3tU)s zUCLTUx^#?q0DQOm5O`fM%uTsk1NmKK&3pE^fSIobZ@>(AL2CZpuro(9aE0QU0?X#n zP00yRoRhYIc;_8p>QoG2KyT8)5uTx zzSeI~l@{Ifo3(47YFa@gmOY1CkN`(iZ}V^$3)mKbHYozHkJKd2+8~m)9)^0Hd6dnC zChi8p!+&SH7EL&>17%RvA6k4COGZTZ^tYRY7xJ-UcTgVFR^t&Pty!zunD=9)X}J7# zFr)<7-BgKqg-~E|v@)8c3gUyy$a{xX)GR+VS0vHjyaW~aVPFP;9s%G{bW`ZB1UC`D zQT)hb%^&yl_-6~7CN<+qy0>Y!u9r=HLZ@?Jw>VuN5$*~w$%CbBkFmKgUi7N@Rxh#r znGdqwpvLg+mw{3hZR8Vv!p9~saF3s#lcSf$T7$>-M2n`)38B7KXmOlndBRchii)0v z|I1VyGZRzFKZiMj(%`(1SkC?QL=k_U-^qSPkD5w1FG3AG zoeTioNoMskPoHs(YZl~ftm8$5= z=$uTVKB74z{$!!4N4LZ5DLY)83BLiko6<`$4{utDHByKOpLEvQ)0JkBZ0p@Dd{T`m z-rCFA>B;0`l}u1z%?qs3oAf4mh%9_M9a3G^0HKA@MklEk)LehRN5fDOQ~VfzjM>ri z4in&>pVHCU4*m+W!-Vjs20IRciKa0 zD=a1T1iT+Xn+2@8spnmgPb*GTXiiHrS?(J3!~Mv?N^L!6Ge z^$uz+VSOIN_N*9`Yd4|Pd5%cO_ccS6f*rB9C6lGz%_ZR~ARo&ZNkCaPS>Jcp*_?8y z#tUZSUmNE;CyjVZ4cTr)%{Q8{4a%Z8ldh26^qBtl_OaMN_VN0GTS@l~pJ_CCPjIw_ zY{z}0bYb`{to;ai3qyFw7qCT+jFka6GEyd9)0L~BsgT6E@5MJ~)1meW795gmJ0cRSKMYY5nv z1OB31Ftez#^*C8Q{}ug`gq|rU4tYd}Gi6WFeSW3u6a8QH#{}BsaPh%GtDX9yTjg3! zE@&^OSX7TNo$Rk%hj$!gMJDcQv-+iDt!80&=T=c?o}BoXB4GKxZ{2gOENn#2G%ZwJ zfN}f{lsSkzf%f?m1XHv^Rj$woc3upCM81^%%Dprv2j9FEx zAqOEybB66?Q-JCY3%XZfu{x?;9@-Fc8H8~o>HU0^5{ z#d6+%v&2yMzA-ky?0EzSJ|ZSG9QBdihBNz z{E0p_l-z=a3u2!90K`hF0V4 zi&~L`^#EYhlo{raYd+BO>$-4g*_VhzIir?Ec|7ah&~Y z>Rg%V04O?@*d48=SGo1v1(|o+@G{G2ve~J0OKPuoTC@ho<-NL1$GFD&0H}8AlnT>`4}`G4We+@@SIe6*ccy|qDUOZC4Nqh1C<^@z>cNQ zZRGXglE%7hnnn;uN@##?b+c1B5D)8Tb9ae+tf$i#mi=H`>Qgy`6gO`&+JM_ z&lv;IT~H{G{)2^|&v*l)vcrV2QbI{j!;KW3*IGxcXj%Nty3~niizfLIaT}`U2sc1p zaryQwo+d2v{x4PzH~WgYi!-&XFVi=Zwe`O0X!6sjD+!Y6!Io(CDZ1*EzjX096edH*4DBE94K_gXn% zErDHyt)1flJEa1xuDf)y0zN)xd_MT)Y<0eARv|Gm9_vh3|8VgT>*gzPlwq9&d z;L(r7`dm`sljoT>)#NO?UmY5*mJ^!hA5tA^M6oQ<7~Wx!n6FNsK@Uh*I_|>eEwv@R z0{7bdc6Tmm2aMgcN}S1I+pd#z7dd?qGlpGR#7X*t;qKez$w+yV-K)o1KLpOyxhdC4 zGg1PnmrY$9fE5UJ*}s0`;xme*&J+QL`-W$+fwvXyK`wgqmKH3gDCU`3QbRDg=*Rk- zrwf|!rSTV&3Gz?s>0kX>+%o1lsj%cu@#=7N?|PrxXbM1mvj1r@C3ak&f{el8i1B7X zrGD3kk;va;gVK=$v9&4ozQ@mW(ZAOH?hCpYp8hG9Ka&+dnIA8c6SQ^Nad#A}p-Gah zaIW`l#NQ~0u$A#1ca>be=MCt}d9S0;AkL=2 zWTP3xvfA@IBp<62LwEJ^fjvrzWuP@((j4!Ft^u!W?eoDP{MD<1;w@WX75!3G{dpw z@MTh#yJ4SIYt0s)*db`W7lyz6w-3B@?gViUwBVWyx(@( zS2osB;pe`r3zk?yj0E|(l5L(h`&CvZ0u5&F*R!7~(@t2p7j$2R5oaqTh3XR56_bNQ zgj}Vm#td1!10-1|<*?%sG1yWkMN?_WxtZvOiCOgDraFMCLd12H8{qc_h1CVfr^WiydYkCpsf z6c2TGFWFgW!EE>1ZEmN1|1K_QQ}g6|!K}xLfDxYm|B8m}#y$&3v%MD4DKHj`O}&>F zZoC-f5MxQUCVe5; z!J{@Urcd0y#^ylIi;sQxDMWv}s$ZYnc$ApNq(DtMI8mH}@&=%3$}H)`mS~M$E%Z-a5JlZAm_u}&53HZf}xIY?B$P#$ZSy4&@XzAD7$x% zD4+0(pAc4q<=pAFcv&NM)W~rCdpRNdN=y^+%@#@;>jJth+w0Rm@2~_SY(3x8LEU2> zFN`|bdBEx`JLE!&AIeuR+GYs$ta|pa$~f#xk_42gL-L>YM$0kfgj`%rO0I67i~wB% z$2LcH=y}}>b#o-Qsg5$C;s}SASQ5DzaIkOL95Zi>2*>eN6eEDakOadkOto+jnVpWE=cr_&gP3>El@t}UKM?CcB2RQ+QhdbaQ)T$n`&+JPPtyt#W z^o)U|szv}v=66@zA^!1jzm(Gu&>+WaY7kVH40$a`ai*I|xP)dM&$sD+K3wf|TM49?<37m!I0Nn?r};ZR?AEPf2E(0o}rodKi<`swfh7{#`IF?7th$TtM=;(3F^5WlNFiT;&uZ2?FbG^6^|DXq}rYvgQ z!90F=-hq;6WCAIdV+iyh( zjItz|&;a_+O`V$NSgpTtAg-ae>i(c`@?a2ab;tzoxv90NICWajl2TqyCmn8toN;-E z=)4H^!zZ6Lg;1imt=x0x2-fv;LL*t<3CMO#ynOn`7n;KP!aKIJ z40AekWuFt40$G^eAb_*m9N!Vc?0b6k;4Tjc{I2WNn6gpQ`(j0i~MgM!YU+(@*z+E}_Fc zYIa7x-=Cv%+g1|IT{)DZD9vM+&q<55hL=2ukj}9w+6IZlJ{|$vYPSJR)8KZFP4Jxd|V9+HqEFLLjGS**mn#&OBlVvAL*>Ge31<=PvZ_lrb-RH^d z)&k;X?@u$;tBM{5Ef@jsz<->bUl66|fcuus?=IYFlK1$#-L@QV+dS+kkkyjf)}=f^ z(xk3kl7Kd%hh-@}@jycB_axWHB{o(P2p(LzB?FS(f7PI=5ENdS^v?OqKx}VomQDGJ z;x^l}OUWFb+xxN}8{0>h)~j@Nl;|KR`!++&z?6sikG0S3M60sB)8z#V@LRH{JHjS zGHcDg>oT_x|S)bW($FQoA}MBa}{cey^GS+=gw>#tp+{e8nD&7_y+S#{+YK0j7y zV+#0llBv4-ZfSiw@VAxaddBao%aHZfHRWJl(^C6aF8Lh>ZW!C!UP6vNTucY@yPzuk zKQn1uchbxV++gwFtJG&)aSz4dUrs3K-k5zu7tv^H2_TaGjUc=Tu&&Y*4+0$tSWr@eg2?w2+p564 zOKw~Pyt7I-S?AKNX$S!h)=t@R1o@ZMZZ4eC*zC)4rX!}0n!ncfD_Jfoqu!$fh2g#6 z^V%{kMLdVt>I(5U!&I(R***$PvnR+}JldU)Tb7Vx3w5>BYNuT6JHxY5Xz>ihH<0ZN(et0z<^kape z>hjc7#0Yv>NNU_-{WDh^P18f-yM{H7&^Go>7l0-NgFI&94QSKmu5k%Wr|y@`BHILK zw9Gv76)TL*FUek(2M0?algEs|lNMbJs^tmbf#iaG$~|SdPTA3A_u7oHeuT*wz%bsO^n`$RwiMM^fhr(@Y?YFEDbjJp$^S@7Di$IL~JEJ>;;sOK1M|11+~OB27Ns)o0z^e5&Z zC%Z)`J{4}o+m>f@CqQ#wOor+qa(jEae0RT8(BU7?#eY8$1A(jWWQOd57I*~BUm*VA zxZp?gaP(Y<;7jh$Tdwa`QZ9|AOaznhZ)9IfK^s7Oi24GQafkaJwSBjA{T^>EXb*MI z7y<*hDsWoceIr@EQ7;RpnaHQvU_JRTv*2yVc2f*r0f@)HtZrfI^{gls;phw7tUXZb zd$9EDnWo}NE$Pa|l6F?3<=@Q=;|!y_ZBM-vJEi#$6io$J&gOX6??fSnFH@6Vk(*)g z+<>teCUAW-fNG?w&OJkpRLEcR>I%~5Us=fl+W-&iw|l-nrsHegy&YVAtk)z0r?}h6 zgO|jwqpsg8Th{zaQ+#AfSdz@{E3TJhuTb{mCao2u91`mCQh}$1DJ%8qKi<@@FU41P zTy`z?2;rH;Z$NkoN8Nw~D~j7B3CryAi`NKgR(W>-jUxr7ih7JsKCRAoo<1opO!)nt z%|cij)0pD2)35_uDQT07FoVLLMr74US^qggv8ht?rHhZ3r+>bO?saDeb)$Fc`Akfj zIW|Pe;yCHprGW$ZxoB#|(=HR6kxjP&AYkTi0SwN?b+PDfc=vLaUiC2{4F8G?t{;zh zt&~>37OW|eYw9^i4ulXe7~s4U9vV?a&NE?r;gMU4+w&PFCjC#uRI<&7Zj!1h+y{;J zsXnSu+J;}RaA2=TVmD@LO9I&f_BZRh;l8o!0LtMTBc1Q^^cDymd7#Wb1=LOjv!Ou0 z5qRyfh4oBj#@M#6<2qm0)&^50q9XAJ;*d_J5nukhhQK|QX)j+ooa1LI$TVr;C|SHX zY+v7>hBdws1IIWoaFDjujRZ1%g@JRa$b2eGsdLbnmqn`RkB8W9)kXZREocN_j+NRR zg{(Dg;-=Yivrd8NCc}KJu zTb&b-XwRgovu5vd{oY^%ojS-G1n?7G7BjZuCaX$ZjfE9EEdtz-kERal5^APC3VxaU zkc^3N_6SBP!-4ClyJru#IRVexps|ixOcm4QULh8z_JvojuevxfusUgk*d9R;la~Z1 zy)n~<5VeMnGRt%5U9acK%~3tbZ>&UOLmY18B6omo%EgK6_)Rs&@+;Ek`+XND{+#5=$bUw!aQ|%X8=sOmywca z77VJhZyI~1nD1bLczn82%g(qXEyE7adrF&3PyPUrk*hIZn}8l7tl0~^-Fh{wlxdSJ zIgC+HB5~}!<+jVXe1VX3bpL)F*8oDo4R(S~UA_(TqX8eo!ftE+hUmk1Uxk&kmX9>- ziT5LMY^}v?g60uHGFHD$M%moH5bb+UP6aUb#bL4J)vhaZpU&E=)}Mbpb%-2D`toCZ zoI^8<4EuD)D#hPb_0))L4Wn0O;L1u2>jsz( z&GQlFJC!AU`~(D7<>Qz42wQ`XYOuk^e>9c!s?`K+`iWr7Do)Yul&y)0u|G3quTyv_ z_AW(VVagv4u_h(M4ExDs9Papj%5{SUM5q^yFJ}q7^zH`YHMBZMx75pr@%%~Xquswz zM~KS4^_%?AX_5t6ny5$G!=D#c?>`?kVp~~GI0|@Ce1{|N)8A(;%F;KsOUlj$OA;;y zE_S*A)tm70pM7B>_v1De>-Gl;H`u~l&pwjXajpKz)W3?HVx9k36e6)M)C6o7do%&Z zEOM;Aj^c~lGyW*i78&`=zq%rNjAoRAv_O{|-jW;}UrwFWBR#Z4hV4|6V6(LVRJ029 zo?Gd3pO!dKiBp>B`z!fE=kr6;MjEtY-Ptx*a=44rBgTJmvJtpE{!*IDACXv6M!bRl zQGv-wiu{#&NuJ~$-r6S_b8II~0hY3mD~DHO2oC6! zR7}R@zj)O`^B4iYxKJ4b(94%S;ySD&b&?5wlUv8$Ti0{`$7zFz`r=~sG|}oOLsWsi zeE%=&Sny%TEw)41NMUmznH$#{T|M|ojp<4HKwh}&-?(4+hK9h$6yXY!)^C@362h1Yv8 zmn1s!^it|RK-bWVm>%=iz4!ZD>eo~S-x!l9G>z%PxlzPpqI=P2?hBf4YAK$*p0Wpp zf&L<$2wl0vRF1PoTk!vyueCGyTN8`13Tr^r=uPKMcmmt~n5-7W=GA3q{iK#D3%=Rk zfrv#yiT6I5g$0PVG8nV%D$&)@4fH8)vP{%C$JSFGyjb=7{$oiKFTlzg2K08-hw)AP z_8+#NyE4oi_Wr_lGlsvl`8~uLd!L=Le7bN~qFvzC3h4&&Uaqnq%WVCgbB9^cj% zsb(pE3)f7gUu?vtrgkcbD4oi<)2FlNzmX`ZT5Kp{|=S#EV{g!GEEV(MYYTA#nXwLMcV{=MW~`8RzEiRM%hV zqkm63dW9bqf`%~drwwa3BnWQ7PR>4)U#m%*eD477?lLVHL`&ocUw)|B()IfVO)1w0 z5)7fQe2l7WI>4pLTGOU*kFhh#eDn%T$OS+HV=794uD!?UzT$jtcH*N(g{qSH*ZeQq z9bW?9nKt<=zGKl$cD9{rD~S7CY`Kj#YHh17{K1+LYiha;1=9JwOkPZ*9Gs(MP zwYP3?>-*~B=#Is7tOqp(Ex%xVUMwwY6}=@LXrJy)tltzrLN=W>W$HWz;6#lT9B$`? zY_|frPktqaN2FF*ngGS&@)LC;QUL=cv!DuuQQC8)=|+*!*@~LU8GV?0zJ_9gC{$16 zL!BXa%%^7z`Ekv>4OASaDZaZG`@yGd8}ZVE59&>e0F%ql7W7s$E_>l^#NU${X0;ma z6zIL4>Yg6_mOBj~cWcwqa-cL8sDx>l+acFct`niKj1?~19QgO&y^`Sc&26vI@4vq- zxO-XfBbb*m-AU0&J69p?ESIXY)hPQIbSSSSNv@8ZRSY#to}y@mNv^Xj-S8O26@a5( z{&;TA`qkxent;Moc^LldFOlUNx|=guGlzmkn&rRetk@?$gxp_Si+(mj*O7!89Tue+ zD!Ljt-Q{7WxT+h#{Tv}H>1+|Z6Mo%Fbx)SV%URR6aS@z4Z!4|QzJC$ec8@*tcfcP_bCS{)s~E+e!8fqvM~PmG3yBK0)&EQ0m&? zwcL7Of>9zdp_shT9&Q1Ji5vsX5*by$B`<-tC<+b4o#7~$Kc^gLfuV#e(L{uXHCL05 zTi?){$oqL3J}q-6xRi>;H&kga@9cB$#_JcTH)T9~ zEOzbW2~#DsZsg&bdibdjyl83J4nLS{cJ3N}4*m~6(Li`0X*EH*BG5dsRnv554aG;S)jReP0rB?Z;2uQ5B+J)+Xzn9dSgN+}2V%P#p106zz?+E(4q z#cY5$W?4QWEflv(6x01=);agiEoadI;6?vLrEW!z#rbF+uC@$b%IoKd4d}B<1{utc z$m&In6sOS~u{-mju4lbWfD44bErw}@HYc!eCQ!Rt!INAr!sI+M8L;5aC!XH|8(uuH z6}$>xT6ycfd!i$)^BdWs?9s4lENq7~{qf^RN_9b%i&;*^zXzOu9u%pbUS6)lX~IWd z9j9J{K@Z!{+V-{J@cMXz?Hr;vv+U3PQFjumC4fGf7u-pGA8Idr$sXt!mjV2n6cJ)5 z%JTGL)y+&y56$L^{NSw+BChKg(LgMd34|DbZ4wz}ENxcbZGOev?VdZeM4JJc()>g+ zN}pwaC-GQ4#!ctY`kNVx<16u{5zZ6p4NFEx-Qwu#l5*Zo#k^={{`AiqTJP>cF=y2I z%%uYG-6e(|SNziDdMyJ%l6DwgvN?g2!ts~jd0C<-nOy57H=2k96uSX(k*d7@-W+)j z;cGfSk8;T0aLD-3`WF`;liE9Ft8dB6N1O%nHx77g{DXGsN#mz&kF9RFQuVWl0iBV^ zSuVEM7Du@hDc?fZx_mtx{L-sJ+;V~3h<0SidR^VuQ7XG^E?SCEpIaV`Jh;t4H9a}-DCww5x_VA!exw_2qMYXXI6!d}z*vzT5BskoPY z%aoguK12-swjqdh58R-?#mLW0W*f z(%s#o2Z(@33rM2~6Ho-%Kze{mC@F$8$|&iQk%CA!jFK81BP2$H-@QNg=Y9X~-}V3N zzw2?m&ht3W<9V!Kpcvk-4`5ZjUbgA0RqXv9HYRwbs=Whe%N)Qrery@|%--Qox1j9y z&icJCQN7Av8M7VTo#Qq+KG#2JR&w`2Nb}A$Q+f3Sds&L6zsKB$sSY3KinpFPY~hpS zNF$%sj!sN4c=Xuw|BnYbH>EYLuvCG5qATiupk)_nqv1s4tNS5Bk};@{jrv^r_I0=Y8>Vx*~$$g?DI>7u?i=_%34YG%4e zbsLQ=pg$l9`h2+p9su!u;4uOym_uEz9{y_1qbxuYS!K=s{VvmR^i+;)J?)ghA7X(= zM}!PIGbC`1$$8{{vC(*~lXd8%@?8S&LoWjzdr9K}r`_iVbD^|B`kg2*tZC$nju)Te zgodvZU+LQmwbSwcM#BW^P{GerCw) zaToZ(`NfQ)HBGqa-iY%gcaq%QtWN+MpFd;2()ki5_B4ts-fHhfAj?AbLpR|9?LzDz zpUSN~pw^Ny=!|iK6g|wL5juVHi8m`i85jy^2Yp%38V}vz9_I7@UPRXuRKa5p|E4Si2rX11 zI^yBKzWQQP7_am_uAd?o5}@E;{`q4f+G<s^iS!icig08imhjZj)Vhx*nHG9 z{V(O_=4NF@UOB#Sg#Rlk;~`~{_Bb4_I^;Uw{9@`yc98CB{LN-OMNjMpz9A9!pJ^Wr zBZe7N${>MXyv`EJ$xOHs1P0}aY|N4E0&yi>!7S2~Z(tUgya1A1*1E;REq55${=4i2^N5|-qUMYpVXio zch)8Arv|O9ms{m@A0K6WS6Hv@-%PBq04w12<(*1c?KXZ1isWG<$;Ywhr?-w>)b+{+ zdi`=3bm_>pV+Mb5cQ<|v7-Rs0SoJp ztVX;X&kK~^xwT%33qHVVJaLOJl6hG~3{DxJFi42K?Ym<5F0&)6d? zoFqa`Y93pY)fanM5)PtzN#7d zS?{$hbpeoie(P7s69{z8rv5(B7{Sw;oZ<6lLHeo~$+F#dw#GU9kVCVrw0xy^*GU9L z&|zeF6@lJ)eq`&E`_)1A@p&?n)ZU+!B_{s&Mej*BB~St^dz1;(epT69)*imLjoSr= zk3)gX{zJNva}!_wfl~i_%B4(4E>lC#Qw7NabCi7UwO-Ee-!~xFM7~QzX4`}FHMhet zt0F!TG(l$0Foy~MuZgMDIvDw8u-q%P#By1Q&WpwmJ*`fXcK*f zQVJ`5tws}`%TUk36?PkhOcbLp?8O zsXe0X;ku_`VP)=hi)A27bMt-wZLV7hqu2|BU0@IWtxX~nfp6I~?RM&#&R}&b`Er^p z!xsASt@~}UKFh|cFE6KY@Hc3klb4JqTft`qR=cv|!Tysw#m=h^_&z;kesFpFSbe%_ zr@cB*^On=6-wn%;B;D~6ws^z?z0+KcQ_pEd1I5T>Tq$6lT@X~X(E_kv53jwY zHGfc#Sb!vzeRhq=UW<%)wg+A__sFoVBwR>8Tl;wch1)};XU`E6j&`-r673q1!yF95 zDt&Yb-&x>m9>m7^_#)_sXWbu-8(EVFR|2kBh(f(x7Cy7&EC^#8sJ1=Pj1NKzl$8*<$>5{hGyd`I;2ZHMVTEu) zgt7?<{z89gwfIC@dJ7Up!xCh+-ybva@+wLxMhy2VSJ#g5O6py!!U2rhzE%NcjUq8S zB+b_Uf_10Ym2x2BHX(bBNCMPm<%~$j@=FS^paYdo9(p|nf(N|KsYI@NH=ch;;c+jo zO*;J@Y&X&{9@x<;|@&NLDehOhSoc1C}8mv&WtOn^=Y8{b#bGjDRG}uzku(g499G6}F zzR2lhp62z#X8e}@c%o*Oqy1DkdRM;@CLt#ekOS_&GSUjgKQSXOw&nwfy~Jd!ik-zp z*3@8f_+X0#~zE1fKXkNi>?N3dnqja`)P&nYJRzi9+8qt2Gns zKkr!HkRYdtoI)TVKcBM;vN;i!qYHQkV=?SfPqL^iSO$_#woii833nK(3jlNExE=rk z<^PIGelFsKBOJax0KDlV#5|QqW9lMA1E^LzPrYbbkL+9Ockz@0n7bJ55VN~U8diTl zKDqV%;6=ED;MChO1SXS6IVS@I{^Pv-ebGua?t`A1oFXQZ|I4iSit$t7BDsA4;uZTf z9gBN%+ieKfKAx(#VYwk+NWGi{>SAB0IErDdDYV|#p8{^s6J4af7@HOSy?8ORW7VZA zvLbgHN8ts$7iJ0=d0PVdEOL8K>;&v{Ppv83A7h6>*VgtIq{0{Hau**sh~4(k30AdB zK)yJdIdA;%ojQ&+$~Pia>%uwYLuU70%@STEqCb?P|qWK;@g7JRJFEyRKrZ$-Ae>nh0s7l%@#F`Tr52xLsjN14yazH4v_E@`aVR+4Ap-rvY(Tp98i!`nj1nIvlK6RPh=PSh6Ip+A-VCsKjX z{mbQ}{}w`M5)*s-tWx_X%bTvnGgf>zc7vh5ff!}03P%`xw`CF0Iak|D`+9tT&Iw-! z$I*sAo>Mu;Xz<4T{8*qfva5h`$Y2eBLb-iWDZ@noPUAf3$Dyv`ne zCN<~c)Hawc$>B#`?7(t1N%PBfP7zIc)FvI1H#JCZ$VGZMo_l9%;VjC*`32D%lhL-Y z3mDoKlnzh;SX9wv;b6ctAQ?GyME8q@8qO}8;E4kCT1Q75+j62HG=drhtha) z;u|tD%ue9jnX&*01}nK~kXKJQT^H%uGZlBPU!3QrdKpA_7-D%D5{~9n+J%YadI?Mz z>ZS*Zqv&oyX)58`VX~CKeZ7}N)k%GJfK`OI-0RQ9Cu*Yw5ufvYylm#=a~R@RZV92B zKA}`ewGa%D?dmchsl~j?^397Z+=k`m`QzBB`ESrdzTnSlv7ncu>3<3_!EqkNr3>89 z#Fm8pcj*kc1DK1xwLGb6iRXRgZxauk9rUO6ur#{RaSE``Nlk!;XQu?{Gx6r(7V;y# z`+>g`o3p%-!r&uX`8j}IW>YQiE1poix&Q7j9NFeZE5)(5t5TDHEai61>L8%Lh%>tB z)ogc1npn6!SVu`ClQ-LTrhxq-ghWiI_nfx{T_vgXgQ0q;jp_JGidsjC>fn9Uc*Xnt zN-U22)X@^^P}krcus=!k+vsK3JDh*vu!ILO$jhFwtI=m;DEcCI$3Od0-a`1u)at{s z$UPlzl=B{HMQeJXsq;8mDaM2vOl8-f{tF05k~4+F0xaQbeq{32=B;;%Tt{ z{#)!|Z$s?WGp{EH4TKlSSqs>+pLFtT&`6-Wf=RP^y}MwQ+G{F3$n zuFqsg`0MEdB-%P6;%*SNAIsYtZ|o8Uf%}7x)oxtxg}_g1%3Uw^WJbQ)&pQ2v$s+y zGCO50{TEH;JZQ5p;f7XoTwT52DT#&~nT?q7orHy1=B9f>OClZ#1m}=+d09RZRSqX; zcvW2Kt9GsJUIHSlKJoYCFuK17GWnIht(>gjs|m3)6Tt<`?`R@MCgZormE$dzf6v{? zat`yO!+fABys#2jn@l7dP?y7`%-V{0pxYO^g2}+x30aC~VkM?MHSdGf?=_Z|@6S=p zb?QW^ygs=a$&HX+HW?rG9S1awNZV|rN*@};5`5lKvO+if5`T~$YI@!FZ~)uz=fhDy z+;cpxLI+D@Ao3Jr<(#Bz-y zY`Cc0d}jA>vR4f}etMW9u;neV^z^6y+mDf4EcjJNz#jy86c>YOPK~7ama1&Wx9JD5GRd!h`fB7h)9C9b+UKQ-AUMzlA=k!XP44Wp#EcNeI%^z zhZ_13$jO5AG>f5_L}8gCk6HJgobI2-J(x8=<)nM&r?%Tz&-?cUFN+Bfn1oBNL3W2L z)B2%|q0VL8a=e;2op3%Kmr&wRyvBv|Z2e?zZYh4Xn0Nz14 z#0QssA_#!Wt<7syKdaCKljQyDm|GZ;*Qr`Wi2 z5l^QYcntJ!cboc9_CR>4*n*1n5}%gCJfG16!DTZ?O4pSQ6!kMS=cyIY)q=>U%;&mE=(L z9|Ra8Q5YV;v;v^On zZA;k)ornyDYcy#f?5_P!;=~>?m{}U+=V<>HHsm^cVCQH(^6LuY0D70EV)ED1-*(Pb ztq^e{oX{UVb^T&%_o7*9O8hdxn_hF2@DDJ$OmxRG*x{)en9@}_%VT}cY%Ah&#EHwp zQly1xd$a0BctBM72lB_OANcP!xc5croS$-T%MN8n>IiQ|c^_ncDJD71b}Q0s+@@5V zM*l1zwXVsif;Dv{&MVj_8QOV zl#J@3uFV3-A&X;jB2A!VqK+l?5?*V3woF>0$Zr8PP zn$bWdlfB*bmhN+NbpeTU+khX-K)RITZNy=f#EmO37XD{Ob9^ve^dE;z%_uS}8mhYS zinox@^o9UE)BD_~1Sm9Smcacc`Btj=N5g%gS~-;Vj@e zNvKmC|KF3G&nlxe0&lr~zFj_tFy%V&Pt*FZda$Y|80`JQ*tZiAKYtpFmDy@6M*P~< zg}3+)>@3WX!=4k-RQ!H%S-+0gakC>zj~BXzTZvlJmiaPigkuD=Dcgui?s$$?W4YPv zc3AgFz{(rIcM*G#28e+Y-F>9G{goQHsLwC2+V@2Y=#FkEzpoMcODo;r{4EW+0A zTaYJh)O{k9b1d_)*}S8hVebd8K10++$T>eH8fG<&?Zv!-giTtr2D^G| zG*eqWE`Hr=I!xQvlg7=C+VSr}m74yF%7@IJ_eDLNI6vB8&77@)8b9Cm`t+aCI(66+ z^T_{>D*iG9SNEFs)&B`W#&_gFm$QrChf3bEj6)J3zW7CMgnT$We1eA-vwX(0OE$&a zMga`GM@+|bU%;LsD^RjcJlvQ|GY#R}MrN?aQWfwDXfh~^*DcTVcnu>S*$D^bV6Gb_ z--Mb6k}1;U-l4&_WC8op(G(Rb`zFKOS^ z-DWl993!~4c#>TVjifW)&~Svl7XW_$fXpT6@JhnttaA)@71sS`TOJPSdt6Tbl#=AQ88ym{ zuUkWzNF?o zpg~LwRW9%vQua;8Np!&y^F!G7tPues*$j{#myFKg$*D2f2R15oH+_gZizHGj&mX>h z_$U0R=x|W(MKNtX4qwNmG!G-#0u!;@7b+3e{QE>vAIbXbids-tuS8x22e*jXet*!_ z)wQ#Ttho2D@>k9!|0g5;zc-|az|?9pQI`Yn7WO|L)m_6)Ii?zP0;D>qyOC zr~5l##=!2$6~4oB?tM_`u*``E8~dGc>J$+rmjmN)Xa z@{5Bv;0qGc3XD}E5APR%$GJIqY`vC~;quym>Jn?Q3qqLNCFY%&%IKiE-}ugSSdg>B zg_JDEtrWzrL{d-L=0rW~WfbYhywBo3YORp_D3_J%eR{fs7S1E)*n-1+R-rL$(2HP$ z_E}s)JN4e^sQt%_&;i2}D6BcVcIF&!O<{2lHh!aZH~{~2XLwW)7u?u|KtG?Cfe^uO zyoeJ+dNNHbsKHiz?(;zTq9u}2p~gbIUeo+7*?bj#cE;wWF(JT#0#*t)s#kt~M?Slk zF}krLBG+SW4lSPK*sx&sstulffm_#7hHJ8`0a(2#Pqeosy^6?I3B=>C!OheN**2DP z`c%J1*}zH(Mx}GR&FoBLpLHKrTq(hze-<3G^KinjBdbfjy;oPzzHu@I(sc{ifN(11v4b*Y|<;|*k@cuigDSv*5cu*_dk3Gh$ z<$;=hrx#6XyaHqKIEp50>z$M5GxzdN_$VDdYiFJQd>Hy>Jl>yQCq=0v-$tN~+h}!k z3Gnn|6;m`cF&|THtYAc3hFTWV2Ygsrlsm%DtBf6D8=x5c&Y*lqm%c6M9zOUIYY(KU4N+8R-SXy%G`}NS^0?m+*>GHgaQO zo43RT`nI^KFWM<>EKWhrU904#2bEuL1tY&=mwGn{a%~FQufO%;ehWkcvLvzy(WrrH zd+5>EK(V7+J(%n;C_g28(5c%O{RrSYq9ygRb42SR&|YAS3vM5E3RG^=5RZ#P_1C}W zHIz_^B$ClJb1Vds*XwVDof{CfwKeqE9MQ_j0^WSuVS;=XG_3fpj%*!*AWQceeTgw* zqo+5|rFJxP4UMuNj{59JO|*bWt->lFt^_!5P&2o2+fTeWe>Cl^Ly(~GBj2M+Ri9b> z{`(Vd_H+-xdzd8Zo6QJ7Ju?zU9wztFz0A=4QTz2Du`k+XL!n++`E7^K1qFO7TsqlM z(!kk}w1f<&Rsr@#?1vj4Rd8Tovmmb-)SKzZfC3XZldXmRSc`t0rI;C>_S+vF+vK$r zE@o5PV`kOV)P#?zi}BF0m;O(sTUh$JoaKL7YTS?eD52KFPZfNQ(W>XG9}m&y#ten! zw}obk#6}v^Y~qxu*Q2!5FkNluHKOTQ=k-X@^CM^nL_HB$)LR4qZ7RM z97wE60LD}T36`|<<&~ecw-lBvV|1_-+j5)r0)%=XpAw>bBG!}g=6tzi66$2Nl8;{C zMhj5I01J^wbI-k`5yR@c>l8?70^zR%)=3V^ItV?k*+jt|*=u3@hzaBvL;Tdz@mJzc z@=+rPK>m+kPl2S!SIhBNCSp1?kxZU~W4iraiT53S8mZQapOzOdb+QyLvmgO0o-C}4 zy6!&K--LK@adLw=PJO!=*#ypyEl+obOfDB@g_yQqQkX~xc3+KUYIScEMEr~nn&tKe zn3~xEW$Dq9;hItBT-Ql^KhKj#A3_Y~BSRL<4xo<4EC$IH?Qdpbmx4bVzV6v4YR5m+ zKlxT(kuN!GW6!t|=CfwGdn?xXj036w4_kjLn{=dAKh2MIxx$=kw=@K8`x;HkCrisR zjy{|iVS4%=6n@mKKR$BwWO2m=>-Ig_ z!2o2~>CvWj;`4hT0;*r3{udG9kI80$V*y7OX(u!Iq|MXwfvGQ?(~Ik^dFu{0YQ?Yj z`PG_GtBAc)tLV~&0;Mh3e&RxANw0ohw#t6w7TSUpV;@eh$BW zcgjgxO;Mux`bFc~JFStVt4+i1m5n-}-|W4L281JDBr=Hi*3Z5)ag|q}i*{n`)Fhg4 zoN0u;rGX;3M3IwcQ6GLBLEC}%xZWG7ztn7LSn1;;N-`>w>8DZPGn_L1```JuwK?O^02R*o~rw+l;j-)MR4{ z3vV8(nhl5#k*zOBN*^hErK!bX<6OC2o;+wQ@EpvRa)l^+mdn(Oja~X>3Bp>3NS-}g zL5VG*B)u=i$8b|P?oX`Kzd|H$JF!P)0OWjxwgc6+R&;#2ZtBrS2<-Pts9-XfE^Gst zL_j$+8<1jv9nF8TNPw|k)X!Dn9lGQ50UMjVbH(D)3FQnKI6=$?`K@Ip5qRLh*2ddf z>vMIeWqg(?w{5-WCncZtJD>l#G5^UT`PblJuk*Xw<^9#NgbY zVC8e8ghJlUw<|nT>bEhbiKIpuiwaf=4Pgk1A{^pOnew~7RsT&XaUD9O#xq=}u1@A_ zg!`sLquq)L6Pp@9!%Sl~j!=-%vqo->MvU=3ncEZn zaRTC}r_+hki4k`S8}1|fOz>g#W#(hTUKe{A-N;`#^PGFon?3;9tG)bNOYgQksD(eQ zzZvCH&B^{uc4x->L8&d@Y4O*Fh%(T;d5w>8nT#2Z^u{{UH>-ol!K_mycPjAa0GK6)kg>(}YIDgcuSTNP9$f&RD zLGZ-9$}!Bc5n5L6LF%JPwzC> z6~5PkhhT_bf|?K2cRa?#z2Ccb-gIr@!vqyMR|W=5t10N@HaO#@Ck+67QdnMj(^qG(8!km)3%|C zjb?979UgI}&qH-eAFTy>hvjnR0zW64JIQ+LJK5b*HC%JM-7ZV4HyreI{JXiguQx{e z$NB;#wAuuGcF_cjJ)ZgHAO^~7gnCce>}t%D%Ll5f5Xr41*tP~Wu&MYyASNMk8BCWS zn=OF~Y{yvrV*FAymJ z&rQk&mGk5ZIu<_30w{?3ZrAI+pc-T#d|FK7DXO8DRl;D_0bOQ!Laa|42Gyrx+vk)pc5qrt5A; zjBktXysTx$K(1GGMzk9B>S$o;m;Qa^bq?(yUan)$jSsdb^t)|cLt(}`GqoeT&64yp za~{%|y?({QPT$P|0RaN8jk5YgKK1RISJKy^+KFpNe$owql;~0|Xg? zd-z=I5JrTzMVz4>{B{8Xa?Zr31rW&q*ONngNN*IdXQnubT>M3MR@$@op)~D7PSK6dlk5p|Blg%0z+r z#2gR*;8Ke2`^iAKx}xSXBE;ZCFVr!81TTLSI_837DJ>3rkgiUzzwzn9k=O%JG9K(H z0(d!Yu&%l+>$|9IxZC~#KTS%x5*;%x6{#i!{`om{Y}Olb zXamhd&F4_9^yJ*y1HQiXXyrGP?Xm5JVk~8h6O*&2%2%J#jY40~O{y$-8Ao8BS-@ac zej~gvb(0H4sZ)QDm$1zzJsvZ;nNC@dG^d>K3v?w2nQzE>50_3j3P$zeZ{3b*M=Xm8 z{HW7B!{hS0_kF6%Ag{#tnEY1+dxyerte0RbEy$9ju{4-=77rzIw{bv8J`VtxgK}2_ zm0Rz0MbAc^60jS$a#1}?Dw`(}x}Pq52mE}2bF!pVTGJ9;)R7hOUTE>{?Oeps%RxBs zdFh;VL!OHz`ncvE0b0w}ic+VBU<|f(6?@FQGka+=bZ)`@pCCUV%071a8A6)QFEef? zM+4uLM(k`7`s-3|wPc??GtTe&!(ELfn|U_{XeJ8H&;naW~m|AIvr^paL)NCrD<#DWqMCNVl$Z^q)`v&qdPX~1dK6M{K zhVwGYJ%lQ(TT~d_THa4LF>`gPKP?3)u)&bu>p7`BJ9*kBL--InY~LDxT>n9YY3lY# zEDrZ)QzJiYb98X`SsQIw=4imC;Y=AFlFVaDOKcBnm?&I9EV!V?^L{P%`ewx7fScsj zdZTV}wAJ@g$fU15D2v=|UNj@)wPf6IMHYKzCoxEn-08k^wnd5M%#X{9izk%-Eqt$& zC$u!t%-_P4x&Hkz$&TQSoNHF0I4hThW*W>=d2Y&F#>-YWN84CI7KUV^5?;{c^LA?3 z{lV|?#t>eRo55scy0NvD^={@!*{k7=rAIE`T8$3mA|BNlbQ$l`SvRN<&RUx? zy@#3RlGL@mHnvc!9j}OXgc}0F+ajxv!5CfRnuS@zw`A7R#O_-_aOp~( z5eaV3s~4DAT^s-|^b(ZG0pB@iUXV51E}vJF0?-gZKqpT-J)+6+?V@+!r+f(2X*AXy z9mpm%ZQBc%seW?8uG=}z;J3u$(^K~7qmQWNv&9wWR5n1=HDRr|7mH!yc%9nOyPhkH z<;82+j34?#HO;U^7E*`6U?tc@VB*@vj53w3YytzIA*qrzit-P?d{BRPY5CXLgJ=w6 zKPgjIH#Z4*+=DrHuy2glm^D{MP&80;xTs!k=e9d?3J7k(9;{M&e(0loK)I@sa^y@Ps;Be8mWYhT~U(aH--XD_-cUrSj_l!ZS_BsZFfL*o_n@~{D%F#9Zu}wKSM!fLJ>mWL4zAW33FMnkxdDLzl!sO#3l_O*usY)0s7o|f9RUCf?va{aNf zvEU=K7jRFY4>3gy2DAt*RpCTSCN&Y&hh113s|v^ z>3FX_pZ7RY<(`Zl9{)iJIM}yfz)dt}bowc5r32hyM$j=6&9$y)Q3okE1{>XDU%S^5 zE4D6%P2xkaFt1)|2PeUDj691HQUa_^nrk?Qy*t35~eA_`=FnQR%<1}6*ND(R2Ip8AwTkEi_~{M}y1K?_~<{Bq0X%1VO8#96B-LHA0-;VS}xche%=1l|eQglXM+{4c5 zK#`<9X5S=ys4>6}cY$Y=;KJ-);fKBQybR1$p#{Jp0WKO0VN_I}JMSOllOa4lk8kd& zwcj%l%-7cLqrVqTa0hrj z{W)QF*&OppfMuKVUUZiX!Vkmm)6TJc<*MmuiF^X;EQ&`xngTZwBjhs!Gd;$f%e?z@ z!EA`*c2d4sqbGm9DQhv%MRg!w&yY zLXBQzfx{1fL^P-jBYh}rW2mW*kcPCqcYC1Ro8t8_jXU}Mxh@I;^ zbNx{Suerb^+nBv#z=KwtS{6rEiITyul_8+i^ygPUuXPoT$9#aCFpvv}L2h&yPdJXS z%UVRz2XKWnau8wj-v4W%cL`FhRQE}J2U~T!J17py!h=#|N!$2^-=G<=V@f24z|?9k z1<^TIySw{~gGgU?0xcj1&Oyz`G<1gf`{`2JUq8t~c2&UUPR4~|T&r8AL-BD9`{`Q) z^V1y7rE2ukEJ2V==?iN-Kf-2eYMry5&q!}f)Zi&4MbTr_?m{J}TTg<9280!Fx$vEi zw`7%Sa)hfXXJ~21c4BcY0om@`zvvW`+qts*)Tba~BY%3RaoMn}egFr-GI08$>3L?# z?aW60G&)2|_FEPfFukWQo>PSgFU>4udbUx#yAa*Uq^sh{PcY~iDOk4Th(EW@4 zH$3>)8tsptOj|Fb#`Vd6&;SBh6UI+d5IuO8Nq-oK1X(UIpg3>2)rjBm75%?9-I7Og zug}UBFT`i6c+u#eF2Ll#!(PE%tQN41O5<@@mF8O{qM4T=&M9P&1CK1`Wf59|fe7*q z8T$w~Jydw)RXFK2Mw})1GhNo%K!9|QT_f^v^Mer92;$i`Nu`^I1S)bxL^N5!vV>cR zBpK57zy>OKIY0vp1Axw5Dc8SZ$tvg&AWnpn4iB8FvT}{Xhpw@Xe$?UxP#O!I|C+kVJ764bW zH`;qW*xm0&_+8+ObJ=GU($l;vZT1)`L;gef`Qc%sBm&8*&LctXMdzQMSUHTSK=PXR zON7n5<$2+6nFVK20E3P_1bp5rv%P9$wDhZ_CoG0t zr6dIpLVs>Z%(6kunLpg!Q8JqVzJwov07ji5B#)M^_|_h7v;njAhlwj0Zs}r+_R8eZ z8RHdhF+W-UhzSwA`VdRZ2GM78hg?0pU~yZ?4(?{#y0X<~Z2KbziE~t*URb-BY(Qal zWOC4(tb29IcJ(r#Uq{QT>=&Ad=jidL%{nY3wdzo*(G&5N)gAh%-`=X-B*d`RhlYlR zmb`NK_UHd{_N=OkH14W3gkBi`-MSkQY2_F^(O9mapzwRj{O+IN^*X@ou{I7b?~6Lj zw_c)|R`Uo8F2FqGj-Gx}rxiJG*d|zS>TGJgaIbKp?Qd%B5wvZSOup)Ffru3@? z5lZ}r_Run;oEAYt?xFXdO*Jr1%mQIga=Q>=l-qc4$<*PFH-sfuI4~sX+!sZy-%Z$M z^X-Xi2(U-403)wJ1)m1^Fqoh@FTDZZ;YV8C&LN&1W%*c-u_I?lk`LbNp!FDVXR84D z=wo#sgLg>PlmS+t@m`%5$#;GY?Fl~rrPDz`T+B#-+y;?L;Bp8G&rES|KC*TZw2C&NQ&}OCZleefusylq|Y*sp zSOFZuALkTTdJEPF`tK2!Aq zA879N&WXvlE#G$+Rs)r)1O{KSh`kC>qjoC&9l!H7J0+p|mXLrz&%Qj@t9}*WA1Q_H z4wtOQA}ZS8Qq;b6qdJNuOf&6xQJ<%di8K;Rj(Je{mbh?@ zT-V^>7i?B~Bw})BdLOzT)l=R#6y#x83OGL+uGX?+a-`?{cNG4`D?6D3=ye)U299wJa z^kw+w=SX*)aT3-`d=O+$Fd7*dImoT3P%zBKutuzB8~Z=>^8cMN4@ZR@DTbP}uxOF3 z9;|e)8UH;tcKLgAeFC=xYauJN=irW?y>=d9;#J<-m|IK9s!OaCI#3|Wki=teyols~ zFu4Dk7$%p`ad&m&YEgvTvhydroI%w8=-<{(!xp}SO?B|7aExH&+vqC7e*BmglgGYf za9n!_+%feEo#6NqQCgBETE28qtXa8G&$(00wWustVAR61R1G4e!lly{)|T)~v`&sh zPYgOTwh2J0ga9OZCR3CqIvG zOivSn?{?e_O*CP)icuw|(zW zd3~ed3n*cC%X&C7E63H_lk-|Y?hr#gOjka9Sy-I6>2>JMxXXN8g&`ekq^3J34|uur za*rs%0cK2E$OS(EY@!@X+y_VH*3CSg-OclX6wb>Wkkii%Tstk*3u=>cWeEcG8e6aux{a4#mLJ@F!!M-p1l~>~^-W zH-z_>h_xcrQil4lE_E#l!0=Y`FC!N{h%-&fO2vi8?Ov9XTemB7mGa#Bkm_%r}ppL0*GF?k`0kWG337A7DBqkqUINaZ#B8 zqw4+TIUsJ&vm~(ne#%t)U5{_ro-uLEE>U4($A?PI_dU6Lh_>3O%ouW;Y+*>K~MWeb$ z#du4_1_PAe(_*`N?F9D*Hhe}NupclC^Q{X8{94=j6z!4tr0=?PbeKTF<%?8YWut$) zT9-1xJAFs-um`@3@L`r|XAO|c3>53BzaVX$Jq*oEnKa;~4-OSsk9xS~srDXW?_QG? z#I33e2(nm~{fGxLmg7gROg}QY9God#CCSQ{s$JO8fqR}58rs3F)f=?KqGS1i>18Jc zVI5=%^NWj;ctM2nDEFsuz3&V7i{>KH|BMLjx!t+)dH%bjy&Y;6y0L%7K2s;!7P+_Q zdA{fOLsa8pG+rQFE!@GFHnf#Eh@0&Z()IQSf=x4_UxC}}k;{Jr)j1tX5Xtr6DCjWJX*TUOWpM`mdgNp{O$#JZ zWPH2sajaG>8hc610W^}4kSI~}J)taVafyH`h00xl%uPwrS>-B)t$`UR3&Nss-1xLG02w_GPtcVtdn`FVdKw zrsjS?{LQKlapKh|=exKs);*a_p33%$*q`YJ%<|GuFiWvx_YGmxt3iVLPtkkT;PHEr zWwbHCZ}ZfKSxsLY42a|vw_zZ*T}+_qymt=1j?g#b{fRMyH_nbr zdY}_vejjqB^5LVWP|20JmAdtMSSU7|AbhKV`K7-Vn^8mO#X>XKdE*$T;{jr`vThXK z;5fAnyZrD@pzYqJ9Uf&YC^7gz*(hojR=5yxBUU`FYWrH@VSWO3rd}S?Tw{bT7flK& zC?vIBj8_rfAU$;m?+$m4ZfukfOBx`s(eXmu(dtTnL zv9Y8e1~~u!uf56Po)5X)J^a%_-9MD2vg^@UezUiKQ+|x&FAgK@MSQaT5x~5IA;hY2 zDx11uc@lkJ|EbVI*i5oZGf=U$b$L~wc28sWUoa`cq|pMr{D(h_F-5(N?#BT)J#=&< z@3|%+EJkeVbWj%0I|h`Zw~`DmSQ4Cup>lvpE@rSRuH==cL^@l-tFG55PK0bJZt<00xGBcYRh?0VXG zpV=#K>1yA$Un2amqN;H`jY+PL>D$`5I#Fl-2A#6qNXHa_sB$uk81SAzagXe6i9&M0 zoeOib;Nr(oveiGdr$S10Y(nJxALDc8f{14X*}JtPh_f6EJzU{)eJ2tgWF{@h%beOS zo;%KQ{qNgd-p*2XFP6rj?I+24@&da!uUbR2D|#IU;(>(>p$LaI)K$ouGUV||b~Zn@ zr!Otv**(z=F*v;Rsw3En@Zxa!H>%flLZ5O&mOLGt2VFq>G#IiiPI=fyIC zL`enr@klRs%Zf#)Tv9*Gc&>lDRvHl z>Bl3}-2ZK8{xkp64kV8G-xPxzt1Sb^i=;3mIdyf3e6Vi2l9C>VmhNVxo1u}Ge&;#A^PF?u>ra@^z4xAbt#y4@ zv0UQ1uC6#y!_%L(=XJVA<(d^N`L4S**8y~xPi7(+F$Y;TjEe(89C`pM{@_jk2Oib} zAe1uy?V{|Ee`nO%_jS@pAU2Q#q>gcO8dA2E(HK2IBN4XU^LE@@*a*c0l_^|X0&`Re ziJ9V-WzRdLxH}uLy2+0RxE6}t*NV`55|_5y>Curdm!YwtRkS)vDuEIXy8k_hm>3s} z%5yH(@Yw?%gXCul${@HCcOrf(-atB_Rzy4P&)VZRcfD{RTcFmJ7uevu&cIWrB+DXu zHa%1T)b|!CtTryBmoIu)Ju&=bET05VjSvR)B6k4K#o3#_Jly;~(v(Rd?k3hy<}z!F zhHFip%F2<7hs@J|m%!bBKf-jrGBHxI|7KSr8b$OyI>MR?bT$>&b2WW)25Wtq{9O`P z;mmiies^Klv>&nkNs1>Kqp63gGg59~Eg0S~#(e18x#3F%rCR$dTC)&~<_Q;lZ6 zuA_e(L%I+$EAS`%lgIORCtqp6JCH{hm}_!sb(_T3nt4q$L#h-FVEBj6`tO|cvn)V} zB+p_OKBF@J2^FmS-^NT#O_D=sz@*Q&owp&>kM9QHKO34FUM*102B{t`sb z_A?3H)sY=B4a4-ZtcZySTbb6PLFb6DhOp+`U0X`Rpf{HN`r*;%z6_QlP4KT^4C)_7}kCPs}rZ&CcG~eZMuNA*4$5*|5krh&u?6z zhxpSfx>rD>C(L>-pje+C51HTVMD4ZEUkCV(p3-GA?Sw>nQ;9O*n19{d-1~iAkNZj4 zQ+2@yRR2Zb*JGe1@Wo(57<*Zm9>WY2Ej-2QEB@}6w)tuMX$*v2Q|mAyWl&X3#b;f2 z1flWU#OM(<5l6ZyNXuO^@D!=$Pp?H=R9a4!=s=Dr>62Bjxi>dbG}^shShG;lz=XB#H(xnw4l3!G+{9ZvJ#E z-#cB*Zp82N5e+E2gR%)h|7E+_ZQtJT1f`M-ch}rGOzx`vy*_m-sCrA=djxkba+nfy0JJ1)q;CJ)VNwtOMYg^n4Q?bNR)h{?8)l6FY2 zq{BzZjd$l-DnH(Jao96F-COVBzF6X<;o0Rh{u#QFDYcQ({GAr0@Q3izX?`5oNsclZnflLcMb5tWLWgDh%6_o20m-z1kL~7SZ{6qYIWw zOL@biwcwR>%k)6WO}i|ZAYisY7lM@h$W~lGO1?Xq6h+3Xu|N+!0w0%u-!DGv&E!*3 z->q%D2B-;?^@($%*VF=dR?-@s8Z~^$x35DK&?PWBBg%U>t5?+@6>Ux9!W$)yjp6=V zeKT*Rv(6^%5DVHd6B8$q6 zBM@>Ugr#4Z!8Y8hYSg^A&RNXtZhucO3i1anYth?xzmE(@$WHMLyL|rlej^pSJ>j|R zdubrq_zuw6u;ir@9L&dq$x2p|g!NmL0R;m=PX&vSM|zFLnx|=7)twpEpa_uXV$_RJ z=~Dze$}>1y3|gYuu=6n@xZiZ4S`EkgOZ=N_i*^ASm_?fi+9x?WoNQ1Sbce# zX0tBmQ9%W0zZukUWtAtg>-8i| z|0gZ`KWU`M-5Dd7#H^dftoSz(vc$^^3mpCzHvTN!ZMW6Fl& zs3me?n-2gEtb+(-Sl(Zs0EtCLAay?E+ZtZ`^9fOE+DGk-m_5bZI6Pp7N(!O{#&g1- zI@o%|hi&z8Il&Zv7>Kl$=dGfZf^eY2#v76`+%g{(~43$^OxR5Y_RDsEnCIOO8l5&Wz}^1i)H$(hXDv@5Z^x}bq(y{ zlHx?`bCUCx^qRtCv|BS&#^nEYBSxCm&trTJa8tdWEi+i4Tk^sx{d8*HT3y%SUV9^{ z>man0C{MLLjs=*713xkoN1}27OlXVcKRL1k}$$dc< zR9y|Y3}}ds*RTujZ{Z2nio2hEJu#{vdO!xN)zf0l4P!n#Kx9PeG1*<2xLkM<&dJQM zAg;*1p%07ma~i4lIp1)moKZ!x_N+fSv+h&-Fsa0&BXD7{x_Ir3l3YZ3#DH(4CKFyd zAq1fC+66)3uX6?|pyj&lg+Gn?nI4&V?T>o(u#IJ!k?4k@UE@t-UrgoH*8tK_FqQHl z$eUeSw_uf+D{gNy)3V;xUO7)4?IgFldYbdU?ljI<rtiUP8I!`HLw+Vj>!l73^ph0(+={6rtj1CJc<1A6cxq-+;g6;llpkGgbIkv zq);)iYQq=Yo)4G8`W^+Fr&j~O0~g&S4iaTKr@P!EvbGOvsF97xB3j|vimGNpeMW9fbVeH}yVbUamWYB(+ZTe(d~ z)?g8#6C_;Ti z+H_T?iJq=>bU@tO$37}1ps87vCrdW|I7mjf+{;5CiAWaymm!Ac&P7FrtjgJL)cPN> z>->rxDo7axbZ@{O^P8-4>dUM)%lHEG5hanp5qeT0k=L#-qR)&ncpGje`3P+-)7y>6 zc$_bXCk2T5xBtwG`5OR5pi;hSaJQ}Eo_@sj~ji5yB@WJ677y!%wl8fr#T z#x9?CaZ@ryi;oI^riU^Qj=acD+@c1#n-JOTtRQ;Gb{(a-o{)1Tt&R_7`QG1to<%@Q zBcsWY<&g+i(*L{eHTrXRZ_ny z`ur;CIn+>34agB&t?)Aq-Y9`Rk6aX@{Iml21(gRhugj=x)|z`B2mcXsu71LL*6Sdf zZOSr1uN=b+ngK0-S?wkeOB%$UP>YQEcqVu4TVb$jc+8q9SoswDmVj?fo4-%!edd|| zq1$kskXe4ALAX-@IBoU1^hK1r7A$Y(xA}@JfR!y@uAOJ%Z!r*gok?h5*6F0XwW8cT zY9dClMWv@R(l6H{?r;Gzq&+X6SuR`VgoU69mzuZ?zwTc_*|y|&`JAga=et+O2Ku#M zI@l9XH3l5=v{AO#T;}vc@k_tTIcvM&0(MqeF}`;;_Q4~bt1!9=xU!&wTyduWqQO1NxBv7`#oT#uFT}VgJpKu9DMSRA3xg&9{b0b^y zKBIx}Dt;8Zeb~!jJr?SfSsbPtjWrbHCDYqM$D?Q0(;qTO2=AxEkj=-up~ zbJz&D;fG>fUs$XKln*({5D4EGZv`N~hYWeAk3O|lkRp#x~kA|Rqzz`MHnF?l4(;2~s#h?ri(qreu)jW5P<6ek@ zZ-?@A`nWZ0_hW@N!Vs?i)iA4}#Yqax%%OUFFUS2q0;}#5a*o*L+u`MerbC3v)=-MY zNQ6aibbs4j!-K9xFUH3lnR4l~@1nl9?r0zY=+Bd`c@K@^W%;?e)IC{Rf$&L8lOgP+ zM?b-5%5DXK;Icz%HA?Le8t3OLsn|=*e=t|?I}+vA12b#Zwq-?K8t?l>uayececSP} z%?$WCCyv2qK;pBQj#e}$6}5rw^CCm*X#6mcbTT9BQAq}NKnwL0C__Nr{yj4cM=v|? z1=dJWq};&di})T=cr*BJTy)a@RxQuqJP9L$eaK$V3i}gahQQ>hp15#+{8}`7pvt1n zPyy>{(yqu^OHli3RvI%gU51$H@xkc{e%nF%bPMCtt{TRv5et*2tFdWzbFT*q%d3|; zTBvxG%cVeO*b+5U_V@LKMc7A}`?0zMb1R>IY3aX5MzjzTV-eE(zO`&T^v0Z|{2dPH zyh9)X;^|R7Vm#nvFUNhdi56v-jFwkZ^c)i)z2Y~aol#IE@4Cdi*mWP_eDiL3Pu~HQS`bPRN(IT!*}V&P^SCmQ zzb=h(S>#+r0K}vMYv+diQW)0$>X+AWtz%w5O!*EMlz$bd*t0|FAYr?+ zY-Dco!$altL>9*J4z}9aONE|ROX;)m@Z$oNLmdoEy?) zT!iKHv?Unl693Pj_No$zTAp?`p)+f`C^NxR)%^1)f}klLV+E1SvRGdhe2hZ^6MS{a z{H*msV|J|ZW|v9D?)bGI$m0dYIHq7xdp{$IXpt{B_lNm2h8=Z{&b?ZJhJ?bpcv1*3 zV38E2gc0p%`d5k}IG7Mc7-|a}^-*Ol^~8Dia#-ZZt1N}gv=`F-3H-903l~S12;cls zEq}5WIb}lVsI8YEEQ0e=6*6rQev~5o)fqv0(jcI}5H5;BE``|KN9-!LL9eS-2$9Ut zdFx@JSWELdRk6`^+%|6A{H%BH+Eq~yoW^LGzvfTquJGI2$cS8kLvKzPE1BozV&5iw}m{Yds6Hu?eI}HQS1*lhdoUe znrx9SB{Jmb`XW-PqH3C=A%H~0oRXY>GfaHqLS{RGg=VD-+}dwJq@!5LI%IRY5o zhwfE0$NI)LO4BAoORSbsbQq}FijCU_*h2SW=8_Q}nS|AV(fwP-kqKC)9-3S5e9Vx= zgvm|2x=870)Qr6}esu5jZC2V4CQt00c0rB`pM(HIkr8y5&#?JZRb#RRK_j~v1Uv8F zD{gMCYSzOoYI8M&J}EeOg{mXq*yVn>t*XK=9!msqc&dF`@L+NM?hOHq(r7uuJe*MPx>NZcu)RP4~ALS0V9qSkE5n1Q9P)CHelH-YgWR^<}v=HD@<|Lyfeeh zZsav{BtiI5y~>Wmy3{WiiT@CNWsJ$dtX@;5w3io#d)_2O=FVBb_2N&kX!{j9Zi;5q zp{s=h%kbME~_Cb{EKC#fYbiC= z30B%FqBZSmyWi{fi7Eyss&KTJ2t_t+TR&DbSVjc|fL<-+f|vp8tE^}H+dh2364_gO zZb!Q|hvZq&knDL-uFSaV>)o%gk04aN+#1Bex}(YWKIe}rkY>-#o+frss_aWysJq>S z0#p^}m7Vi9U=+(%(|HSzb0+rtHg}QJR8cFd5-AEmh?SZk&beR7vWNsRO~ugr*&6ml zzxxzS?!krYKT->WwvLXf^-hyF(TKHwzc#l$cER@gn%~4o{#$E3Z`1sTE4j%;f2D+8 z#fkC1wYZ9C`};%`y8G@VLmpmc{nEynuVLL!r5|fRb;=g=EdT}6r8Ho|YNz<~bS-Xc_tCy1v@*T{{$#ZBV8wm>X3qpf9(B4 zPh?u;7P?(HBRZJK-8Mf5Z6eqvXnv!!VGDwP2dfkiiWy6{lf$ff?yRvlAOt%!UU$YC z1dYw}tJDwdWE;9Sk6LSY;c( zNbYa`DLwW8)h5qvn^Dc1Oj~{)$D0_c;QVA=_`~xwXe={9m7{dAk4-%MvkFJKzK8E? zSpSz6VtKV{if-nebU5+ih=w}0(iA0=+B@m_cqxKU!*7d*wNvaO0UT6^HSZh)7v5mB z#|7hmop6|?8{4~PBu*sTLF|~ehovqO?GK~%5nwocUFl%o!Di-H<50xtmgHc)!L?9z zA^vTLjG=q*6Mllw zo+gO-=3lvHz4`N0ku^$B?0i;fu~)))xG#oq&kcm4Q_PfVD4Q`4N_!gR-q5GyQX~M~ zq1hHgQ?+__dsZXGJr9jfDvH?+{%^O{8@26!7WhVe58Ye`Ig@4D>F>tr`&)f)zEw(P zkF+|MKr&&bnBdYT1=zge*i9x*H`RA**s~od9XJ>G)2I;WG5?`-742J*bV%;_Q6(7W zoIm{>-mv}>Ll*2y8#2}*Km@Yi#kU6n7G4wF4uVK6aAQfjFrmcCReo0Zdal@HANEay=KE+ogD`gNj|aEEyf} zycV=)=; zl0}oa_%UcpaAar3JA&38PRlucLwLv7NT2=cCetBSES2Kt<%FoO$M*SWQ_Bv@c2!h{ zWS8HE<+<~QW$yfF-5=<7Qf@c8iO-FXa(Qh4HoiS8q)>F=+XS!M5M$D=M|&0SzV&Jv zP0IO2#WQm|xAl%S&-Jf+$WSG+yw38ti`cfS#_Jq^#AhnR^q(VgM>;)mDMRCWoJ0NJ zG?SlXxpyDmv|0$q%>^S1};|H;^F>hM>F z6<5WV*y))5iYi5`Zl6UX{;9lWkr#YpY|a zw^zvzCuUUN*GEg9vEpwa5}SVA=U7;ieaCuxo?g>vV`j8ihtZo~&fOmGYdAGU@Vpnb zeXTE-pyHHM!?yB6$z2Xx7c$x|rQL3)&D#%2dWMuf&mFFrp3BoUxwsQCf{cxm%3YRa zSdFk9>a4uiO_!Xg16GvqlgCXA-*GZPYs|BD_yfGYc&KUXOkM)&z)kh^~Kk3S-_NmHr-*}ay^plaR|L2mT1xmjJKcu$BC& z8xMebPyac)z=Fquy@Cgk7bP84lB9RVwB4iAF=UbVOZ2XA_cNw{!G5n_@7idk2|0a3 zdo|#v379>1$Mg?Xq#h=m&)Oa3F?$`P^2}@*M1A_xC8jD*L{tPmWhtSLSk?R6#!ESd zg?SdjBD|f?C9gbU=3l8Lvp;2s6?o^Dxwm}-nR@)^CH?KQckxR&O+&S%&_6{fCP78P)g(GQiHe9_tiKf%EUSx3#!5TWQZ=?yn52mn&e~Qbuh2T7~W%iGlzN^n%5N!lELy5!z{2=#4dIPoM*?v&x7B7>wY8+@}TC z0CVl)6NZBTYPOO6JLbJW@x(?ohnB>!(=TZ;UJkI1GG3VPzH*M<)*?p7rtV97F2e)mMYH(bM+hp)qRx{Or|WTx)iN}Ji+Qx5RfEK$ zAP2pS9@WGd3F&cj{-L}J|u`1G4!n`XCX}PziucaF5)oH+++NFY| z#j{=-qL2Fe;)I@<1C~_3{J1^};4(?0$3>EJuZF&67ts)7Jp?h3Ub;9pQ7WOj;y;S} z8-Nuy--PdWCuuswp7lCihK&l}fB?^Sb9ba>Z`v^os=ThfHO|i;Ac2lI4K|ziZ4XC7 zn>etW<%gp-riU#5%Ljo=Y8cmh3skIt$60?3cXI-|x4>xmI;n+7Fw-e<`D$?e)5dl`i{qrX3#jYzU^uf&_~ljBdZpem(Hq9`^P#EZZ<3Sik# zm`_IsrX+rZ&y+DmhOlD4hH;h>VToF9_x31*(|lI=^LfV6LP8)b`Z2lBw(^iWLG?-lcK~gee4KWgrmzYZheBltEM7u@;Em) zR;opTa}acAObv<`0B@i$|2N~v4&pTt{LdR`m$m#&1UcIMTmBohtkn8!;_Cjq?H=ih z7VGxTgqcWgF<=0@{PMUhrMK3DO=}*K`7-`JCHz8+bQB~2AgkeN+KXZS@=1leDmnsN zpyGS93U3T}Wlo;ud0m%JZAr)n%vBnnf?OGDW2vOt#^rkbsgwsdu9{*#T4`o#;p1k& zt~;JtrUGD(h)GejYrkY5B^0%X6(IM-I5Q_$aBlfPI4DABOT8b*RK<_9y!DyJSD5hz zKz*=DoMAHdCxpO~m@ZdsFqwNB=dPpJiy7SHwZCv^0cTl`9>a3^9$Xf9}IYG>{GW@&*$6j<}WV!Mv)iZnS@|R=A_`$6ScCDBuK8881 z=q_IVfj}feb-7#mbS2NfQp=7J2S_L7W9yI*57YP${sDYUJPxHE;PEKFUEo(`=?s{o=K zjnpM0J>HsUIS{XS8*(HL^}O*ir;P3Vfa};k`$pzw2GfH+2=K+4 zY>Q!1Gh#0;72N{YJ@(Zb&|183;eFsD-y#M}o*o^TN;whnoY}r5=>d}8!lz5pbU`>1 zFO`8AeAag~+Jwp!%xY7J7;;$nyLQ=$0A(vIs)CBv*IE(ytYlf3#6uOLYl6F9cq!b- zcYIsP(nH@+?KD`^PR-w3P@9}go3+V#;X+%jv$5S~22#7HHcDq){C5l~ZyJz;TLkg6 zWoO}{wLe9;`(mfYZ^Njz(;`F#HD1okIzp!d zWhdiitxHwHlUT;Eyl2UI1q5dJpjxc(>u3uv$;EZIq~{{JS^>EA7$xlT_NCDAY2Is} zx1z|7O>9!@80}}}ey#9xvBEDnG_5k8letY|HAu&EW1Ae{_1jJSoXH>B%RW+#{7DRdbrKnEGf$Tc5&fxvs7E1Z4js@7QME;EAqk4@mq*8 z#o0~X-3u56{erf*v>>pC1{~1tc{nj}&fK`)3pwmFEUHUf@8V=u)5jc-sq(Tyl`5c--qA>~3-T`n-{lMVb2y)x~JDHOr zPmY5j2hg4hM>AG6hF>41jl^vInm+~=uM1^}MTebvgyt<7(TS}s<*`tnw>)PWX>$z! zXbO0et{`BgUv9yn;xugU`0h4`9*csE=asOvQC?C*c>t_;82+*8@6(27T&+DiQLYaU z5Y^WEnERj(_)O+qf9a&d{BB6RzuNmw1oVXa;rPM8&)cPCy3+f4T)I|Z+W*|;zQyP6 z=)PscgfXgUw6F3ugucJmlQY@d6X$2JcLM2e+3^ltRK%GBW*4jk1C=;!T_ag>gqd#D z_-ZAbRJ|0pL8fh{MHMxYk;P$xX`UD`7DZ2joVK-V-LmJHizor7@tR&7uR(JjE0GIj z_!*Rq&>yPxU}Z}_w5rpYe0Bpz-7Wg5O8gYWHfpc!q39M{)J`jZWC>ggXhqQD_gIj~ zf$ByIHHC@V3EL%3gW-)Tzm_V#O&9v;WxeV2S~~Nx5_|x^aD9LYj9`ogH-GnD_$-2n z;`o+Y=f!>Htr4VhoPFp^n>9Ubnf|7v#Xzg*_$k-2TXh@s-9IZg|AZQi5$^q&{SpzM zxfD&%?6^Dhd6H(UGrx-YZ>q(0Y=oif)WR>`5U|7T{n0~f!QrqHm3z}7QP{$nFvi~< z5f-n`80wG)(l&Ie?S98TL5=0QD7=Cjx z;k}f>lZ2@8uL9XDCUwr4IDG^;5G-g*VV_aJXNN7&4|>AJfXs5^WlPcwO;f;UMw=tPT$)YTc06!HXOFyU+M>ibQc3OE~ z=Xf{V7HdOf65PQ$BAt2b;8kwmQ&VPCqd4R8n*qH`Tj_I_=h=^$bsg!mgL)_w$dY7# zSaUfd=)Q(J+a3P&y@YBTNgMf{`rjzxY~9Z+UmJO3^hEnz-BFD86*3D}f3|>4Pi1#% zi7CUV7$9aLQ!B9(m5UcQ;i!Wl2b?N!R!~Jre5f&4)KzkXm;nzw(AqD)^E5@rt^iQ}4rSuHD|jJ_z{W5lZ4yUNa$AL>a9Q8CnHs@&jTkO|HfwhPkw_mV)Uk5+O> zT7zmPFVZpz9Q3~>6SXG`=#8jds8Vq_@`a=v5cSNRxq=@}aOBIjHV96+TDUm1C}we@ zMF%BhJIyDzWNcO=5_eX$%b$mhXfF~2xu6L?l9@4}2qkD2Vkq*q5(_P_Y~rsR9KU#B zz}MS$haV{?vXNUs_>Ut1#V*bn(x&}a!+S>jrptdP*-u&O{&*0Yo#}lj`d_*H zqt+YelMFl{zV1;~DkOg+rL!BLHxd@K7a@BDo*k95m5H&V*@<zRMa)Z_}TWSHS7{QK&Ht(e#qnq!-D;>9K~?TyWi8*Ai|;-(25}^ z0ZN>|DhD4+^4r5Vjh^VRvC6k_EyxLY0AQ9)%etX+29ZdB1|9gPt{_xbQA3Hk{#_65 zuenY4hr7$cquZtjmy>C${}@EqtZnydqHfoe)0YvuHzH5AlZf`LFhuqL<&eIcs{N&Q*3IoVj;Jj3+9^ohXuC~*_~s+XFFL^rY24h? zUyaUlCS@z9s$J{iW2GS!%I~P%b0VN+8VqkJ;u2e#hQ?sQptmWpACoJMdXViDH2hQH zuibxbGef@G{c&dV$WVI$B}3tJ6*L2kQ0Pj;f;Wn445T}CZ;oi`pWzC0JeD^Rw6p^s z*{!tl1SBR0U|((&&nr-I)oqXqZ%Y_w%JFgI)o_Dtcs;$^lKj4tG32Zli*AGGQs!Cb z$A#FJN{>!iFLx-!xU@;11Pr`uO!AaXWw2`ng_S*D4p5YP&Dk!088H7h4)B%lSB}9( zU;b}NV#lM0n3hw(PxSA6(NL7H<~5ps8LRnJmQ^W^kyr-1QcqI`Tc*X!=~Fot>3rS2 z>3ME(@hj7&1WnRMoFFBP$FZ?e{i=M-{3%QG*T~cI8dmR%eK+ebAlYiuqegzW5viN9 zmW#R0eb%EJUy2JX*`2cm>G{ndXwXTM^dfUF*LPOE)>G|E42E!od0C}jV8PF_xAyjX z`C!i~S<%IcmiNxhXRl`O&zVgGH`ac!Aq91JDYO;A#kBNlWU!jYJhNla__|I9SU-Gw z!KhxQ8l1X?4?Z8$M*<38R@K`N3e*o9x(#dNG$Cwvxz2by`KRVjy3y=<(X1zM%x&hzDZ@Q7oG;2>^0?}e_=gJ{g3cGtu9d5QRo!RAQYI)C zj{ttlkc?ro)Z1ASO7W$If#K?kS`*j(RgH8Jtq;alRt5Oac|d3$80+0luV2>ZmKU1= z>B&f$cf2z@QhlBV=O_O)Vx;apls0|SdS)5d{r8+Y#vBiq{tv9^Sf}SQqN2V5PVMR( zz8)uUUzgaz0jyg9cuZxixnxfbbJ4ycBi-QMeTaIU-P5!5%*`A6}?d!K1PR2 z*F*+72-DsVwqJ7u`#*w#zqMM`nslfT6Bxe$v|)H%0G<>J@dg7>>DYOKau;40&bsW& zACwflT>}{(Uqze2dkDv)*>ve+=Nx0Cu5EXV?l8K@NJ(ukCp8v)f+JJLJe7`b%%sbC z4%bd~EHD^=UsKpuHX`{qmT>9ElSf3(yY9va6=z0Rt>z+UPyY074WguPO)q`qr{Ztg zaiv!Lig6>!=GSXZ=lW9V_GrM6RT}I^)#PBU?)N9T&+RLK>-t9Rv=@miKl%~K18_}M zJ)os#q#wVc*t34s**inXZYbfr=kw815Xt3hO?=4RZwJxutzAGwF<2{Uj@PYhicr1` zwPhdWiYs3^sf48bBO;~&kX{?|D93ujHNK})f+R3-P1*BFvsO=3$yY#1z{?^O?Buh_ zZWc!?UW}PUd=x&gl$~l)YCOfeM2RK@8x1XStpC>5|0>5qsx=i&u1Ca98@nDX`QDaR z6I3qTa+Tp>Zy%^B;9mT$IA>fK^iKQO1At8^zVaMYX`9%RL!Yvgqu2UA!<32%>lY7s z)E4uQ%7B`p8gIW!_an%ku_>4cHv?ZY#AeAu;_zb~2>WJf?f7(~=e=~2QPxA$JPWh2 ztEbCN$im-^hRxI)X(o!r8;HS-W!96(GPdP}x!25Mzxaq?3}3xpFN$J4U8}|*ToXx6 zcRfEZ*Xw8S`OX9kZ675v7RHU`i z_q-5CT3@;y()>QXlvuQ z$~+Pv;@s-?o~=C$NZC#hUEh*MCV#xk~;OE5tHw&VCiPi0fXsmCl=xdv(d9=2Oed z!^JrRvXF(ZkDnoS`#-l-ZI0&t^HMTP6Wi!*`tbR`hxX+r3N=X4_V*1X@2@4EBG~v` zox|ooep<4bpMk$Rt6Xzg-N;hpe4Eq9x&i#UemI0xR}pfv5U>~k7!ga?$(d(S7Kw#F zrsE$CNNk~ABoGzeU$pnQ<>@GKdrkFzL}yuTQm129 zP>>1h^-JDe_g71537rW$qRGiAtLh-ix@`-;P-$g!b zx!i*=ZW<&U1IINj6Gl z-pvxprR4(6IGNpnvHvPp%3tsc7E%lK_`*DLHL<*C!$%bL{=!RL^!_8V8qd5Nu{HOY zDdRvyNiTv@Y&>)QtC&4r_iimPtY;|i2Y16>XEecgYw1Y<+bqTLtbTK28lc>Gk4AVz z3hII0O!x43gSx-6Fq>dFyAFewYTaBf5wT%wslU%) z`#&7x=4L>7CGgdr82U=|PAlW7@!uxoUKA(MM)Uv9HAi?@mg@l9NnDJNJd4H>(U9L| z({jJ`!k;}yM z=suAKyCTu=3Y>i6_Y5XT?Oh1Tsl_tepASDg!b{i>Nel#r>j<|av$(C1{Mr%{W;5>& zlv=#Z=Z>;(qB(AF>Z;wl^bM?C{vZkIm}Ruz@sZY@0VFYll>nq~*TK6lK6OgKgOFi6sneckNEC`{PH5rl;x&v5E z0jYPBdzyd=x)}>_G(+}C+lQ`D`r*h%#8*gf%AL=oc_lAwN=v0FIz-Ilmhe%q#sbk! zZneb|z^sTZr1(v@RHJpRX@+DgmA7vd_lyjwX)iX&W)UM8Q=G8e_j~q?0SrYUPsBEp>w>@<)NG*r3qtAwIG+~W; zr+JoxgM&FpVhD2e#s7C~2=$Ss-sR~&C;cYf-6gD-$hQ0U_xG1=d!v$FQ55(;^8`I<$NQL}%z&l%6p9cD_6sy|3!c4b(fac| zobd*}YM7SKUJ(v98;6kMn!5WH8!4j37bIvq=g#86?XO1$zIk60#X6*247~Bb%NE-% zR-y1*CQ0c^DQdU5ehRfcf6W*q5-3ub$8{*`A|LtLBxYJ__aa<*`Z8CCt!lKmFp8E@ zxV3wPK$9gZshRl&d76U8QX8^yLqzdSX@RX-;KJ;~;x*Nw2$iV2j#}LFk7->}2iIP? zAHO??*b%eK+#FmTzHR2 z#Hp7Uu)WsXb+vE{>*2?&a!WHD1dctSVB~6lSwzRBvjr5ULqg=+F94yqSc9|-0U4O~ zhuHl4t$bmlFT#hOE2yhcQ%=t%36%8Jw>?u(S9wxIK&TJ%%alA+1yIAnnZCO@_}kc` z=JL0=c!6SpTdzO2*6Pgd*Ah_)Cmgw{Io0>-It82_KP@66?lN%IXXkI@jM?cCvmDk)2{s zb@r2T>V4^q{PG9Bqo7JwRUo`e!5Z zhgk~MJU}j}C913TQQdyMd+QiMJ4s^Y!W002osim~(wNAD3$ucHw`sPHdPsD1#0KNJ zvy0Yc0nmPxrTab3#z(b+J^S$eIl(Cd%-m`xf$*?+_uh5Jcn#8ng!!f26*3aN^ccvh z0w$JghJ1Pg?3Z~LX%p%G>0>1EL`9Dq_x4giA{F@Jxhg+ITU;o&Qoj7$QU-MXqfE^?fOUgkX|(=YJ!IAwFoRD(ixW-!%tiHC;+?OxkaRJ!>|W~UsWMa2 z5~)Cfirf_)TiHRvb&|(FzN>OPi?XtESkHUALt;*fmGhpYfBq%A05(zQEuiw`{|s`k zz-?4guL8anUh#hOuWdM^- zGrcWG_KSPm?2n9GT0S5pXPu!9M|mKQKK%T}rPqLD{-QY~Vihm4M@G~mn`Zb$eWfOk z@CWzQ=li7`D>Uk&G;YYlzeOCh(mF{5)a;kFGkvKo)Y?W?#NeP*BY5$eiAcHaS`MhY z)tTyY*3Am#GWH1C+YOyz>m5v4*S>ihTB-mY+VO=2u}OaRPa$=zOxmRWVddH+8DcQY zXSMeCux_0=y3Ax0e)<8qadLfySbU~YdH4mQrMOsIqO%bv-pVw{76lIkuj>ryF0SxCNhQsSOfSC7wdG0(C1Q@&Ryoc zOpDjzDFJ_T;J6n5BG`pm=fNzV9Ys3O!m_YLm>5}9TEw@wMYf#!D`fN4==T?@=)x{o zfO3qNM)x}(f38QnLN6vB6XVs=h%AVbLt3mu8-jDIlv?g24c{$t9e9YKxy!YYG@{xM zae-8>0?@u;HIXAz7p2b(sLlVG^KkhD`~GjtRAvOU)KO7UC+qYN`iG4uIyUw_BgXcG z=IjjBbL*CoR#umUy@4=z*y2g7nA(&7nAv%(Mb!y1<02LW8T84kq9F;nDP zloW&5wQ8cX_cWL#00yxjd*AZo3mfl4wlSAcUcyGW-_>R*b6-DHaF7p1u%Zt^S$q@k zJ8UCjtiDDqOEL)#XYkco6k+7EFGI9;r$dW5b?ZAaBmA_d1T@3N6n1QwJ46yqigd(1 z2cwQ8RgzkchD%uAWcV+_EZj02=zdY2=|}7JcGq8@boN zm!~g`vgbkEJ~HH7#=qZd5Z>+ENKdj5wcw%fk2OKCmd^!X@0lr`{U;^VAMG0i6B^-* z*#g}|Q2OpesD1M)X#P{BY?ZU{%7W#(YsZeI%U?CT`g6@#&O*mPEVoe#rxgIewni8! z;=b0sRsJefLqOfZeYJVMp|jg%eUXpkXQgu`ty>+|Dfh(aL=`|CC(50cPEM;S;^Q@p zs9oX88k;JhrQ`om_0@k-cHQ1XNJ)cqgM>&)cXyZM0MamYN`pv9cX#K|FffwRjl|H6 zbculUJNI**b3X6Af4TmEy|1;`{?>XKCFNHLq^5JJE4|^5{M-8e`_p%lg4c8NB?*er z8$+9~dORL1@Hz8!g()qwTs+L_BdRxUsWQdrWq@|p#|tf8P*f{z(UEMa(D$7M=fGRg=F9+ZQ*B&Yfm#ECkqpdMBU zdrSq=)jZ>T0^-9})KfMu(zdGC>M&cKU|9)}mpIqVBFM2}tyDBfVBjaur|B}R9@YhA zo}>{jOo~EElNJ=}%_#Q}Bo1wlMHhgU1iyneG5`}f;ZV%&)2 zRIbeuzkDWnT7YM#c!SKSvl*k!h{C!mSMo5_E`z4BOh+g}o~YBK4d95<7Q zh<}d6|1IBvz80>}7iRwq)U&!dc>?GD<7znjex>GfR9UVyRg&E4Q@hUAn?lf{(Y2uT z<6Cm>7dp0U^LHnzylZ*{PG!2Q_0FcWUskaAjilS5BV`Nvgy2PTt0tRV)_S!zjZF#s z-C{FQ8kbf7eIl*Te;|kmudumXf7D7~B}^|=Jm9$edOLrD*n{VX^l=ko=T~k3;uEBI ze^Hu5>d(9wb&RMI<_E1a@{xEqnNnU^wOqK)?h^&wJ3}MJ!MqJSY2iIR{y>`R zF9aHD$GbBOU#=DWg%CDTSTrnyd9fZCdL&UIRf#(-gQN$`bMn19kshp21%xWLA*s+5QaW1=4q#{$r~jj2TSDy zxJE`~Scu63KPLugJ;cThT$kdH3(Ur`Dvzr@2){yQgC!xJ@>IQZJCk0`0Q^q8AxV!X?rGmwDKsqI!2`M zdMr;Moz@#_YtwsrdMKDPnEY?!3jZ9N;`7Hj`>m|(=AQf8@H4mB&%e8y z^zJIgj&B}4Pc;oegFxgh}>ouB&tal%t_8%1B>)i;A z81g3#f1DZ%Kc~1I*N?~)#mr)OIy7J3c;;Gea&jG#38gG%pJ&>zGH~9=8B+#f5aG)_ z*0qn$w~}Xk2?-X&Sf8yy2(I8iyRq&Ltji#Nt^#)l+m@%wz0vk;4|aob_}8u8PHv3q zrLEGWj|;sNKz~WSS@B`#qjd9jFEzfJ;y882#q)Ae9YAYoP1EJH?|3|lzx{Ji<9j`? zH#XNx=_MqzdZ()0pFfDf;jqYHljB?TUeK;^oU&6_4#x$H{Jtov&-M4&H@_qp39ife znAU92caf!oBSaIQnZv_RId42)FfTCCboAb_W|ximZM+oDRjYMBU)Sx;Fn#REa+YcQ zfkIt)Ahc{YC7i%IUr8`z%z5~C4h3DyX8+ZZ6u0ncm(kH$PHD6r9bGnL$0Y?JzUcB} z98wRmL|N-6`G}0#ct`+Z$2OvgHo42NfFDblnE<R?<@N6cN5B>f(nJ0Vf(-Y^8 z3fEJGMFvX!QajIsF_z%0IZSXUg}sX^%AyUX^3gLy#DII@x#}q8(~odFgJ9KcK09sH zqH2M}J9*r?AJWe%zCM%;Z?vgP<436-Ud;Zt$O!dcJHOmGyDeFzmj>cHp49u_xwT&} z7{RkLd0dd0k!*Wsv^$5|gHTF?0cR9PWts`1(&#u%bv?3*@)KVC8-8uJ>2kGPZ#vu6 zLf$-i?RxAdL{~RSkDu`#RdC5@xL$4cRIl%mvG#{0gUzF*!U4BrVTZ22-tus1Xqx3Y z{w7|&Epa;d)_d7j=w*dPPP7PPjuAI+6msJsdd)+_M?!#mmbA1Fig_d8y|LGwm@Pk< z+{QOw-YW3-$o`+h5^ylqILJcwn$~c1tufPC~~; zCW+w2mMB}(45@l(9Xq^>FK;~nw(p(dbHWm{Y=DR-DbA^TSVIT#dgJyExTTpgL*3{PARCN!@6H7|2*AMzf{er&~R;L`}1V8?E(_6tU07B&vE%u{Y^5%?- z8?GXAbG>rXVYq`>;sLA7TL-U$wImfj27j|vi>ABe{j(@3KQU`Sx-x}x2l$~DVPL~Sk zptUivCrKPvEd?}E=4w>#5t~Nym{zPis;eZDc;=UFlDp4X*Rg^tS4$W%LprTZf3jCu zn_*_TQfkQKktheqWqq`~^=?>J!J>3In$bZne_t;WYw_kbpT&P+;^~5A@>MpCL=kP^ zC>IhvH`-^X$Y(xS#g!&hE@I7kHj*7$_Bq#58CtWU)+tI4AM#KHPk2ypbgXS|X;CyW z$rIc6{L8$hbo2YSuc(fS>$cdD#y2WBnDU=>T?QWyJl1G6)(kd2*zH00csOmdar#~F z3>_4hNO*jjesw!qhRX1|Csn_0L=2|GX8mIgd_#r^nNNX`A45VTI;;dHzU1g2x9($g zddcld_WJt$aIWCc)!tnd6s3uIdTdms^T@RfqGUV!CHC?eb$=UCe=fcK-VpDvHHrJA z1bQU$_K9ThK%Wf*Nl=V}MOa4?&-xO%aqkT3>dNI;G~BVkj|T-0cVQce59_YbRlY-> zc5s;rQQPvJsEp344$Bh}cIpUq4hOe5R6p+ie0Hx^{JYfI@&!L0MRaiT)&qSmpgR9? zyY2ps=G4T+d>??f3qM z>)LWgzfzR3U_Ox8N~WjDeAVMdsHanQl~j)wJgI>EJwo3Gz>yUblflS%^t1RZv$Lyt z()``Js;W>{VaBs`@|IOEf#KCOOH10f%xyxXo436(V&$&+8LQ9Bs`|M;g|>eY&`=$g zVAokc5Gr&1xFZ9mH@{5LJCS!d?QGxwy2TtqJW(MIEnTP01xBczkg~;L4Apqm)Ov%^ z_t#uH2CYAu?NcwdciL4nH@ARtA)3WCw;@pla1l+&K}6rO=j6;)%o97b(12 zm;LXc zrlc~_i5uW;8Bo^G@@_QUGGlJ!P!$L2o()d>#0(vb0iup6%a7F;NMal#Qs%o~e9Q4% zFt|r+scxJgt2&1Ni(2 znO6}4iRX4 zdPcm4^DbxZeaC6{P8gdfFxS^7*GuoL$Hd+?9rboY0 zGHL^@RRF@RpMrRZNX_?oasfHAH{SUBAshSgIzcv|l#oCCG#_19#$e6~MB z{G?E0JJHKq-^3BHY2_o+GG{qCTVA8&k(>ElseV@lIpFDG(H9PPnSv&^r1~6xJa1!D zn}dX@+!sNkM$yACoDd8J!AMPoM0#8^b^A#QmgK5B63l?$oK7> z?#sJ>F5`#47oR+s7rYYi+Rr~zgen=Ps*5#yj9X!MkruFBX63_4*OJHZtENAXJ1(^&o+riZOv|4u`3sPBV3AAgk5(n6 zRGbQ2{SuBt%|09+ zKJdIDCSst6<`HS)(UJXKFHT@VELD-3Ad*a$Zxxa9c@)eQNp^UQB0D;-EK8Xrw( zH#&qM>z&usje}y%tjyT5J&I>Ef)9;bA3j|=kqVSB$#i&}x!r9(zPMgd3pLe9352J` zR3wbtbRyJSKO4>VQKkl*j_mU*YHk)xq#$6q?WO7+-D;|4=Wy7tt>XB26P>5}QTtm4 zv3+lq(~DrQ(UXhGTDdK`x5_UP(U(qT_Z?P(o0gl<$4a_n^m zl5Z7E==#ktUK(BcGmoXyfqDDCowFJ&sV%X;rR=Kb=I8BpsR0qv*xsvfcfxi1^OK*q zpKqt@zsm@y=&f?vaD><&+DtJ~Eslxxi{}G*@g!8L&otLDou;q65auWUem){ChqE;J z?>`%DPc*M3yZdcrY@vvbIfaH=|L8Q_8SPqeTqu=L=~e2q!)E*`KTMxbO3K?x=pOvEO- z=t>jHG}}L^WlYF6GPGJ7cyYJoi&XG*>AW0q9^<`fXztQTi_Lm}s}NDc;wLEy+bv$% z&F(g3VEW!EXPq<04D)v?^MBwz-up=!p-&uS!!hn+@(2g*ocf$gZZecy$8$i(GX9d~2a0J!I-F`I7q@X8f)f z5CJ&=RsB1RWBq6WGgRz1g=fabkh3Z;Mb5c6?lTckO+7WJPIZO*xbFv5F z_w+q27y>v@m=bUSmxZNnTCJ)_V7oFbENqzsRTHD<_#)|F>ZiJI|G;wmX>-ZNt;Wnn z)!p~=b-Oe2)T*Ku&Pv4+RmwNNGRSu!W2|pGob8Ea$t3G3Th^De-}WFxNWXoTi0y37p1;Be+jNY1pods6<%n)l$2ykq{RTNwO{A^iAuS{Br;MY)!iuao90n zap1=7q>F?jI3_#5X_0O6aNY4MLnCsrQu)!WS`+6_? z_F1Me{NrfshM;;{4!49Hs#hLDWzI@u@rUL1>!>DT0kaaWgThJ0G&#c;$2)@ir}`7? z_M#UH^GLlxSkW7oo2ulS&=t=qaVBjh^%J+f8H#>@vcW?Q$UfPXJ*mLKJ=SB}1W8Pj zHTGK8;p?-EGWz$HfHF;fY;p?UVgk*%{H4aJ3NKJQMTu z)KqL&e^Tk7MdLlEDL+ym8EOgl$=$aPQF`Zi4^f6Ibw_o6|8Amv$>9^A`MinwQuV(~ zj%Q@FkiuLt^zrwY)#Kl%AXtq_r=e5FA!B7_Wy9^n&ES*7D~D}4YJNlgCMc?t}iWJQE}Lm5-w3m8-H)Oud_irzDqHcw=9Ct$@7=u4R8Tt z0XC6EQKVl|#kp?#So>EgGkF#4gWk_li{U$9cvjEBn<@mu`^|B!7QPNLUkQ{|Ewby_ ziprm|E}1wv>N1A2=xsRc#o=zZ?GOwLF4;|r_+#QO7(&O`dBTb{kQv6yKZ-7$L_6H8 zk;^lT1pPSt#D+66)fmV|{CK(cyEno)iCWLWjT|7X-E%!+v*2;ODpX^hE6OB?IjLx$ zgRuCM*?~urJ_2W|KqM9jo1L0&nN#(8{wAq5v7YYRmlq`&x*LX-y}NyNY6u9N(QO$3 zk0j0-|7i>*bBNY5lJ9T%;X}JD_%H!yk(@%Lj8S8FXR|)3B9foBgexBCc4~Zp8amrqF#xdf^9N`npzP@Dp3SA^U0y~2>#9mQI6Cc0{Q-rn7qC5x)>D2Q zxglEXiM@VvFixQ@UyaOS+pcM?BrRRMySr=aJrD0bjN$f_Kh%6>Dw%ZB5jQ`F``{9S ze@RYE+yfqWsMD_|g*mR16#@b}*Ifc%9yZczjoQlcL;(mbqkNI$g5AeudLiT&5+F@k zCr<#v00$)7-bC4@Z&NBc&5)SMih5OtKP9?yd5_M|)mEYHBh`uXG_xm<-3dFeCMBS4 zP9VYC&*>cSt>_|Aw%PU~pSzLo18^DVb~=7?Hn5iVXas@{Ycy^r0&Oo)(n(ho{JzM>-1 zHlNxm8NfeSjzJKFQrY2a%sH2hXY5TLpRLJa?8E^R+?0sw+|O-*DU0q=O$2%tIG#~U ze}bc#choF$e@-JLkRchnk_J;Jv~HM0lGdmLPTqUsHWZhb^mZ&J9t8ewOQ zDs#7pB?v>jBz%m=z^#WvtH+Q`lwX(i{5Q+>A=#IZvC1k9OiigHCj_d<)-3_$D(VPk zV{wlnR*I?TlLk~>;r_YwGP*{VmO0R+|BqM^&YBBSbX&ribR+&OrOh}b$rMYZs$fLyDo zFNAHpBSogBb9*kuW0hV`dy8Wx3kuD0{tFi6(B zQfueJ)uo0P!-}d^Ch04R=AWJe#@jCAq%_tK#gm_iQ2o#fEMc8_-aYKcg!_z>-!U%@ zb?>Zi#h^|T2MYV9!JjID4_E8v@dH#G56Be!ddi%F%QJj$g@X_{tJVT@?Zo-tb|hDg zC6NUvg0O5+9Qs?Tz;hL$lVH7$?y?Rh)ZoKa$w|s|mX3+<4Nk6^hV39GNrz%y8es;K zPy1;buU%cSTIZIIXP(c@&ioK^$cXcOqd;0*UU}6c#C;=z>@~s8 zbFnL(er?Uo&BG;%$-An~zR7Y1o&U4@o(VeR)TRLm$BkJR)TaM;1~Syd?kw*f_r>d4 z5}K)!bzNN>9=C9U5`@nn(m`j*%*frhR({3C1=lM&ywHKUG(l#f2u4GJz;dDQb3WG2 zC(v&s%Y%Lte+r)8aK_O+6DE{9>8*+)Ev~e!Iaxa=v>%p1S!cc%vp1isx-ryW^6lY=-<}8t0>vlJQyo;|N^C zjD9MDNFBr%@vr3xTkhVS=J3JdN0yS+Q`_lh`(K&LUrucVk$T-evzLnu3DQ?BeVVFE?OV@ib~47;WfOg{%>2HC z)6o?Sour+=qFw+Uk?pOEPPXv+_dn}jPUd=bor<8;l)v*kE6+Qk@C8(EB_~M|?&scH z2U`{u@n{x+X{UJ!Aaq2~9WKQxiob&B)_Hqo-Xe(hL40#X zN>@_nMdzHhJ);E0hg7*i-qA|iM|HiwH>FjB818$an!(BuTM*H)`rv94b z;ttErij=egi3{G@pT8qlBK{7~e)v5BJ~QMe^>#Py=nbi`D__|+e_70Qo5PKr1t(QB z0TJz`@U)|m&{$&!R0VZuvzKln5xGNOGao4_qYov=A!y8tzgn;*k(3`~VLFfS5O8z3 zHZIBf=8T0=>;}ho{m&NWT>!UVLb8 zvSpO|N(x(o+=2aUl_Yq6T=!iEgJSdB*8%>3Mo6$GfEoJh4@4Tl-3~DXiHGGE24)H0 z#%h}Y4M~TFYZqeMNft&~&Osbpm~)ol`%QJWnE{|=ZKX)0sb?IjNN4`~#4@gIWdj|3 zNBeW9P3?owoeZpiUJ*|BMuklY4S_qct@>Q)Lh)%#bs%>)PD!n;*p*a1H7CnJI=B|q zZJcXpI21>W84C;RKAsppGU)nx2V47}JHj(zZodp$deATEzfdUbQ)#^aF1_1U81ZQR zr^&Z-3k!@bEiH`>OCQ4AJEKU9ubt2tsm>`}(fA2Cu>lEhTq{3y6gE}7xt?xbH^y`z zG1f?hGN2VkboMS_$H@HQdAA5WGDc#&Fpv;f)o{cD6WAp&Uzq&! z&J6{r-Ja(7SnqV=ZvsjRr4ccY7^9A0L?C2sxhb!+{ECWMUF{P9a-B_7HKGjsCDuSG z?YbjoAbcs%?l*)H=Ab!^VrlgG!RP+EsN480%*jt94U3XReC;V__5RU$_ssDnfw%Pd zdIr`VfK#Ubu6yNK?-mKHSiqVnH#v2Y#}3EyE&zk7nF4CLRx-t*2tWE`L`U;h@-7a% zgC3!TX|SW)A+-ahWXAp;7Eq#LWX)@67iNRf5fq`iLslsFORoAdmsb=*+U1*Rm<=SgfosF`dA!+eKcGwv}4<*W5GA2gS03a$ZAN59V3&5)xZZ{*(6>&*CWAdc=YTp zKtCf$r1Q0xDuygfolX1T2^?;}HsqprpOaK#yS`c-M zUkmae6?cB^1c&crEzieqTUibJ+?#ptbCpwZXnn_ct)`@dm3i0Bzf@GnL;PYru&Fq3 zR=xAZWVum=w1^1_73?aNb>LVe<$y^<`oHxZKwkSf=31s(uy-fxHRkP4xo7yKFol%Mbc-{BpvL~AB1`RK;HDI>)5d)&nBkKN zYW!i}*c4Rso*Nq;E|@C~!W{=|86=FJI8Yj|f-?c6NVNgo zN~Uto7!(}QEW^dq+ZqC-?-nsLPlO^Y;SC2p=7^j-%phmi>$@WRO5&ympF|4i*_{Yo zbN}aWE!J*NuWs&XvnE@t_Ekax;x7%i3T8Xvz48IDzx(AfkA~So(_y?A5C&(5`rg%_b+r2{2!^*}kJZfL{DdoMr&#V2wCBaS|Irwo`dFqr?mz#l z^aOFrm9LHb;TSZ&CKAD=Mni=+yOj()1y=~alGp4_#*p9vN3q6EMg_M#qc?mg@+K@f zxApYw(n1u#b)M5VXYMhdfkXE{xF^#L(aSjSvXCvcT!9UQ=Y}kx?CRaT?|5#Y3HEl+ zHD{=-95Gm*aVS2Eh8Ty6j=1i=P|SNLc|(kcW+jAq(#yn3!uyOzcmvIwkjwT64SOP; zMhgd%M1D=+Xu|FaRR_qBYejCH%Pq82Meg>pDaB8jwOXgfe$@6cBzI7!xQ}wgH_JT) z$nDqx2C{X`9j{q3A)zVk;2kmIOV_gDN$Y&j?&LP3-_KNFIjgg!$h0VHN9Rl=VWlxD zo_u0Zh;nG`ivFkwfRD3aKOSYMuX|-opg8%VfHXhsf%})#JTog6ZE%u7`{cFF5QU1# zDkaZQ7&KworA+%v$dA<=2K3D#-YGA6wg~_nvtH#AUn_#RE`eIAFTVjf-p`m7JppH5 zC(!=_jkYP-bysS&wi&y*yT9p~3F)Y>pQf@;8_yFp3dw=}&#q#BSw~9?_}|VCrX?U| zJ(03b-_fpsn{ZLZ)xSd&3cW0_4)X0qRZdlG%mgGD$xQd> zQyvQ59{!H}aEXw=>+7oEVoMRah^8{Pbdmzf1QZ)gcE%hJMgC0z4-7p;&XKcdA??Vz zM^S~f8m_BV_eeDAwyRJ%#mlZ!t)B}tAbFKEsJF<%kCBBvYx)oO`_;Qe#DPq(xJ!0xOI6A{ijG~s#v1twTfISCeC2@wNUq4 zQzKt8fFJkz9Kn|>d+nA^zSDic&Nh}r|)^<}0vVzh|n> z`Q+#{u(fGo;ESNTVm+2TOQMw@mOX`lBbKb+`?+b>MvHOrNm)IFiWx@IL!IA69x;MS zCd^JrjREt^)1PLFWRGymmQ>~CBiYr3F8VJX@Uo7xwY|`%PhCFWr<~ z&%~#6JR2?|*urh!OEcOnjG#)I{LI$OfIx4ZSDLE`MaK!xcvMMi)f+3?chV+a8Cc47o0t_(AlC~lk4Qd^)k;70)I%{z zRt$OC2uLp%dfNWH{D`x^O&2HN8`o!OwyGX@X|z_tT9u_G@i^TTFJy5KnA8t*66(Lv z%lQOToNz)f%d1+ErF7F~it|2W%Q5;9?A$&!Px&P zO;Ot**H79LM$d_?bz{iALX~PZt-#e|y}%y_jlGQm^!o<$Rtr4{ZDMUwn26in8WOKr zZit$hZ+0{ya*)DPLr~F5wJ!jE@BP(1c=**VH=pC0MUiC&XceAXC%w4(N1E`rYXzQ< za)dSN_L?aJV?}+Y79H;u7c`0G3#^Q9^eaq9+IU(44BHwi!L@5&g(s=>Y_wxnum4{C zoLjBo<#inqz34&G0s`5z%Ty8x)J0~H+JER%4gXiB@Xv=*r}JU$JPpTx6R9%)q_&>x z2*3TGmpVt#o$}F=Ny;t_A~UYu-tmC}K7*k3&1ph#_U+c}i5IvlyMceiddl5=aNLTs z5~~)#D?1fsSCL}2P3OmNbqn>YC5+Ev_gl^)OoGSN0Uu6YMt>U9N1Hs>!u7HKo-IJQ z%x$E_k+;#|+_&BH>71~crKEa=exS2oyVE3KE5`5n=|$nmQkDRof)5H6eWAox5mtq} z-}nAwSBA>!;(@};ke1pF%hh}9fXbTul;<lO{0T%YjaJkQBX zIUNE>e^zY26;$R_YSpZGUjfe6Rr8}3lq&Ys=fx^?^!qy1G_Ra$yOgWSQmDDr+i!Tq ze$sv&zuzLvi7iQ%;X*lJdE=ycK=g1Zeth)-RjRtSgX zYX=(K2b$Y#*<=+FCY#M29OShzws#?SNkZsI2$`@OzOY?{385sJweMwysQj5ho4}+D zb@Rr#I&xukU{K$AEW>9~yxjCq%J`A!)OIZ`&DxiXVC~N*iw%v|6J)W~dEV`5PeaNKRm)xxwvSBa4=DXCTNl@&0- z@#)-h>8d*o)Fix{weOT3*4?Q?H1CiY4Qd@77!yx3POmM~h)Na`@Vy43y$)dWxR11J zJga)R72c787sC5bNb&;vu!IJ;b8%|zHgc_cB3Og)8Wj1STrQrNOpzZiINp6k zhoi{GO>BfN<$vCW#Y(P|cmuzVQZf%x@t;ivPxVux?H-HkBi7auBT1ix3Pn(Gw_r=- z-J$r-?9v+Qu@h=wx}eJpsV2SVbt0`bZJ|{jRb%-Xozv z?v>$ot;T={uYV-Zdtt;Tl9W70MycORg6UXa^jVyi_vwl?nT)oQ8*5tJf`F~!CbZEe z&&kFPWP3$ST{D!8OQ+}H6?#w;qJefh?=`JSU8V_=#dN}Ch@0UUp^unf#^c`_az80U zuZ*;MDVX5}cY$Ymn=_pwvt z=_Q<&n=6m7X9ZYP$^QB?N~{^6yF_$2@#thE9AO#*56FaYdr$HKy;7G{o{>wgYGQ>( zO^Dm`hET`8hDp-F%jur4*38UjbB#l@?ORT$-G*dZ>V`9ykgDN<=9V)f6^W4}QH&)- zG1hG<-Wvf#x-1C+00mG#Gh*a{yodoKf@Xr}%X_Y!Un>Fds^t3U=*=!tbWnV1y!Cio zsCL-zIJ6%pT4fUpjhrJzH>2QL&WoTxCvir*XMmwE2sT$YrJ zR(F1~%>^G5>8g(4MpKE%A-rjsI`c0oc)f|R(`V>@)bS%=KB(gHXle{PA8&NC#}U2M zuC*1<=URZo0#qu`&s(OW%VL{5!TWJMC&n}AN%t14nEVyZJki=*>T z(n2C!;=Nur`Kj)Q(LZ+?<@P9b&M$Gs|J|;L!nF4WMY($Wxy=&488K6PujGb@XRr1` zj+l05gE}<3{w%iTB(u$b(t*a5(U8Y;vSXweX*Ve^{Mx-AK9I!6jTu7s+1aa=6mJJ_ zaJIAiCHU{9#E(sJJjRKEja@RGv}bhQQlh);n!b7H3Y>Y^y(NCE!(8K5jU&}~C+P)7 z7MMDSAt%0`h{|g*&E6aMv_Jg%O$cHOn9Ri$q1RSqx?cT@Wby9p>AvD8yRfeQ8(=JT zuLzNvzlf`X~7rYLG>wNc%&6PfXWU!sdF$3fOSGH-Ay_GyVnPq>^au4{VI zc3(P#x?z>n2C`pd9(e22cwXze1}Z+|jwA5iUi86W`<8<$ArAOd2C1S10Z3Rks`6QP zP9A3GT~@BXKLvTMA6AUnFi4o)l)Bruq03Ds(6D%sM}=d<*@>@^^Kh+XcIkyIceSes z)!UKQa7nFt3n(JQeNs?fNlB@su~946%^Cj2YZ(cJZT;KhZbH0ed5lNef|Eu4HQ{tu zIDOPA-jw61E}y2U%PVR8@x(myvG?x7=6GTw$iICRxwFn}%Dp4IlbIDgXXtL_psxX)#e*B4V*8XS{96Wf+>w zs&Hy6tz5LjvD$-_A;}mW$EEiPp_Z|Wy_`I8Vz;z?^SKj)uHgzkh~}$_9vTBM4(MjWw6^Q%$ZuK|?UqbPd2AE>52UG+=BxEU zwd0lA<)iTN&H>)@^b-I14UymQ|9OhXe$Ke~uWd(2XP(@02hX$7GdiYh)nWOuN4hoi z-Se+;Y5^@GZ;w%<2$iJctnA$m#qwde7h)Q#F|0t9(#g5Y09;p>c${^#cmIuP6g^o@ zO9OU#4x7YApG&obDcNMNF6%SC4svhEyM;;l^I2d^QXp2mNjpo9-qS>n83aFWhH-zX7*IX2vo6Wva$uPw7^~%*j*@Ev<`=y}I z)$PJ)v3lK1d9W*FCqd{t8SC4OphVnMoeJK-E(Q73Ln{ij4#N7VIc_3oY?zr|dKmUf8f8bj$k7f)Pm zi&5=+WVh>qMIP#omC*y(-{!4%xRv>p3MRWLxaKl<{*p)^^eE$Bn%g%vEc})ePXA;K zPd0u2lG-s<V7DSRy;)AGg}0<*TFv9Euf`Z%Zt0c*a@JuvH0*=2 zF4_tGk++Ub%55F{^7Uu)}!!WqZr)ak>GgedY-x>)U^9+^^;q`g2dfLPV^q!m~i{mfraHO z4I|nj2^>~jI{T0c58AOvU0vqTOT#|l5NGpyH6eIkkoZBu33{>OOA#YjwefVwp7}xK zA7yZKuj<=eaG<_%E~OT*L;K7@NHyH^qjKy>G7G^_^$J_AyEW4!t19S#Eygjm`^4i_$c z8cOVjLz@Gx5?!MvWML}r9^0~~RSKAhtVJ83;%E)u_Hiz*+`c@z25~2HdQi6w*3~tn z_W0*)8siqYG)70@LNiE1)-YLSf2w5P*ysm&!MxNHYTJIKXY6<|K#x4#zJGl@{wpD8|!CRMrFqLX~)Y#yB*6I?LKoelP%WNz=YFN@pQkYh_R^^p}k+PUKn8< z9ZEopZwV6~3IMa-0AAaarv}+vaSZ*W{wp5w3f9EngHMZSG;|BYwHz} zm#(NP|3-b2=MyD^%Mic44YdF$AK=>&To^H2Ul?jN^7o@&HYV{hLxI=N z@k4vDMmUPscY`Ijz3xuYYx~AL{p+0Xw#F*1`fAy0&y@E8I&(5P4F{M@1~V1nvznd* zQE%LCmRMY1#>XAi+uLM(nurvpGVeTdxbSS&?ovo-GQ6ZtapA1F!n*#x(wGJZo~@NF zgwq9r%#u;wxWDQUppQtGGpEa)i$7fmv5g%TfC7^$vSBj)3zK%c+^Pc~p-yEGLwgy4 z;>IBx+q7xt1Y{4@*!hds%VgIz({EFsvhM?YV=x$JzwI!Y8#bE6(+k+!O-;#qh?iy} zxkn4*x}-DwB9>>m5}uFaqTIx6>`&=BplcatnH2xUUU?^*elnx$klYFcS*mI#J1l>f z%@)k@`IUJTC;g9rGsoknVp4K)Z|1(|;xLjRM_p)v`7_c2>f0yflK-m1^>hNl9K=5O z9=sDDPJFBhbnCk~bW>cAXm>i$@oWlHYpuwRtrH0he1`4)f|pLuQls6DD)V;B1wpsI zzZP$rD^x1u$=S;1r%;Tej8V%_oJ zLj0JFEZ^Q*#RY26X}MpXs_4T})gLe=#&%R-yQU$laqWkWw62$@^Yp{na#rN(%GzY6 zJQKE|@eG>eYQ1*$oLVd})K)4v*pK?NLOcjEr=-cLnYQhrjLJ}J^4YFfqqZ>nyE}s`Td#cZ-U!#rf&;&qCs;SjF zLCIWJyTog6TiFn*Kv1oVpuu|Tbv=1a^eq$LJM{>7qjAc&oXayU>Im%GpNdktOyw~(JqYgW z@7^^x%IkfqQ-r>F%C`K>i>m%P{%L10R_LWX&$ntJ~i2B|-f`!%H#IFdwza}&3 zybYRnz7q`B)0S8aUE zkFR9K2CfFhB0~mh{`v>gm|eiNg7f>+nOAbky=BBLUdH^IFsyoH=Fw3+?dFeLT1hJt z(+33&QkEjI*!N3YOP9K5NoH}PsQ+m7Pub|;FL;kqA+PXv8S8QZOr&))e?rvi3L}r4f^^0?h4~iF zx*V~U@L5%>(1}OE-D>s|2#gOno=y`GK&-$Sz&ke=JZY>2PZYN-G@>_FSJYh7$f-*r zX2@`>A`x0$_Q8P2%_4l);FZT8uz!LwJ zz+-|6zfloB+>?=B3km$}aCnLs*}maxx7=1FLpaq;Kh5ah% zn4faogfen1T{isoibHppkJdRRV;NsBA+X>~7Gw?T{M zC)Zlf$nT(<=|P;HDmrd8uH{P zaW<>d5uwj+Q~5}gb7wizCK9Grx8u2-=&cmf^!uY~)wcY6&KIwBq=kq+r~^!p@IbA$ zY4!V@9J;+7Ztt~RzuTzdO=qPAeU%D9=t9R6*GHffA8u8ZU-&^AEn#R8%;-lqce>U(S~vq|hJOih$%rsf&@)~e15^M>oBarci?Gl#d*W9os)j$R4VeRR1kkqu{ef~e zOLB!E>w{IL>PhVVR-|xFMhS9wtshxD1$m9Buh?7Jt(&!5pPtsCGr*hX1n!dzGW&nr z=fZ(cu9-wQTN}y?A>$k zwc3?Ac*w^aRqx^5Njg+Vb9Nya)sBtljeM({W<|GI{%$4^)nlmtU3pM)rm3%z)BOU@ z93?RZ6UENrWqv(!=S2@*2e536r zh&iVH4DyTlvyeL-fyu}u?1o$7o(1src8*CB_cVg&p!VOIz;GdSf`XF5#0WXwA+I3H zbVKD_-L88t1vli^diO7UOW4Km z-0QVcN~88xH&h`S()cvD)i*{1gtcyUve_p61J_zcbSSt2pJNs_l3nH7U2PJU?oxD4 zSQ7SI)0I6Pa~HmW?Ckz=TO4k5cjtI5+j%K{$dRu5q4xh{?E`b!*=%1OXl-9_84))7 z412kxIy+}wp~fi;$WEOj+L#)APF-DCU=bHT6Lo`oe3wkqPgm>4rv4vSZy8lp8@7wC zMR$kN-Q5iW64D@ow19MXi3^l&k?!v9?w0QEUbKMpnY?>{=j?rc@@Eakc;++beP4+X z9+xseMn9k7aN;}2XXnSl=DFyHW*2X1D$&Lck|ie2_z7vAH6&WhK%Tyo2Gao#`$W^rc^}-rcYo#%K6!UpdV+WW+i9 zE;Eq-8)n~qn)i{*BE`J%hB}7r{0dvoUT(i4O&ILKWJ~A}`92put; zVQ^5@KOp()I5$rjb!yW2(~)&uV#!{714a=VIp~RRd$;OG zXECU1_CCKzbOpn#q=O{NivqvtyiAlGqp>Mo}dnb~*#xEOF*FIT{`TW9L}Y0{_4 zj2et6(UVqdAB1$KFjNb)L%4WLiF?&2_J14ml*X&lN(lef<`D72|0zfy5eFX4O)tMq z-v1XNZK99=)8owy>fzUeN}&r6LRV6OKV31w+E;q)dgKk|9U7s2VHMSv!b`h*f(rP* z^WhyCu`A&36;s5dK8f6GYf1Bzk{3jfLgy`iEbsQy3RZ6spT(bKB(aQ$U7k73C7B=9 zt7&SU#;)%2R@XEG2IE#0U)TK%yoCTv&{`OK>GTN~awU$?-;e#}rDajU;6$+Nw(I7S z?#WW6a};%nT?LHcA%AaqT{OlY_kBZb=bFMXBMci(r7(fRef-GB*1MVQ9s-f zsiax%!)5mV3s&8BQh*tAYjZpGQ2%-SbMFl$k10#Qc%cc4Ba2%ZvyJp!Q9pGSl=rJe zGzgA_S1NaH3>KoE!t}Q^r@`<>r-xD&QB$b*a*YODkOV*(qHYne1AWaEj82mVdM+k7 z$?890jFxSSqzYE;l6uzk3f+8{Zc7s$>fJxcD~0*kF>oue8yd zeCzqe|-*H0KustFuSn!X>Zy;wDg z0><!lyf%|^PPe9tX_L;o05>*j| zdBd28Zd99yNx$Z&9OAqx5u$DRWFX4@TA@SKiNUr}oqi1hKV_Qto#3=iC-{RDJk^X_ z#=C5((SwEHuwrZbHQkl{_g^bi(o#;M7Cq}LzoQ zy?)q;WJj~Y**>h=R5jZmC-YjzuK-n#I>IdM<4wMy%vL)Ex1#hNpEYRHL_=4WQ=r47 zzv?z{9=`2-LK;BjT|Z!xC*dd#Wxcs3K&E3SAfiq@VgB2{{BtbRuA2Ww$&GyGclRo8 z^C096`mS*yIUg6ib)i(kgCPA4N-oTi)}}8k8QnY7NJQ1iH7c`G zQ8I`WU7T&LtjRt?qlBsbgaxDB%5Cxwfw8jmhp={b`_+rwH%3bN%2`FWDvs0_s! zIHx=i?F8Y`BQ5u`X#SUT+PlsdZ&kN=O$Cl!Q_rnK01s4ef4tS|pjm$zc#`(L zOKKRQJ|m@y@^MIodR(#_AKY7tn`=#yd9K%yYg#14rmdFA03K5+S+cuR#IJqgf}8v;MAFY?kRS>$+5;kl2de@aL_WbpXYXC4R_?6QM9tI-Da%b9(0V+7plHd-LT?c zYQnsPu1tNIi_A)K$R+5Y08_MOkdj~jqdHx*+tOk6{)|@jHw1OnXY!99QFM~&K&9)n z3}bm|>`mm;eyABn>GE6dsm6y^4D0La?pF^G>h*O$h4^!Y?EiX>?2RtgJFsd=<@DOZ1Z+fA7Xz?+z$Ed3t9 zY`KoHUyN!UJb6)7G~5-_I%#asKJEu;^rn9YND)vj(fXi{G8dm$@q&w(ei;oj;$Vr7 z;`#N3y#L1Ot(X6TwWv`i<*TD{p6o9$r`X7+tr9pE-{e_trfq+Hg;h6gHA0e@En^^^ zrCV+^fFXE{HlO8e?%DQuW|Aw{QRAd z(Rf}+ucdi#G(%fdE)6q>26U382{gBD)oRRJJPItQ^x9-P20EUjILz595pn9Fb{-s2 z>Cey9Oj|Rgy@Ab)7-V}$bB}TU*Z00m*s8TkMVK!FW1vrO?zDbDbz{%%NZ#&6-Z;I- zd9KsdWc+Pp=d+vLbWz*;WM;Ra`-qgh%xd0i8V#($5c+fmEj`Eg^WqF1q@Vwf9HwLZ zV+l%Kq$MBydMO1;V0w|{BddU`&U3D5ix;}viQTm}d`K2jl8GW?B~43H|E$4o_t6@G@CbBx6zpHrc;c1qrN3Kmxl=`Zj!-bxw%bX#|^~`!IAfj(9@T z!PA?Gutci=M1N8u$?@N^9+CK~!1Zc+H{Lg+I%Hu%g2^JqHk4*;e+ECQ9gzK-T)wN^ z=G;yBI-a||o1Yz5?Xm;cY_ zRR5;)RTA(!9*Z9@i|?HFs>YfErB1av+NFqjR824h+^M3m-;;#UT1{`N!y4_Kx(6lQx8W?*5n+9qJ*{wK z3!Ar2_=pQXr?!bkEZEa-{uhvIRX*62;aYXP&2-k|k)%wvt>|KDF6@s~@v~9>?mA}a zKJOogV?q6Ep*eEcpg_kt<``cNnIX(THwzNk`(-g9O;~iU(Su#ht)0~BJ3oV>$^xOW zPvd3cz%x)$DVE-hFfD)=lUC5Cn;yGve-OPl_mmm+T{W}jXr>4`dg3@Z`v0(zuD(vN zo0Q90>=0R`rF)%(2w9{>4-&;eH;V4J{D9~;zzMJjJ*ba|K3-+K{3d@okiA?miIVrW zZL;{{o$Uq*DJ*>Wr2EUN5Uc5Zw#;mK!HFqbt^4?s{_T(-HO+>Z$WR0HW+#?6CaJd4DQMs6 zLupB!VP78mVD)fWb*)#;%Bt1=rY6CvT}6glerd}+`RY5p!cr1p!eicHVus2;6Pmc3 z8K9VYv;D&131r+suh}YKLcOUNW?vUo8WUPfANcLi0$v8$@P9i-y!0~^q35qCj7@ow z<{vvff^l?F(yv#{k07R0Z(5Da(?BB?j7^54NDbm)$&3Ll_i1WTAsF$k`03cHcD8Rh zYGxNfI93df^lJ8rK_B%QKG%$o_(X!`XxSU))LRx5l{ijGZ_lMUV#GIiaXn6-+tFQwJUjr#2MEy4x9I6n)uBd^}cV_Vf>>RB8$pWCWnOF zn>aQYV!q{c>4As*MCZc!DsF$PgB+>Dq^`lDW$02}`fvZ6KB=msM!p8ph9nZ9zd#&m z#+T=Y^2&90IS!{{ixqD983AU!-DEq{0TL||_Wfq71h|^DQYFm4O&+#p7do5y5Wl z`7FuI_bc(*HXlo+^dPQZ?{%=|icteneh+ML+C445D8H@W)#hd_=tx_hy&M_4i2o-tjjghW% zt=O>S*b|68o%jT-v|A~HBwfRg%WFU=9|R9ZfNT?ew8IIurpc+LUA$F(D?cQK;f(LU zr3Gb{*kZeb9AG@2JJ=Cr+ure!0qS~TRV5((0=&XIuV->L0BdPw^$W;gl5F=JQMy#^ zu^~hbZ>c;87J5R{QecLY?LD{H0|h5OnIUrUt>mqKhK(S<`KVf_ar^;Zz){j2GwtJT zJ4;})?w3FKAhpV=wV9|{FJ~0M7b@@S4t*a7ZyXpN3rW`HUZdf%=zZqQfs(imZX!$} zpmSb4P(JFP>*!sTb{*5FQQgMd#U3XUK~vePO@=o%y3>Lm!aP_j8N67K)sf(Pw;Q?3 z+(BWY6(aQABpU)PoFc$ZEqJFHmpV280R>C#@p>nCWqU5}Lb_A$)6wfot3@XT7i1 z6L|$GVP(tYOS2Qyf^epOKTP#>(*+^}O7vv+{OO^04aa=3P#*E81M!`U(T7~#OKTGV z87B(45vu-AK-|Ib9F6=^xrx2D(Ymzd+-SK)SA1Lp-TyDMgw%J-T`X#iLf24Y+1jz^ zWVYph-Ubmt^M00lf08aIqkKQMp9iorWJ40dmOtS^Av-$+Wq4^ru1$SO?9HS#d*neUNU-jL+ux+xp5Fw4Vi9)RCkg}uU2olx=9o)HdP-p zBhc2(=^i2sshjH*Ow=Vr<_mSmPfi8TJZV}38HbV1>v_4O#KEPJY5QZCCS@yGnWHqk z@!PKbis(HNQV7p0 zT54iWVot85K^~wy|DEMj_I`k5*kIYLLjMQo6Op_F^sroNL*&A6FXsN&%-%N92naLf z$a*)6K0Rjt7D&ExJZ=2Xzx8+0GWDB*Z1{g~`hYFWr1^Wy6ve6WhK!O7`+-gS##c=$ zhV6xSvaHZxe~(nXlwq4+J*=M%bl|vddZEf>7x?(M{--W^4I8)BZ!7iL`+WCjzk|kl zzFf&R?%nn7O<;>OOm;yNtiEDZ+h^1Mw?!(X2fBwID+vFz8uF1-tBGnlW5Ob z+&oTi)iZwYA}@x>Q7>zNb*PugVY4fhp2mzZtc{XbmspkfRD!bEGIe=R8BA;9F$*52 zBE&qp?ESscX3dx%VrIzD44!p_c&h$qlcKPAa6jcr94-4|g}+*M7DZ5?s)yTa>lgOBoigukq3?qo;-(H`kPeKB-8cCk}m_%vvTpk1r7yrJ1MgA?SHHvV1b;RiBAB0qpe(MZ-p1=f zv7{i%wI&58kme8*SL%+fwDL7J(!FYuCc4=^#aVY31B=_niAyA`*yYC?3aWi>`;Sgn zu*^iRa^H%61R;|uSZ-yFVnB5`1=`&z-0Bdw9WC~P1CgYar7Td-;f&RB*`^# z{FG>G=?{JdY@hL1!`O*Rq439sO})S4(|cHN=V6qazX?Ofgijs|Ea8j|xg#E+oTBE2 z<1t2S?{BQ3&G3?2Kl9?ruCE%EV>68z_Ru}#rU{NDoy2AWk`;HBbahQnxK)Om6K-D0 zH*aySQ5}Z>j{soYoRxL#=|i8(g4xGl=6x2I0?50BZRv_@lL86iQ@Wi!Z!9!Mgm0O4CXQGDvqyGdE z2^Ly4=Rkl1n+J5i(+>xKX)kn_fpeasY6(<7W)Lk+TIHMgyRSb#67Vx{;2Kp^v_=8rIpE(a!`ub^)>n~3kuc+aF>l=M!abY<2)s+5N z)B8tkeq2nDMn}3GJt%;ZjNhoxS-J>ya3QEIWI*lx<}Fs>%!%ec#`U^`ZBm-bVjrm= z?V;&Fp{m1_F|xxVI?*ObS=xHoFy6YPaQ^z}`2I8DVB2oXZhf^amzqhW=w@IyW%Hk{ zqv~z+!jSlKf;U)j1DazXWQUf`%%k^2?6jW*d(#tKGE+U_{(?%O`@q|*$c;pzl&pH+ zV%zB(rrmqkg^=!iIL6X%)-Ksva>@;esBFA}B3|SI`CQqFjMeANLhj-&M z^j|RJvdP5w*8UjAJQ~b7YNmq!HzW@v)9so-WtU1$5@v_eZeKAB!G5{ccx}c^1(Oz0 z{0$^n8?OEX&iQzYM;$-s)?-$z5{rl@ItBkG!X=Y%ePL;Nu$zYRr~Ra&rJ`dZj>J#l zUFF15rkXIwd-@jpoLPao3T3PNWTJ#iUwDyg!MH`_K^ig5;aBW#4=OlUdYYL77zaF$ zW1XZ)a0ePX9lmX?m6j#7buH`c0&eR-2=;KRXUxCmdF=mGw_L%*<>zM52)h2UQR?km z{z%}QgG&BA^;47n58L$YzT2gNw78Xd5+}iTW_I;vqzjeS574n$T*%7hYMrl!|=JF9!=F490-1cxu*zU9xFl~iP z{joaUWX*yx*fKN*Ru&=^2Tl7bHM?ok&)l0lH+}k*-Ns|Gp@TR#_1k~R0T{vRi`GmG z$0iX7s<%0jFQe)ZlSJnB_RKv0Z3g94TDTv*outDsPxs6h+HGz94}7ug9evAh=ktv^ z?83VN@Y>H4%YXB;$x12XAH0!yA$^wlWN!xmw*i@~Kkd~f_9#>4OUhDHNn8tkj&;|k zPD>;j_tU+VQ^X%{8am?g^XVEWudA8dKX7~t`GLHv`<{;7?KG375_Y0+fvKyM`y?n= z0)HaUA|i}drb}rk>?j-+LexkFb;;lFC!ndUJ%%e0oa|xTtyX4yr z&6{f@aHimX=`ir2i+`U!(jP@o`Am;)lT+T~-T3$TJu}4n0_C(~jMeSPt5chbr&pwv z`Q6GtM`!oOU}D`i`D;}m0{@tT3E*=i2MM0rMO6p)R&D;*CapFYKQ#J!x?MO`oT*H& zFM=IFvoya?_WjZEu9sen(tXu60gsTd#F_OC_x$Rg?OIBv59TvGj$-gcJVc;R6LI+9 zEzsM$0cem5z-gdlxan&NeC{p1hFh7VZ$``fkU^XD)Ma*_2Bvv1Nt8(U1aRt))AA{I|j? zip|b}BWSmT&RFhxi%+Wa%HvP|4MGjc`ltvCBP#)0D@(klD9|_HuZ@_VLZx9cN{uuL z*~9IGZ{D8>g64Qy#_$tAPaZ%JX#Y?`MqMm45Efe&!Bsp{Nc>m5&ywKZA_nD5oS6&P}7As5D_z>nj~fx%989=n=1M}L~PBmyYJGEd%eui^PHsO%4k_j zmxK@l7qDJeXeqQcEdq~$e?3-vKy*YOIL)6ctntGdkMvh~^<^Q{a%VTt%j&^F?Izk(`7eo>Tmk)$5Xcr`t%j-5Iccydfj1TS1fiZ3ktLlDS#st?l`sxnyC1(q!6(Fb|1yBkl$XbQ&9n0Aud+!j zlo!lo<)+z%zN?l$i90~gb{%86zGshzmRQdwns*Rx*gHwu#ru! z77Exy7(n<}($0u0mbegw7{SW*sq5MjM{opzKs!8qU{sJ-hi&x;6e%q_Rl4 z!K+LT>Dyycz)uOglI|@wDXAaIltswZ)}~COarAv}DZ+o#!Do?Qbxrw%c0xhop0P=> z+OkMSKJbe^O*kXQXm|)C^nI79qS=1zjZTTN7}^Tv!M^X5q;NOB!M^j>9N!K zQ1A9h(}$Y!q}!WM$e`5TJomC+paGWoul|sGOtF8NbNM^&=oF`IXWuHq$ulP0T|E!Qegxw7l2G53?BW&})%xl1pYZYi!Ev)K>6nP@^P{(t=rRO&L9Qm=)YlrRHCCiB(MANqtAmZ}&Un z@lyG2uc3q5I>iC=tt(MdzE#X*k(aLHrZJ2~?Tir8ZyerkMI<$KHbx;$1c}U$Fq%w) zH>Xro?!B8_$b-@YA6C312;fOpk0W-sYlS3s-D^i&@8}0Fi=CQ$$NKC_9T)d!^5Fl0 z?!mCQD>B8u25npsYWs0Q3);+Tj%*I)i{t1JtI|F*VY3xmX>IOE!i^?{FB%iy9f~P`;>PG6t-rk) zy6bwMPx|vj`xjNCz`@Zl6xi0s&z_^$%HvZ+F~+{wC?$S_$C*&|zwY$iR%LOCj!a?( zvk4tdIHqS;%{4;3{p$%LE|Mt}{N)D<41z~|=_;enKpFDKOYMfFJ~uj4IHjt5wjbxl z%s08q_YC4h-Ie0pzAfKd_=jQdT9)ZLU1tvyCXyg!xPe3Si& z5JC<2zOnphgf`Q}q;`#nvpZ{>_6?V^UqEwgKQxFoq+4G4W3^2VUoeNjgo7g3LY>Q2 zi7TsGwcMoi8`k{G=#PTIZ?Vd;n3ySS2$1~K0yqwBts^m9kGQxLCns7YcfBVAY=}IN zRxeWk{)Ci3K*|gz{Z_O(XSZ)O4SO`Dj`Rxy35Lay7KZtUg#VVSaXn3(m!vCo;oHYjd?K+4IsfMGN^v*ZQA&a4*l&dfs@bV} zEcLPwJo;NPQRUAWAo5Ub5?L0z9Se7H>H^+;Op$W{ z&J?^|XC`~OJ9&J1H-Z@0bA zt7FHmevM+e<6d~;IPQOlSKz$0RCv4^U(1pfD!(lK%WBP6JN5o2e>bk;Bl%qaNIrFu zPb^Kxrff@!8`Cfc%tIU^dnNgy=JM)1^ZTw{6q%=a7#5!aHbK6WXvF<^))3_jZQ zfEj$h!UujRU81!gC1si)Z>G4mQMnNIUnd_Ke`?mFD!-7VkM8$HcM$BGT`bq#2#d#(}On4ArCT)nADH-0zH+Pag4%v4?}*7LvhwOmZl zp{>ceCsf@<#rxg2$>d&;QpW4q8v)7*H(y4~_N?X!G=p78)Jd$6MDB3oy=L(n{=0h~!#IMURxzwq${hnt%c zg*cQ~j>c_%`sSOUarS`W*8!E=`K)byy;(c!dJ&uX4LD?;$TSB#|+OL6rk7_RAwlxOr~0@maN_)RjujL>ZdN#}FDP15WB_UqfjODP>WU5z5yU>^ zbIrrCP~_76KJa?#ZM|n1Y>ngQ8nS2!6Peh?g-!j>TQQO|ddz0ys2Dz=3c3QvdyrqT zn^33Jqtk+^F!E66FgVr~V;E!wqD+Fo1Cpdxm|jSNyt0_I9)572R_B)krf@fSB}Su+ zWwKd75~E+}9IuwTkK;Yw*`8EVxhShQ(_FI1+SM6@V&DyJi1V_&(RPRcvy`0FKVnJ{ z#F5s(Ow(DF=4DU0i3x|z9r(hE(f^nsH5(6rDY7s(>MRot1c8v@c0E98;js%&zd+U` z;vkkIgKhhmm3OD9y;kr{t-07J8#ecE%bD$5MBx^vJ~#FYeppVK@srnY3D@_0YrpF@ zuT5Rh0q4wK`JfVfGF1xeFudKYDAI%j?PmleY2AY9IPy6pEtDme1bP#66Hn?t>aaI zjD$Bb)eSm0(Y{9sso&D8HUu*-3G${XwpcuIWc!nRS6{6ztak1L>WF+zqCB^%Zmi*; z((tOK3t6YU#+gS_%X4A>e4y23(ovtSLuIoKx2!P^m~*=AJdtU5oWejM<7}v$>%aQ zpU7p2_1JD~Zg3iA}k-}&Dnt|ZWA7^cUV6HIt@N&8$c{me7Z5;sT@<`(S z`;DGRqfa&#dj!yQfwM6PGYFEYZ85uD7La;$&U|`^;*?I4lZTm6ips= zooetWONy>o-K;co_CpBHqY4}r^GN*O$%f5Qpg}AJaHfmOCV5#vTsQ;ho0R))=avti z+`VXW5gq5BPeQF{cH==&ZIUH?%}y#Fbs?{F!6DPxzwbHmbyw;_On5LH{IXlL!Wh?! zxA~y#>`I~%aiZAX4GUH28zd2W%;DTle|VfW+a`+tyAVO+&lA zNG|{k<~Vq!?sh%;zWfZvX;O7l)v+%Rce{txJyR6}bTPeuCik?n>-vxJr;X#p&4>T{ ztG#<|b=Zx{{@dR7Duv5@?0N9Bl2SyePTdDFAR2ds-S-03(#FQ+{Vn5g23Yd#MsNND z=>o6;Et+)*ZhL>6QHGVt+lqQ;tv{Y@A&ugAe(uex59MHj0BSNC>lHQQ4+ga+4Fd%e zObBccVu16^3`C-kphHfF_Y0fJes}Y)f7CsKXv*@8PI%1;IoLL`J_8-^55=^07Pg}6 z1#MHBq~-}8pjLF$G{WS)h1fb0Y9h&kvtyMjoe7-n``|mjL>}6GKyx`_bW`Po#N)X3 z)K5rjq>Gfd#;@8(5tZw)#65{VJ@Y1z(`mU#YO`!;&74DMsfB96SpChm%;F}7O z=xR*-zBTm}WWkL^)u`jlnf8Facx``US8rIOCp**YjCJsMS!3W}!`uEwtBSD!$~?dH$|>aM*F{>CoFM3KV6eFQzeKOE-Cu1wuUl5C zWB=PrAmvtVO#J0>rbd}rtNdfZN|f(k>cv{mutde{f>QrLCuAo?IS#i-x8FQB9fByj zTunWVcNNU|Qmt{pB)pTs1UO&NRt0T(+7ChU+&^*?O%((EZ#{GH3>d?~C^&@SLm#17 zKXOLe?I7|%x)e|ju~U32U=alRg7Oasj)RI#SDywZ74E>)pW`)m>??`bP#e8`FQ&U_ znX?UuzSq2HJK>{vX_opQ1Me|NF8BDa@G%)U2Nv(oQTqDopnMnQazHELPVx|*p$kz* zwi~#+5rD2AG`2zK$n9Y|S$d46 zdjs`5hBGQT&zpsZOSb%KrGoXOR{Lbp_`~JG5$7;GIs2G$bL!N4eH~3E#?Rm)HMJLv zpsjY8hs7G{;Pb8f9{smzL5(OG*si=wo|Ai+^7|34{=!km{>PMA;1J95stntCBl7|` zw>V@T19|61H*xUf-me6_UZQ@EO$&FiQXt7_TkN)Jd}yie=5Zmz5`(*Wv0R*Luhj47 z9;Sgo7O+tZW%r`<^KT8k86)+^fab;M()1CSb` zEudoc^sbq_1cPGbCPt0?K?ry(X~xoiPghrW7g7A5-{buErv#Cg$E$lEomnWh zYrv>iO*gl3Hk}6e;rE}h0zKHEd@D{scp|39gR(ful$P@H#s1N`PB*XrnG1Pd7bv+f zv0j1U>}0d*!M+Y3cKHC>u`0*sHg2AaLS6X2V*3-q0HJG-OgcX5rnMzR(GFCILSk}Y ziglpdZ0sJA{t=$5O$&o!^*9}goj~NM$$F5nA+cls;~vK~A0CvVsERiUg5f6yMV(B~ z+HaF^j)A3U8s)!sl zSHqxr2E-!@s2CWu75%?5bq`>X+A~9a)hbK= zBY?LhtA4%0lRq_1U*!$2IWU1UQ1&UzrdD|j(#qd zJ7y(>_b(F-K=!e1G3phesvxp0Qbu1{L6Hp$~}+WN}HLIVkE2N>C3(~Yy9_v-OlCsm2pnk#}7inds?d z**YGb?k*ELN>{b6E^mY@Kx$E%XTeF!^6Wj?qA+_M&Ixe)=({(EcMua z6qbF3MttKqCP5S|^dzvCkjRZ2WFqCb>R)JS;Ze@`jTV9Y1{40QXmeJ5zQ(!)e>sU2 z^H2<(LfXWOlaLgqbn{=gWzcPKvwl)F!%T9?$}T86EevvChG5z1erD$C06&=zqlQgh zx_APKO)CM>PyaKS>gT8U--hIQ*y9` z)R7`Rh7twOboG$(3w#ofa6 zKwP0J7v7Z)r~yAvAlS^C>eS6GS{p?@^`8o_F;;LvjS=qQ2RaPDasW><;2nNVoWL;V?QetNzkH;PC18;8I=N5@SXsL$cq*xjsl z5k@aai&D9`5uz{6?hQBMy7LI*YV#ej#P5QKx+BKh>C*uX1+J zg4%HEJ|Bu9W+u@jTSC3)rv6gXuGr7;!u^A<@^bqFwgyK7O`^@PvVPRn$5CEx;Al(= zIiLE5x@FUboX;}K;tk`ubr$;{R{bQ5ZxZl&b_KL6!bL~YnKShb?s<(u=LH-4JsakK zetCx8uQk|bJU-ucoHdUDr_4NW;9bU|W4fQ({9Qnpz6yg2)`^`Rz%e7=Z1x_OIK;I* zf%LxyHAiLu{|2}ptI&g#Oi1;Ak(A4?dIOK2(Gdg8el}~Pz}4M#-54GnjpH5{(GYuB z93O63yJmaKQ|SHW?()*9>FH+q+BLg$c6Rn&B;YST)}|b@&nN$jwi#uh=u&4Lb@1!U zyu5~A7OwO`_1n;9os?58EL;-T7?_Z7t~884SZ{j;HLGR?XYQx9DXBU!Col@7X{w4o z_=gCr39(uoXcc&8OM7AAOyjN zM!KAAWgXX;u;;*NCZHFJUz~xt(FUeZ?oTYS&l|%;|l77i~EToAO&*+Wk-p> zVy0?@^q~KZC|M@G+WzE?K#hq+xmSX7A-K;h!+gNbFsedf4%Is0>H|$YZ+uZY)pl9+ zL+-XiBS}2^W$7MkFcln;lfbj;b!rGLwU%%Bet7d9L(}fvjQ- z!BE`#^G(C$Y=y5T6BE?>lfBn;%8is)_O8i(VGft=6()PdtL9IL$|Vz+RXuJl=|_o` z5sCESn>`X%vdaD^u`$!joaMCF>-ahZ;F zanE@|-r~A6Wm*^uo-#ejI|1jy^?)nH1Z_N{S!fKX0mmq;**3{Yo1tudju8P%c3z29 zmHY?7jL`B$BkU&^`@TbN2Blg|qxW#XBjfPS#___)?AS7 zhmXLGCtLSUAbnZF;qSO{<|$8tlPb(WOoUnZ+ogsiF>Cz%j^gu7uEKzw2Z;EPAQ`UF zfsR1@48k;43RFmBt4Z?I|KT+M+N9$sZ30#ki8wB;d-unvg@Eh5kEKB8WA)6;WTMcs za&~HqJ~fX6MUPQ=8>BFi&g?CPz^ash7Dn&M1gB>);Sl=qKq8JP zOT4hPJbL_s@?$E@dxgd+DX_`X(7fmMs%qaSue<4tXPU*u(*;0B@ETy56i%FQPmC6{ z^Qh2!K08uE_=-DAA4se?N(*Bq6k6#?G{J_Hdj+i=SNxBg_-g;`KWhdZe@c+et0*ie zJ-A{lRZ!!<`TBa^a2A_&k44N-JKf_@>=Hi3V$e06fbN%?iV?57}vCen_Hdzjz7q2Qt z84D4$YzN-hGkl5qoJDs0V}1d1Up~q*3N{y+qF4bUzegy6>abJN-tp;AKBAstvfvjx zppfHV;_^W<3OrBWVgIojA^AR95dHPz67-_7LbVa}ncZYBB#ROmBq(MOIeDtpQtw3O zumBF=E`!%g;raN+gz8qBvz3G6Zn^D%kbk;2ODKnnD5oR$G&ES=J? zu`y*!dwZ?Gy6$E*-bhy zLOPMcOW^q5Xhykp?_jdCEvdX#XBt)htR?W~7ho`2d0>AIm&9%Pev|H6kHyyVOjYa=0VocpoO(>j^k#qPDez z-{BDFRrRP+sKXIZKIFJ5d{y@2`_l8n1?B^`7VVybG`Ie!umol%{y}`X3B77W@J{O0 z|HIc?#YGji{lY^_3P?97(%lV`(%s$N-JyVVNH+-5-Q6I<(A^9$bclfTUOdl!_xt-! zzIDVACu`PyU)Mj~gAg&fti6whzVp)XK1LRYE8yVBcb9Tah9)AbEGhG@&^NcqxCV6$ zm*kyo{2ma-U%EvAN$z7&XxtatEnvoqN=r(lF?Y=EMF(1*l6455@C_E@)%1+CRjpAX zP7#0VYbBzm-r{u$s82nGTHAA?-0T#F6N9CO#e@VF%#)%t?HbSuW*w6b4mxsL>!0j1 zEvHg=4GcaF@)a>K88ZoJ5djL8^-23gd_!-_rjXGXLXO>&hRM_rxY-&%mKu3kH%S0E z6mIuB4l6tN#g8R%P9z2I{Nn|8k9AbeRMaF)NK3sn_#Y~e`0Z;1f6aS2-kqtR!q;?n zlP`}-ga9mYveBhSEI0)+eSW-SH|_=b+$>w|i9AC@c9G)GQjP*4C&bAlR&+4pk>tAD zH`67^YKnLRR$sRY%T&!5)vDz_GUshj)xNR9Q@8D9MUEVVr3Epo(18kxp=H>h-Fi1_ zf|g+XwPTfH)7WrbGn~~)b^Q3rev3KP^EG7&l-Uqmi7$0qbWj;$VXgp@v|$)~@ifIP zgL&qvi3Ky^U=fm+Tn`M{iJrmO_sRA3215L%8NAhz#vdo(VoAohTlwIeKc0Fm&N65I z%2v5@d}PC@m7I5+eCUQnKJX=$Qge~TtMbHJlXuaGi@zHF=bSga%!x3=E4`9WiCZu? z{FZkaC%;68N5hk3{GDT0sQ@eTE9Ix~#Y_=%QB=%)SmT9@&tQbqq%x*=YCTGG4v6q$yWHYAr$_qO zpxGs#na^Kb#u<^w3d>m*!AX7JlXD&%?vtL@g(0y2wkROSUmz!oUk=P@g(DnbXl{5p zO|vinP_W!Hiq2mu2yMTM`m|Z9qx{UBRPOk8g>U(|Fk@U!-Se@eM0;IFG@l}3aaNq- z%c|^g&h%q&+sJjw2O>gc)L0*o`jDhKPVd+wDB4q~*uc@xU+}DMMTqEWzJ&M-XTG`1oaMSt)%wwFwXkX;jRcY&zz_5S^8 zPwX=DXHkxPbmQbLG6y;Vhkq2osD>%J0K=MQ@Nbj5 zYGTW4N52@hMI%~%4_E!xLSMM_;Xr!hZ;=cN1d)ZXQpsPAYXWO3GE(6&%A86d`adT4 zU`e7{8*ma%@r|)=wLtkO+vL^EBsT5mXuZjI@XfGmAct-33Y4L_6uQ5K;2psvU{WEZf}- zQZCo096fV|5Vv7Us>8WhVj=!m;>q6?@ljQlEHwjiNU%zHr29>f9e&KTwW>*SZPM;V zz^fh|*8CrJ)ah0!&wq6@uSY3Q)JMf^+E+Yik9hN6c((6R+5H;eS;t>)cF6MI=g6Ce zT7y*d^(zguo!a*B5WLpsf=c16dJ&A_v3j+kisA!s`B)c-JR1Bzl}b~IkO(3T;&Pc_ znueW;CEE~shXQkL%F>MI&G8`CA z{8I#O30F&Oiw;T7R`>T2u%6aB_&oH>pgXp;$6tD)Pe~Ap-q-2wG^}bJxCw!c5~?P+ ztmjOC?%&Y{$icSic>PGja!B`|2~Vb#fLa57D5b5POdHOs`}&7r4MP0YrE5~aJ6tu= zx`dc!s#gThnOyt8o^dpC$#+9!ljjq+c0EeJY`8&tniI!5GrBEKexJ||DU2lnawxvN z?j4mL6ryL&rvr?{337$^dThH1U((={w0lAJDRW9 zd(Cif>D*&l*)o|cRjGG@NZkd!oWI!MFG!R5NVFVdUm(2+c~`wDiePTg-v&gxP=@v0 zaWjhVvZ!lT+j)b~=zLVhOP4X$B`k zcWkO9wTP2enU=f!EzVX9u8_yzlYnaG>pZ)l_#{b4YZ%8aye|qQP!6|*nQlX|FyiP< z$MUR>gjj~MMY7GVr|Q}fP0EAB=#y=KBtW+`*2><@6>5^9(_3a!=77pR(?os~r(JVu zh2jhs)6#*;iWd|sgaQi(4&n9RhwC=U*)7?u5x|gt^KEW&Z-cmZ&izmuG0G$g%<)`b zc1ZVYev81!X>p@nhQ2saWz|B-Jf=$#Ctub5A&m+eS+`?8kny=8>Cq4ki!*rXq5e~| zaev*7Tk=9^4om*~MKtip2j18QC#c$)?xFSKy(fy_?3-3?O?z;q(cW{ji1|{@Vynlc8NGbh_$0h{BkKx3WFED^o2LBIhY`i8@mcip zr4&WWMnB~&{V0KmbA|6B34X5kdcme=Cl0Ru$GhuQ5O-@!WQ%GV>Q8+l7;*WObuY(U zJ2Vil{7m;LHV6lXtM$!q9=V0T9KN9+hc&gR>h~zMjH>ib8#s4_M9G4Q);~2Bh=*EF z1#_Ujk-=Z%MT6C6ueotUho;=+xQ8Bl6X80FfN8M6tcs}4>)ti1EXMRX+BBTcwd`}5 z#HLXBpxQixIt{S`?sidk{3hu8UedH`6)B4lz4zk*bDzGgVz45PM=#`>DWrBE=m$E) zng&OFo1i+mY{2+;l7ufYyn2;-c;0u>8XSA`h}gRgpH^6RJT-SZPf$DT@ou588VW=U zreSofOBtK-Ec=+PS}g$4Lc(<_M_DKO+H6h|8f~6!;a#1E=>K_vwhF&OS|RsS^v|qw z%U4QD0gD|A-_M*bWB

    dukLCVEB^h>(&6gMR*5F|L9Qex6A)A26p;J@e;?i0%bG5 z|2VzeIK2j3Eq4cWykd4*2cE}OEn_pqa$K;|0}(ZW*A@3GV<`;9MMVQJae#ofB)fid z8iBlzO@fJ;0*iu{v=#;7pnxyjP;c%*__r z?=hE$@j2&U2#8UY13jO8{rL&`uMD=?(1d#T=TNZ$$&%tjV`TW14xRBYW^+$~VAZBy zboNVYGzx{x-*?tLrtLX3!XG3E+^AL59y}dBB!HZF5p72td?|336+mL5O$HT%tns?H zP8G-LM5IOh2evr58B^=wOJsY?SJ}U&Bd+Al>O3ottmW5tW>vno`b-L&M>hfX;3#-B`qN_7O6wWpN=LcdvpF6S(rDKz<+ zHT~WWYb%W+J99?&{HPxW*AJv5AZ&ZSjgjqD0M|7bYlh;S1&dWS$?G0U&@A^Z#lhA- zp=Yh@XN2sD_j`MLg_>!JBGrspRFDj0>rgosa1 zxOyM*yGb6HTUO)q&V!|sY~==VgpRjHVmNN&S(rE8{>x_zA+13pp@W$$UM2Hx_Nxk& z;czb;okA|dZ~qO77~_`h6?Sn|!LRg9gD)z%CgDiHVx8ak08G3yq3NY)*Ei*;)al-x zZk5#B>Y%?4p6K+A4R%UUgDG9B_?GpYpTn}THAKy^V{wc20ZVN_a4Fg3vRfet9h8b; zOtoh3PK9s}gUBbmr3Yk#t&({f$MOf?gfz^==xvEQ?(o%)s5gtjW_#+=Fe9|oyJn+0 zjtf2nR0r_Gc11$4J#rhDa`4;JhKDYD`Gey($}S;0$~1xdt4EVq4|TR2v= z%7W*m{LF8NLlhL&MjZ4Bo)yk1c<5F&bh7mK7s2QLuX-SRl&dve+;Y| zsjnBMy$1#Bfy`kw5&p>f;);())in?!DDnT@6@d|FQ3=FjJHn*bEWZ!VVE`I}bj{9k z{m!OgFE=0edARyz4a#5pT3epZU!I-HY?@l^RBj0sc~mK$B3jcwOqKI&-;}RbTsO#T zHmC3NV{Pf<=r_&TGI3UsBMHIB38C6&a2?nz)t% ztO(r9ijRk*?9fIuumu|+C2-}R7)@JZ>P{?>_q!!OOm@=9eavW~kB;ObJO)ZId9<8lj0=Q3K@0>^~N4SBK zT~0%A5Qzd3>#65a??Ba3Q0*~qG$_m6fSRoGd~)I7=kjyuLyY?aMBCYT#~F1bv~*Id zZhgKRA}A$U+1T`J0$(i;UWJcFA~+)`*hwx&%19^PW`2Vw8nbX1o9QsKhXcB@@zp1;UTa7Ake>z0M6^G4Q=` zV#ldPkaOO@L7K*A5_EE4S0pdf!?0dlTdPbMJ6UD6Tx_5^y|L1Fbm2|4WbAliK#qYL^tT1wq~U=V1L{c8`0HB{%7HVGwzaWKnklnJ>gIG>=8$z7eaNp9m&Ye)S5Gv+R0;&jYhjC@y^738lac)F$2r!zzc~&QR z!Dj+H3uX%3>QQBkGF;{PS5BdJ$p_3i)-G7wiz^NX7}-`z7KkJv0&x)IoCa_bQOK5m zBb0}LjVT}*k$<(m`lP84{Sz+|@~Ug>I&g~BA1%+%teHYZ3LC)ua=?Jd`xeq^=y8V& za1vkaR(!;W3Nu;Ea)fl8agz6ZOLT)2$y2 zFF7SdAAO7sc|#wI^k2FDLv;E$!L@%6ODL$L>2zK*O7sMl&gR74skQ2EY5p!^W+x*TNN8 zKuIc&gwF5gBvH??O;Y$}d2+No&677`e&<$pp)RdB!m>`Lykz4O!PrwoPhmLQY)KQ^5iLuR=#Qwq^O&P$6)y2YC2gKroGm9H zI#7|Pc9Yp4GSZv`NbaaYg@rjL_e`JA1zH?ZI=2nSywiy`VhR~t z2~O`7>(${rib_|@6syGm`4XQcG78Y3XwD+zlQqGMN08fblPHyfG1#)m6M}WUPFRRe z<3>+>Wxw$I#)uVd)DZ=0Dv3NbKAt)SCEwrk`#H6e2hZs5&B(E+AXTI-+P#LR$9cyR z%pq00m{dLoSf>QFmjCYp{(3)sdUdz@Lj^Vyy?P$j?>Us?+Fe`LJ+puqm@++Rw9#W> z3^9+Q9ry_-{@ZhVIrsW=yQNQ;;~g?usv|@xsoz@+D6akt%d+~GjGjT~s_-O2rP!G$RFzn8!9z@eW=&@h=&s+3#ZD&3 z;4-zg?Ry4_qFEE}?fmm_PIoa&k$CLu;em*VNek?e<|{&^hLfA#MhWksHOv(B`dRJ; ziWxgzJP@uZ>Y_ns0o+yWd$t&h67w6}R$pgM@<`au(%>q|3R2YFf5Da6(!)~8U)$N) z<`TrO_rPV+a53&p3%W-V#9|kLh3y5_QMH$b0{Cu8Cd3w@>3(rsWqx#UgMH~1Bde+` zmc5v4_IYJ)j5!)10i-vA&iZiJXgHwes8jy8eP0M@(T1`it@d>zAoF4yDRbeh%*CH3(V^!ng93ZE!|SlGJ;pC%dTiZ_bieSv`Br1n!$gNH;pZvX8-#M`vj5U+LDG^4;a zPcMI4zu3pcmLO)MhnrgqBaPU`mY*alhk!l5fBLSzT?TC{LfcF`3thR<;cK+|eyoO- zhVz_cHMf4!F{;)Kkec^By-vDKvGVYH)H`gNc_~;RwYmBOa&7YLX9S#H^$5mpdy%d!bCM@%LjU{P&(pQq86!T8J#RBIi*_oszNfTSDY| zS87l=SWqqt*?RVyHoo%gG-bV)-0eqV&a>Y6$Raj66k?PJojXl74bRH#p39L|=r=#u z2Inwz4>m>qn9S4opH#y(-*Xrcr}%9W;o1r!H?UDl&UA4=s}AGUKMj&G*KD%W>X37k zvCi6>Ed_GFp*%Uumv}rE*mvNS7K~(XVatam#T48A9BrJ<>0tdFgGDQ78-DDGnh;~J zr>aT?{PxdZF~k!23@RE@r$qx>eVR!EIxWL%7(%|`m!ghEI~w3)!jQXeDu5%(^)mO= zM&}Ale|kGhEc)NPo&OT+uLof18%#hP7ogbvC#8lqzoM!trQ^I?PxyX1e(dRXlLeUf z>K-p5MCR^Y&4%Mr48BUD9F{WO0v-mjqvK;WKUw8VUp5Ki5IWwpU^8h0Ya^LH^1@hA z^lZJkB)D>r9LVc4EH+F9ZPHu+U+T%|k)eLEx+YE3*z$sgjfbL1Cj=AwNCwiXTkBhO z*dN4FD!` z0NMH)iSr-G7yym4=X-*Jsu*s8GgI$)tf{%#Ry<-702@)zBC)V59?raaDpa)ozJeSD z>#tp{%Z)b4!}=YcL)63C2TNP_kE$nd`2#)05c!og?bD2h39I#hYFIZ+i&BN36tW!^ zaTBdM{9Vr3=mgae8qMV@H!JmEVG8V~S&;naOVyjc%M)*X^FQA_I~dszl-l3Jj1G>3 zhL!IkJhZ(d?Uhq|SCd6VKWBib?FyntU@oe^DyJy@ORe>erR)*aYc@{Jc}>4#?c9GnlVWN5RT6zwK$=uuH^e_~d_V&#N3X)2sa0puZ^?{t)6#QV zg4-sIcAGzACu#&Ufl|!mKWE7)i^NI2Rf!tUG$U59T^81+U`>T|{6J_iUh_eE6mHyM*^50p! zv$Nf9Dqjo*V!d^dd)q1f=jzG=3eItzRp9w`+kGn(@D#;RJ>{72ny$k9jz;l&W+u_y zFi&>@Iwh_Arb2Lhee4PW1xR-8%*6=Ch7RU1*yWz&jJ8+K^pu+>EDK|l%Qzjr0epsG zT?l(H71FpXi7X|b8tiL?^H&LyKa)-Y762_B@L_|_cTiy21jt%CKKfd}NDW>hidN9e zbA?1AFXB121M!%>Vv9&WllkGl-6#q%aV_lL5)fhhB|qVh|HyX^GUe?Ic0NgF8_7cE z)cjUpxE@(nJ&jlom4*~^7Da~Ck(D#KOwV;rR~I0NCegCRHP4`9%gab=hlH(amWo$Z zpxT8-&X=pjH(?5WjKj@G{)+}occ!_K;*i0jXgbJgjF<^<7Ulq2q@&@}f?o*6EGFPj z%WX4PqPv6_S$UWZ^Y<>R*$kLdsUMD}mg|s26|yrpaqHY_ZRhC`mI0)Iyy+OwbVXZC zWODr(eIG9)?U&UF8T?%Tcg_c!?kKXC6^0O|2T@MeQft? ztN8E3pmPPC)S|tuiw}?w>3cO|1-;w`?a3M4Ckg(Y5_cVE8yN*8hYEKqi`^eNEXNbZ z#$;n#4TGMpS3a0N+?+Z}J1Br%xUIhsw3qCN4p8Dt3AhMP7rguT6}9ZIQM9yMK(#hL6Fx$`ZCb;IBi2Dscln)xRn&3Bj935!+XxZ^1-^)nOQgv z4kY=(^LggUWug?#_-8K+DM+=wF8s(kCBIu9cFlb7!$9~Om+iO;hB_m?bzW?Jcf?!W zA|cD23|^EBi1%ZPTM?^Exlk%j{?3}SVkr_5fdZ1?YNmmDS_#6SU5JUVzbB(8?Wz2c z=}35W<4H2V+jd)gv?c1C&wJT1&w^k_cfVpCxOinx{gp)ggvbW$G;*%TdTjkjQD6`8 zBvW99ZT`LcSOg=!Z0VsvKWI)mV$K_Qw9fWov%mnBXgGusBFi*tj7w)ys`8iJzHyrr z`kABlEy_*EVa+@20e}hjRNrBJd@X}^Np$PwGxfp za-1Nx3P1*pQeKfI6cSr{Sp%!jB(AZzrXX$JAN?!#!Bi+4O1!#RESMo^h_SBdq)A^M z%9(U^Gr`0aH><=z51xefFYuCCJ1A{sK3w-|vzU0WDoqq!Ns?de< z6^l)^eNp8~Zem3a1ijYM(s*g6mW{b(N=v93vtcxZF()|If)10HRe_1Ku-CH_1_aoq zFd8B`u*w>oN`=VhqEI2t6CNn-jfCR-1Q7({0E?vY+^RqwT`p;9|lT^_L5YU-ySKTH>L`1~- z5o0cw!=_Q+XNQ1L;Fy<3tL_T0o9P0bWUqTu)qAaV?+e?~uEgCOhgZeV>r;~_6-z|D zXyBF8z5y1x)vw}+(8GZ0zrpe*8=3qm@?`TGINx+bGTrg=I0QL^Fv2UUzCv~2<2wKTtM!4TIH4z$3=EOtK=Qz^f6*4oRA3{geAVH zpLC)OC!SU!ky>Nfe$Luw1imy=#CV=yFB4x>G&uHp&$5uRUW|Fz3M*^1kLS{S;tQ5R;T7dWEc_< zq4<}oBw8-pvJEv1G4BI2e>s$}A5p+tB8dN?mRWQMjcTgVmUPi|MPtxxf>TzC=k4zz z)*YL}yr#|S-K?5L=wVz|XderR>8_`(Z4)s@*+f9x+2;Q9D-OLa7+SNj|7a&KaU*S^ zOzG~Qyz=qXl#Pz`V^%~dxwL{=+7Gd(H9#FkCI1lEm~QkhgcL=DS?D%?`G6|9G_Bn= zAfuu!?xx>Pd{??yf(qQ+hqnnpUXZSv&dEkKlX!v8*RL# zWK~>*Fw1j>{*RYHCB;#j6;ooeWqdMYb`YU)W!hrJYmOF%-ZfwSingDGcv&|;e87kK z|9jyaZ&`2mfBlbQ>J?t#dpK#poqO7T8>HN_miPRZCbsR5pt9pKAW;YYx!h}Xn*ANo z-4fI>>80ZZxh%UGDXS0#0R}ak&e8_sgwLr|LARqs<@}$h;@L*;d+3?Xr zEEZLIKD^_aH|!V9j~a4moK#)^Fe!msBLG8tuR0mv!lPLZL4eXfwAz~u3 zI}>$D#>a(UosI$8jd3K797J-Us?v;>D>|f|Pf)|Vk8E6$H{J)WnZtbx%O6X|9FtRW zju^ABJ@!ibxVNoiJ3YTO^}4tyI&;Eaq+3z_LOxpiQ%g`K5|QPkeyi*5f|X;zggG?S zmGRxXpH$0$b{Oo```5 zMsqZ*a(g5#a-Z0~Z~d><=gQLK5p-nedq_AtZgeVid#^tI zDaKW(cb(urgvZ1xs|3=o{uN0a9DR1+-6=neI?YmK>(Jz1#EEN^zix7_n?Fa0rrScL zeU6u7`g{_fX|-aap^wA;>-q~vY^E~@7)NEQX);hMW0(tf&0THF*r2Dc`oWq2I{pLa zVpg$1LZ;|)rgTLwJIiShhbQg>LP$S_X%SJDhL^F#xW%=j#{fd|N%qg9GOWJhI5G+r z8K6K7>+pw4sF2g#!>m~&`&_(Tb^R5aW~f+M9bikz$Mon9bS#{cyzQ*W!tcEay`3(8-28t+@cRZuhOC z9r>CbYeAq2( zfNeH^{X_Ja-R^?X24&v!3I1zo*?R#7q7SXR4^&~pk#lLb3Ju2hgc#rt-{J~IKaj`= zXSq8g!RSW;c4(J6c-+;&m<&kN9SvQK&OU}SI<<2Wb?dn`ze%tq?>}$SQjK;M^Mz$F z79Oss(nVYUMqT*9KX%R<} zMHTSb_DNJk;vsRZ=(xi=2zPbup`xGnH_m2%9D%2oC{=EFLrY{I=FhB7RI2st9{nXH z#&M=1vy`%;mprBwsys|la;LoQS#5n+%yeyP!kpH6TJ}@ykxZeC489V%$L;pH- z?*TELxI|w1{+C048uFgx6-A!hJ+jO7*wi9S04VOY?3uKg%5-@#eJ@d0`b@O2UAX=T z7#*Zk8@f#XEw^uuWq28WguZOAyWX6$q_w(RJ*VossYc3-;ZV}{CMQBukhH4jJ zdp{YmY?$F~cl)wgGn7aw$bsB@gq)$9bk0y>m=KK{VHoL5Ps!MrpT%OZR85e5Ingg( zgN?iVftvi9g-xRBqI9f0Idg3~TiH>|ZKl|nB2$k8_MOrK%^$huXzA$wqg?rOX7?9E2C_h9jxhB=+CCFt6$-sTFg%TQKM&H`v*`187yb`S!xQThMCcE_UpRb)0EyO9+) zO@V76t>~}gHb(Q<=>%B%<<95s*Hw=uD}Fg3^|bx=_jR@)MeLuys`l!V3;Z`gK4y_- z@Ug9}O&9;T;-#nSAvmt^u><5!Q}9l=v_J;`hm1yfaN!$G#(xFRDpy|A8j zX5t7Prec!qGe2%O;3(l?;bCrVI6)v4lg|=j>e#S0R}%qNc-&d*n3%91Zuw|N#w{B% za*X>811&C$)d)vqDKvlAQO6gMgtbQDGGtDf&hY@_Sl}(>iN{FnWWVVnhz;&myjF*B zm|F``RG$|Ug`xkS+d`wQr*jzRtS&(ze>79!XMy!LyGn1<6jfsnU8!&%lGQIE7V=pP z;!F(|$tl($1aImUX4+~}6fjee)09bMf;DbG1&bN6$`iKfeDBjJ<<>@YMr#>caD@{F zJD{Q=5DwSveP1;h==zG_uV{a0u3=DmV@TfI%>LI5fpGFGC4Ea1|Kfms#kIjZ=v}&w z$KG)tJ$7MND(|~^quKGotMWyHL5Ccu=JB0Y?4=+ib-;6@l0Qejf?>&%*j)vVCEWqf zI33Rr(f;vKnc&PNy86m5D+o^>)gk|%N3FMG1l$^MXw`{@A(j+2T21Dboa*hGt5VSTtmI7i`ka$4hsMfv-u{Uw zvelY@%z2E87oL|h8%r2~gOjHh;WtQ;o$r&qK_Z&OQk)sJ3 zzgX7f*zc#i)P-g!jYPFm%*&%0Yb#haN7eJk0}z3(q(d`nJv&o!W}H}^dip*U#6obvzUHo(;N(>8W~D!Hs9s-;D)1t;Ta7k{PP@`J+}5Yj2%k- zPnfRcC3EgtZN5$TGd;Q>=1$c7cC*kXB-mi9h5SP{G;*B0u2_NO`GCKgt==S2N2}CH zz^r-eAn6<3QgENGIl&$_*)3*@-j`%KegaI6os&3xZ8)Q!b5mzg_)Nd*2bLw7S*(RB zNY_n?T|p#v;kW%;@U75Ca7ETat$y}|JCMu-#1IUx^O#U@dk^%%;Ucrdn1)fBt{m%X2)>m zyU*nR=gwM9C9N-tGsuRn_FZ$v*0B1hi878LX?P+xe$#v;okN;x1nwe zBzWXur=^|Eel6{|E|1UYM?z3;&5_GvH)g|9LZ`<+YvW@*#}7>lD|EklZ}wQ_xF4a* zY;QQ{efB2&1+M~2?e+y(vK(5`bbJitMTvFKO;L{}}3&y%ly6Uc5d@A=>rRK3&7TNIQE4p)`a;2*M+IZe7eK`?jRJ-iMb~$?_ zG6jKlrw=LwN`G@GS9*NHUWj-Dq32^EGwj;3nPWB>=#Z57aK4o~dU4^*k)I13eZ1lB zm2qaM`i-58 zEMd8$9U{;YKAHTcUKOcmW`&6!!UHSoG4L_ORAqI(g$`?YK7+{!r1;1iimV2NTk$m| zYeMbLxtAVxKpb{V6k8_VgDCZ?8YU^#N9*ZA4JN6lHHlnn%jSKof@|%VGD>b?jm8@8 zm8u+a^IKzwPv}qCmwkjn?e_dfRT+N@Nd#-dn`<45r%~q}@uJBn8>qNgiGopm`dz-)Q!P$Lvn5`?nOgEceMQl3utX0> zBMb$m~&mSE10e-A&KqTrqHoz1@$)UKmf$B7P9eT7ZQwx1^EDXCxxwL6qnE*S=*YdRvuM zGrer9KKgq|lciuKJ6HDAEovKqIXmqtD>`e6RYc9VAs@HOf9%8x;`&BVeFchPLig6(g1csQ?2{2G3HpM4Bl|x0W~lT$J9xCa z&4>+2Ofsvi8F=cY7Lq1M@E4l%l=OK5`ZaNZ|_27q$bEhkx29yLjo*7kEmmP^U zzw<5vKGzS}*w|BbX3}fZw~CFGx;UFmN|Lv$!Z6huu@6n=J$+cSZR}yud)g;+FLua$&Il5%|e?vOvAI;5ZQ*#tJOk9vb z18M77CMo476B4M{q4w_2ibN{l&SQ+Dx2k>Fm~dH46^TvRBTT3bTOobua6fv-1j3c| z1?xP7`)%{`sHc#lQk;GVvY8Z>F{9eET$@nKIEwc9=Jjc*G3q{)643!DD92J^=25(w6l}s@(fc%)Xtu74$LIB#=BTiEP`h0 zcs%MZ8z8AokKm~^2jBOPet)XX8G(Zv>ksS^AVhQ>sJ!a55BEkpk>yB0y|fC|@T(S_7Li4s|eZ@oo=7reecPiI>&St>78NeyFe-GZP@IhZ3a)4g zE&33a2BE*O+>prheu;fC-e2&MG2QzTnT^-#(d2$OQ$p|f?_#_4to>Nt19SC}U~V07 zr4sNR*)`<6Vhtm!PCc9*@dZj7@zj^#NtI^p`w7C|JH2E} z-vmtDz{FOgr}}1=nah38V!OSDJe_hvTMl=X=ZJ#OOYNgyQ7?~8a^@${^R(NBQYWx+ z*QjBh3C!78P3Q5fDlVU;lj@+}6mJalbwFNA%wT&>Wcli1^9c+2M$ z=THK^owpyDID6_tMuzuGshe8Y!D4D?AR$*-zTC8FznuoR#XBs1^%+o%nGjr%4*FB4EO- z!&@aowma(z$lUA8RX(IDzAzmbQDKsJm@MhiyEuECl*iR)t;~NgJ$yTQVfSDXedKXn z!^%{SKIX%sxtq?kQ3tE_;!aGK`$%&CbWI?v%enF(V~Lc5UkKrOj+OrScDQ)+mfh)z zM%b(zKkY>O@KJFhx<^A&@huh>R_ni==!q#m&F(tvYUk~K%jp3~yhxnDdFMO1G-k;r z+j-|nq1!Eh9OucRB^-CzUyC+U8hDYCH0v)HvQ&}q^%ZsAX9FU2K51KJA2&0&a%W$; zZJ07x_rs7_Hwr_6232O-kap_3wsbZiOk_({|BW`h3^-b(Zu4NC2SRH8G z;_OD$xmORrchq2`xSMla5e-8d0a5Xn|HiWn`)=MlCxAj;YDTKlGPaSGcZIU9ILxOZE1pZ6%FhUF%Jj4L(Gun&!Ykx-5@mwfZ|))MmqEG ziv?J^3Dp0bN<`>)4&TO+M;cT%UJSz9_gM_B{eJ0=jw`BRGa(Ugt9meY5I7h#D^=Vf|nw4sFGBRp*3^BU$6d;yOx#H8Exbu8hB&XoLN;5R6N2lsmWDcUHLjy>f{@BCcZRNFJFkM+2#`Pj(G)Pc6iJK_{^)kV9n&*4~$PQ8A&)}*$!#mY3)!8DZf zu&*zo#&&?ezudvoPV7dQ%Pzr)yGMpJU^fgfen)~@6=w+GSjs>v7iMGC&MR2Pl{PuV zN)9mF%k}4tye~Z6Wbv!r>!HYYImaihN97e4zgc?HMOq%+go2*^)e!i-Hehk+jSG%_ zn5K)KGH4B(U@8UgZ()8B14~c0OXIwuzJG$2uGXDkoMj?h8NZ^0E9$Bo;aE;ztPhO# z)6MW&JjO(_8O8PKn32ovKN|M0F2yKmgACBO{qt6aNi=%uZ+Tf9f%6^%-`|6&`mung z`o8Y1u;C-FQK0WFZ?|_BdG=rX5<7XT2c}`|20u8*e|wHGy3fgcJwS12cD)ax@5=@` zF)0Lt9!y7m`^JV!DeV7*u(nXn zh=NZa3EW~PgOOO4?~bkV0xZkFV_ec_oIYLFg00anUOd7j?7yOE77S?)n_3u;RDIE? zW@c>8N8E_VRr@SpJZ}wY{`Lnt-tAC(7Y`qT>zwU2VuAe4#nBkY7Ed44VleNsW()Oh zf$#INnRb)+wys;}BnW&uXglji3U@`rBpkbA!!<+8_9owS^TO0)uN+ zS@*TYdw1JYqxt#cxu^KgH&9=-9Soi~6}y6lrFV`P(es{IxW@QQa5xtTU%)=6&fPRB zu@jxm;{QCduUc}Bf5$IZCYVJM6^7>YRZavim|W^loJV5zWbx&(EcoQ~8!xog4BZ89 zT;Kiq%`#m$#OM9grIe7J8G@%UISd?`W_YR2Sif#gS10oHp856#+dd)mJ1gBb|1+K< zwZ_xH)STZ3Hwo0ecvJr|g1PZS zvp6*9&~nF>^v?N#&i+5|o$=N*%dTYVmCTlKRo!93pgxJZ$dT zkK3mua`cyKwLYJ|&t8f*u`LBsM!qOxhe_Y{V4lk23l-YH9_mFCo}9g*VXqu zEH2@49{Wxgp=;1qm$ItkzznPXoJCyncW*$UDs!C2X%+w_K3T2h_Hmg9U zsECslkRvWvRazyj*)>7Mpsg4Csvbv!u}dIvOMPm^@wzAcFR;&v?zwPk882$wynjhy zjdC3$C90)p(Twjv1T`X`WpnT{{|#abLPTHg-YOFSgg^I&}{gf!s=Tg#5%$%~1F$K$t3J zS;Zb>V4`br7r?#wwn3dL-(hLwj!f_I`HILnH?PbYE#!2Y-z|eehpoGNBXaz5dAl1_k<(#@phj>8$?NtcDpUpz+&*^~ z$chQ}dy%2>i2#NGtz3a~tn;pHll1G$?pW*ROpP~>yg!O`t&tsWz(Y zFSb1b&pIPi+Po#@S2#&;mB!bYv(@Y^0<4~`_K$(rt<`9)^7n9dq_Gr$zPorKF&y&5 z$Nw%N6Q}X$Bwy~blBXcySr>QEJV^7ZBS*u&cOFoNld%<7Rb7$B{AJ=RT#0IhU@xDO zidBb3rx+}j-<7=@-SAh$NL$y|Pru{4ww<&k-}85pW-`^3RhC%-&bC0)bb0PuVhIoTA=KHFfy56bUP*IE4M6}<@zqL zz# znYT;Y_OHu3f6rmx?+SYV%X{Y>Kk=Y57$rONHqx z&ubYC1;h)5v3z76-cMpOb|bbr3e+~)uBD>)HriwL8=-GWNkS#(^^2Xi2}#jJ)|2nG z!e>FMP{)1u$5}XQVyuQDWv+6VT~C>>rAjoCsTAg)w`DisDv>w>&mq!8KaA!^#?_m? zI30V-kql6jLyms?RyV9=l@gQTmD7ah3&!u0!oTVmx3bFAzdmU zC?FvWog<(y3^AmXv`UFemx!Wt58YjZfHVv-z#vEtHBx(V-`;!gXa523mv?<4W`66s zR-Ad9$9eL6wn1J2zexL3#~|k|L&uKHn^cl>&5lr+5mc?13w%*j1}k(j!E??0N=!w=ZLP|jKh7=>U_(@!JY`ugnB?CJ93kfmyg9f+3-tX3 z3;b>f<{@H}_zr-B9*l~B%C4>S&Ndf~MYoZ&v5Pq=n(c`wH12ACr2PJD9(!c$q_X%^ zr_Rg8ZDX2ADV$1NtmfscEBWe3!P0TPDBWiLS>OvDHfh%{M!Q?Ut4pZ_p@PhNfrN(+ z3(w?ETY0BfQ2{Ap7eFr}o~I;*JoVz1!nB7X>K=@9#twfq5VcQiPMs&!s zT`tiQ(npWEs(ndrg7i2?@ z{cNC)J^E#u9I_xT;=SNSJKCQrJv<%W`{)o`>}cYd8r1dcAu!q1{ZeM!e(GB`Xv2qg zexU`vaSJ+2#S2G|L6s{L>bYoQKZLXB`beHCUZbL(X&BBz+pHMpeenEPxh(@Mqz7AG z`gb?gAGL`Mn?Jle_5Qg0`%gw9pY> z7qb(-IxdF1HDvfDMzF|qDtjqu#qo_GNV-gph|vD(TP3@~(EHB(IhXv&`Q zwr1uHsj%ZRY}#kmk5SZyIzHdiKm8)oO7w8D<^qqwl(%I6iBxOWg?taOUUuH}C3LtI zZ6z{3_qX7UElrjqZN4ao|6-07&)KUdT!d9eyg;io z#uk>c#43Z87Ljw8TqNn_?ITr8f6J#Z8?886lVXm?t^?t9|LkZ}>F}+ErgoxnE_a7O zbTd?oN;F^@SYzP;{s`!PHtvDMgT`7#*Dtm6&CGV+VSjKZMiuWv+QHZ%>GQxJ!u9Jbu{@(%nMy9m44l0l{0_xY*1@)Mr6Ez2QZD{u~Hs zf>&i#l_h3kKjxEi=B44D8n;feO|Ec}VisTY1w@9nV2(QhZ|T*Jr%m3mT|e}dpP1#p zjNmt+N)v1#EUG`PnSgnp?2U18akavp*$8(oQE%2Cup3uC54z!L7QBHKS2pyLS{5)5 zlsq$iQ;TMcq2cg|^pGiPA0J z7P9eA_6T}b6PaE;PZO@-@*cZpkAC^VV()-3_2%NV_XH*n?&c@2r*=}F%62YThdD;{ zTa%Q1$$Tu9{_#KuYj&zcl6UkO71rKgrclyri2!vMc}?#IV_v8)rAlLc`{E5OLaz@* zjD>e{moGjb#ro$9E>0u084YEyFL0(=$MlMAMPiP1km^Y^r64@8V#3(8^esYgs(;_4 zOj`UJWZQ*Sa3Hv`lic>in}dPD&R7F*6~7khh?K0Xa583S4U-E7j06|iWIdF>UY&31 zQ7rbtJeihpy#x31`abc+I9KnE901@Qu2;_XohU!C1DbZ$+F`jwP{@*}lehfo*U*u% z&pkL9df2>vUheBuUMVrhzEwqMpBr(mlB^CK@$jgE!C4YWrwP(4E zX!-qceI_X<^^580NqpKi%UQRmWHb(6Wf?3sKW_bJYI3{l((_+C)W1ugRy?~Vqvv3Q z#>&;GJ9s|K1N?m@uT%d>SwyoyEPS_Bo-&PPsZy84#x=8IJNG!Yq`3QLUu{UvM9IR} zf~nSxvz|){BSv9z;?Li`;Ctp(>T>{RjWoJkY$Kn4z0YH0A=W6j6^6y^BUOrX@45%` zlBhkZwJfXO?TeU}Pz&(+JOj}T^Nl4C$jlTLe*D^{fh2%F^stkS#8f>%0C62?IdNB<+ON1oBQcfr$B2zJca5ctg8h zLmZC|VF?QaleV4bG9~op(ETe;E^Rg#7Q37wjS{`qO@6LgJFc%9DoLNwkA9%*+g{sQ zJ4kNoZH)JqhYhy1Le2Mqq{w=V23)C-Z!<{wT>D>kkg7HDSkHjCG$F|;Yp zysgCg*&_!_ccNHyRE0P&GhBSLrc!6sE)@N6m@^%!aE|I0wqhB2grR6WGTs#loQd6H z&43{k>G#=V@Ri4*c2kOxK@;V=Z@O~s@bZ#@G)GG(M*s|2>hWu+y*!tjn|r=<_V(O1 zHq2_TXK4jpM^^ZJmNE8L1auQ!Z&>A=nG;rXc6ubTe=r*x*>cHYhzL^RTD$8Dy*=RCZrl z7v2Y34n4Iji5kWy_1a68os67~y~iQOtqr^G@%01{#4f?51q^PlEJSE9mWo`1I(G|4 zHnL1?)Gl~>?z8gEuu4ohq#-V2mVd%{`y5F;O_pm9tcb6>Jefg>-%DaHuG${iWS&Z~ zt3k}=6Bbuf1PPR6J4#5E`3CE|9iv6IaD+e4vrQN6r+aE0#su|vET|YN?O#oy?gX9| zL@Xrp399IQeXRE6Nyl#EZA_HpY}4%zW7en0yVu_GK$ls7aAp`YMNr!RbVhxM5pqp_ zdi^$@*~H+?fu}RKe41+cIJgR0@RlpgWjdFa)0NkS}2 zz_uhr6Z$sm@jb?U&t3lCi{ysksJV<`8OxU7Q`inToB=a{S-0gCS1;1^T z@IT8xBjqt>rVo~dzp@EUjKS6Rp+yH^1{Kw8Be&OI)hY+xfF@nB;t=7Pk{X_wGyZZj zUvy-8%BX+&*c2(nhsx7keox}uDnO)g_Vp?O2 z;1I&#Y~tWq=$?1&#MrfLuEIK^@I|{o6i2`*9iTK7AfaZDyrmwWxNjp!^2?=P-|NpL z_sVPo1uEZ!g-L~rhL*u;Qg_xn;3E3ZsuusW$CY_2`odrS#9`DN(dqI&$*UT%bq|21 z^*Iy&$aQA9(J2k>w+^M9_ab)rA`ILfaf&eo)5BY$fL*2d>KZD$-g#|8UUMm45#nA_ z6QOU8*Hms^_`V{^lj8XGtfTKBS~Nlnoo2(rH)WWCvV9XAK+M9CGU9P6MO*0gozjQ% zJ(li{?nR&%#d|pn1v>i^Qcv6g-5XSEh@j7~oD8unBwE%o?%yRj`N8c6{%A*Lw>pa> zEb5RRw1K;;@0N5;fM_k%#8Th>In_k&>neTQ%s|95xNI999}*=teMP8kD3pI(fw^(8 zI>5-2K#9jxN_C_3Jt@e&{X})G%1Ym1uNVy|s~a*w*?>!;=5yR~5= zRR%XhSj5&T2d2Kpc!jvOHNl#*zuJ}%Dv5<5$Rz~jmtUb6nzq+-HpAHyu18<%0OBt! zbMnWl(MMq}!ISc@8~R^nT9l<|EM(D6Yi%xXQ_pK8g64k#Q^oEOb9AvtJh0>vFhuXA&g zym=FDXT;6DuDTm9;01bvXp;Y4D{6!z9bK(Ln#sh%Y!pBQ*D=fV-jyqnMzs=&_5vyT zwx<~%(tbW0pGrttmFrcM!(opFOUJZa7$lwZAQ;L@--zOPUV$EK439cUe#XRSgw)A9`Y#pHJSxzfmkEY`bi1 zy1Okgjc=9ENUr#yr|Rm#YDd$s)5CX&8&K4I*Na$gA%k%GpE|M1c&tU=Pzp=DQu*>1 zVO5ryid=xVzUhyps|WZT75$y-#IBs_7`h((VM{d!HoE`XkL@S|mS7nR!_KomL6Qyl zjZN~oXw^&DtbguW!)UiWLBWTyjFB1s3zl20ZwneUedZ(I8(~L_&o@lf*!-P=NZ+yR zFX{;-zHp|#x%{G7q>t@n9%JLS(W@0ECt4IEBo94CQj;KLd4#<>CA*&1RdbD`4ea0q< zxBt1{Fg|X03?jWNzVj+oHDhdvrQFTU9to3HH}QG z2hsQ%a=%97aPgGNEMNRi)t6r4s-qqH6`%W#ZuVC~hvFP+?|)Ha|8nn1+rT!}(lMS; zra{CKs*NRIJG8La>W~a`t2^87zYU`_he43rh(-#x4Np+@l z5h)B-77I-%z@#Qp%KF#iSW`3VzveZ=9Np7{+o!4t;^^QLm&sK-WU!w1s*RV88DSBc z)9~flq`4or1tusL$L)J(3+il5dFP|}#;XyxK_N(BM!+f4d8f}LTFDnfH?O%i)a$F$ z-D{m35q6&Y!2N7}wy_baU~;?d!338}1qc|uK%o@S#Ke|)d( z532fRd+S1V*rCFk)QxLhZ!QAI!dr!+@X+792`ln>s(0D@4e%>;(;DZ*l*wUf&niac z`+Z0q(_p%pH`rf{2&uQzN0~_yWC)y2>IE&i`$nfyO0Hz&TiFVy_DUkwY*$ELwJa_=(84u{S&MaWo2tV$X* z#PFhUG&It2$ECKc3dV9W>K}&-AFEFf9me+tb!ob1$--@}4^4)1I|?a}vHVG*%m?^VF&tLPCo(WK>He~% z4QqmYUz#k#@HZ_|mpFpJV1_)H zRKDBiRa`*R+jOG5HN-s;{$uf3*oc3 z=RuXdSX?A9r^OB&C(G~1xUIZOPq27R;4Ybo7-oL`+>?*WSfvlv^i@4!q5F2m-4qB@ z5BMO>68YCpFDkCCAgq)q7())HzVw%BVrUWe~l)^`~jEejF1I*9&x>*)fS;Bv~s_>pEvURPCTWsc7a z?=+c(E_V|z95|~SGs}s33s3sG5EuT*p*BxDA+T-lYej$bL)Robx%b*y!TmH!TiRw?P%|FVL-rrWZw^9Tak)XleyrUu#4t0{Fvde|-J+ ztraO?NF34fmSn#84{;EPAik#s6$Cs`%Tko0P5Wj%^-U)WFwwJCdgY;%-r^vtR?w~JRa z949+C*+>h)~NSc9Ag6>4Ar)X-yK`Z11!j2)vu${XHmr7EdhS zI2}}}aCVvNVWe`K=k{N_jZF@M#Z97#JR5;21`B*_X@mu}ouItz~N`h_ZGLmzRz zk4kJ?_X=pn9@?y1fT*h=q+Q+<&E=iF1X12e7jZbf+e=Is$4CE0tEQgb&0Fbu82se) zCI9nY?$&Hc8O4OG;yaba1&A2jf_)5*)1iNZ()M(+Mm|L&v0|!PU|g3B)$6ktbpN~Y zXVLSdIKXYGWR}0R4>L$T+L0C;_u1J@5Oplr8>_R1){WwsK2nLs2+4{eQSD8Q;noax z+)Gy~mv)ZvwK5KI9n33@;^_Ozo1>fV738*DoHby0)4og_X!$jy0}PEnPo$CB^b?s)a?94ch6eR)rJqseVg&mG)GfJ# zB%@2H&779|{xQyXnwJBt&b%1jT_MUlsV_zaT-?%UL3~(ileWC{T{#v$px52P zo%+ud$gN4VnXO)-V1Q@@knSrwCEw%yU21i&m9PJy!BO5B!Jbg4JK7Ka0}D7v~&asH^EW^IwY!^L9DyV?g2#>pSv$RG1WFOPAZ1%Lb} zcH5<6E!?RcJwKfjM(1MsIP*HNmE4b||MZm`l zdiP8DR_;h{j`kh5N-ao78A_3D3LVQ0i`&MTh1)xBX&i+|%S7U=cn(|g=Mx)jJbsXM zrdobAYjw4g!OpOrr{j#RRg@2hKF&`e9jA&xlWTtSx^dX%;!&-~x+n+Koi#6?Y>M>9 z^<1gX%;haA2?zH;;k^z>%YFo1BKV`{M#nT5yH2*RX=n51BjA+GT`qZi%f2K&$Ce=_ zW)r{`*3-h%q!k>KHZ$G<{-_Q0sLWYBu`-ud(IK5zEjN%z<_%4NK(u3;P zK|F@#7biVeVZ3O@d=S}dF?Axzo-UVpx%<5D7-Q1rXdF6`a=;}pb23dr$@~cl;j_UAezD5hB?Y_;Y&=O^9{q{Via+~C(tMyVkZ5V?6-bEOU>>r zPn4-}Du?6-lV^uXiCW0aNeph*HJq;+DR93dq#1?v^vG-U-B)fsU8nhkZZAgtTAyJI z!QuCXPGU=-6*(`-Yxn&QwiC{RB8|8#&9-^@1r;ovCAW#o=2})2rc>3`j*zXVd-t!G za_5t0w4hH&X~fp~zG(O`SUB=VWH3}Ung9r}Q=#-oo(YRM7kQ>msI#fx!SHkU!4cHc zat%7RR^8JCa<=j49`9F=-n>zBFO+m~QSFTv=s)-j?Tr3z(b!O(1`7*zIgNd{76c#hjmb?o}R>GbA1*XCx{ussAQ=4^7 zGLJ#95mPTHl<9(R6&h7mKHk2?M^pjITdb$6ToUiTxEjxI6a=Ub*~wyj4cR)6N>u>R zGyg}fUd~nHN_Z3?*Xz~uPX{<6S7W;7mnKHDehv9VNb1@}5)4yu}yilTl#39o<2`MWXw{@D-`nTP6c{<36`n0se3)0wad_{Jec>cuRjVb3lP$&NU?E!0p z9FoLhuB#4XPHpd{hqrq<0&Ym(nlY7}b%*PeQOJl#wiu;3DMxILd{3@oEJ+JXimFsR zJdciQ`3k&y;TQ`59HR9X4Z-v^GK<@PItQU2UAdM=bCO{1++hB=6hVawVDP2X zbE3?1rQHnX^!`979gBHApDL6ni!NLCC1AZ1LQB&fx&Db-gEhpvWaH|^0E(sb&8@_o zo1iLaCO|$={@Wu))wI0I&L2;-(&?wvtJ|zfa1TC~Ez@@hhzZn@rZPlMbQg?T({!^` zg~nO^_^cAq_W;1uQZvNY#<--VC(6r6T1Ov;!BgEKCDtlG3(cnLwoe4jYAg>nW^6N+ zjdy)NnjErI(F;a!8c-qlegzdv_6MD;aosyMHeBBfbZ>^D_#BGN#BCIR|8gQiIS`5^ z^h?r?pq#NS1&5TQaZXiq@EhY|iWh9_H+>(=w8$u2EU%k5dW9QG!%&kYILAn8D0L`0 zwb&1mLt6Q!r{sK-2C#JiC7*9pMlye7E$p#NdidhW-62>nOl_&+ra5WYhdKqnmu4}g zQ`w&_m2cX6u7z97zPy%)d0!&%_0lP;;>1Od#i_TwkEKw17_4idDbO;SYO5xw8=RSU z-qA`29uvtlY@+FXR!%H^akIRtdZL>Kf;x{7^UBJuuQE-~-oS$UnR`a~{YW0V`7vz@ z98T*Y(lo3fjJ((Q?2K)=4Cm+Ost4XCW!$RcHU4x7y|E)_tS2{ByR_T7zgST#Y1z{8 zB9TdKj2| zLR=`mtd4yTX_;ck^1~$apid?Aa?E?ntsknWBo)VuxLf7BnTXLa%^n2DC0|;bq_z^T zJ9Z|A>B{{UIcO2oW3@79aH+Bv5NBe-q)V8XwiYt8zw|c+-sRJ&M5JdBvZ~GzJEt}?(9?$jW7`s4=gr-;*fIR&%T0tV-^6ziuCaZZ z>$J~qSErdS$28b`s`A)ghWn)Ul1l2gI5%O+J1^j{CZr|uQW@bnpSp;?GsUjq8y-$o z0O##`w7~HL-y%svgLh)wpO&@y^df7w6WKM-pb!&7AJeicfT%M;WV^-c@?15)r2lx! z&ixj`q~dCvPQf!9od0>Co7RYS-h7Rcf&L@^qP`GoXuB+AF7R?Nm7{P!oFx7AYt|0? zg7v9NC}<{^DB;L#+m~p?yW&e{8OUfV@)}CVfc+$5X|2{i6%jV2Rza35VW1#rmm#va zpi3y0w-IU2Q?hKQr)CHmxQ*y+FMuwxU-Iy#VVX=)t994gG_6n8g62}2`lEbi`I z7*cgpG3-rwl`U`OeRlnWiZ!dK!lspN?u}fL7C~?JOG85$@paTzPtBE&mq*5D7U0(e zEqeKz3@hyEtfA2UI(bOhwm@+~!l5bSXOS-$ckA)4P^vn?$VVH9(R(}p@;^PvpM zqk87FB;FLtOv`V&N#yjzqa-p0R?C7!5IU|? z6rWCSeV_ir`?S5YM;0Dq^Oc#X9gz1x*M3`QyAL|I{nk|33&UEQM1*ULTFThi{UKfCp4 zN^iyWGVO27IHX6sX5}DTR905LIbfA?Q}UJTAd!hOX~lXByh2ErMK>dTpUf7X7QP(E zoMje=a5k@ia7RAfy2bh4v$!TI&O+96qb=kzt%g)*ZZ+URPIT^-B#MgQkP0Y#^nsiE zOT;Cub|!b08@B{z^n$k$RTqQKmelRSbSXMK)?bIx(MJd8{8~;tbb+LcjPugaSV=_h zh!|x;a+O73GxXtQtD`N^Gd?<%aI<0Ko>8r^P+-ioL$K4idb}|ql;kuyLM4cZQM@?}lu%aB!)Ac-^eXhvAN1McN}&e5l+0L&3= zkS=!m>%AvnYrxo{3^Sk@WHc-piVU0vmBSiSJbZ(UO(pgy1C`DmQ4&kvUwy@SZruxN zTIdK}y4?Au=4%MqDdmau)x1xb?UE2z1z(DWZIN+>-cHBS{G`jX;94<8zL|JCS+SNF zgQwTp!sItV54)tD8dhb)ynN-5seg=pR2CP3)dZFW3_LyG6r(Q)sdR_9z?{;=9pZCX zF(d|I&J;+-=Z-TqBYH{O{&LH`FTzYHs(m|~g|A@7EUP-192-_8kmWlb{(^RsC22?y zg5#!G)Q}DX9H8^etrD{ulE@FGWT=1=LXJ)Y`A)<_^_B~ODS-g@zpvglPhL_5`ku4p z{Q@~T-txpm#;4vLU&$!yAw}kngyP5$R}^cEQB=o-GmLu4kEu>X4eH#1G$45y#Ud%u z%+e}>jv=QrM#5h3?lU5{*Tl4;w^)M}^()>iYW{Qb&!=&HrSC{FA$2>NfQd*9QZM2Q zb!S#Ykx7NYD0cfw!wO6^4?E_f#ePW*M1xx9J19x?n86G;CmvvMK?Te|Bi8iGCG&qD z8QdmN;!6A9f4Wuv_dH;x*#GgB|K9TdPhW|Z6I4)OKQF63qx-vdAG88f)!2~$w{l(+ z2)HYhKpCnCVp(I8>)+GI=~~M3j<&mXVPWCi55}DW`%DFppr@e8hdl4jakf=!rW(FoZqnc!U5Vxh}~*yvM@0*p=q>%%?u<#hpdc?)HgT?jG|-zzWO1+K)erc z@9czvI!d(8#(8Uq7drnfbv{_6E|*HjDT&ScJ}HyGx9nyk_!4I)on(HYY4wn755J%w z%17(p=lbWd-^YM1FGTHc>2T3cB0;rn80>>tqksJYuq)1o+9{A#H>sf&#&9Uzbi9B` z-G5Jg8QkQX)Dh9q`{-Wz>EfE_gPZ`aN=C=)wfWz&S%78Ri3PedQ!SPgJ@}@%zc3R_ z{r`Rdly@7(FR`UDp063Y_c7gnJ9)n9fN)593R$1k_hk3M<-ezDI1soAzBeU#e_o}f ztv?WT82WM7H)kgs{AAB-JX3u(s-F*MQ<{TDSMRKb z-o$_W81gOsB^i)r9iQ$8ZyjwmLIITpS~U=G2G4;+c1M~g`VFWI#PskLwH@PeN`hKj z+W{0ZgX(lttWvK)3KFb0NJeG>h{}Iw3`|XRqnPE^N{@uk)FcU{YNkkt z-+yXsoa`BciHLJKm_|_hpW^K{=?wrhN*hG7aHoKYLHJqMl~ngpBW^Dc-yYB~;VY@w z1KBx|`!fKR9tkNhz5%dQ)N)%FK-$iwEms^A&pI`pNT7Xjnw#;d7;ibigSj$McAH+% zbYg5s@9lDquO3v^QTDRw>uLCD?*#QWvimL4nmi~nhXmjV`?y%Nig@b|b-iW~j1TRt!b)QDp z`_!A5QWP6DOFB;89Tu%cU{Oj==k6DaQ=L`r%&`k(`t0;TQSR&*XRFg5(0+Xr?6PD* zwy#29^CEbui1V8K@}1I!AGgPKNs+mr&BCzk)xScE*wu9?l&k>6FFo|uGgM1$`iz95O<}VYCm_ol@*dWo@)GSWqy%(@d430XeLLXetb* z@$}Cc2=t}pXh2hPHlqZ}4`u@zb4Dv>z?X_cU808ks6+g6zBa zA;Wj)4X8{{ZSEX3pG7PNWMyUbA1UO2$E5sS!>Vgt-H+NYgp<<;S;f&$3C55jA)=8` zn}kMiFOrHBEt_8P-%nG74Eh1+h%JPL==(V-2!L<3)_LQKty)RWb1p_LA`0x1*`+EH z!fuP5*-z3|+1NUA??O81fV*0Is|wJuW(Ay`F0YAw!udJ+rx%I4ff|4$V>`svNEZ@z z6L>IjXlC(9qSft^{=H|8xqpSVv>DI44RFynR@i0qxqbAYrU{E1hsGo!wa)Ank*^9(Dp9ho zC4Zu6%|k!x9Re#SI3Gr!RtD|b^Oo?rMZCZa6u+33R+mo-l@!@2ZgM) z;(6xvFXsmo&y-Un9P3OTK-KR|8BXl?Tp5@>uX!Vs6>tmjE z?Cbc$0jiY?Uf{gb@u8xz+(S**Bggpl4!cGn5Q0Aj z+b(FbVk; zx+KnKHEzvav0VKS9YMCkm8_TtD1Iml7L-u4yTMI?rmN4I3!DQ*R8EuHN)^NGj{viU z3xMd`EZQ+rxb&P3>u~`?Q|5m7D{yic8 zFerUvMOp9}6sCGEk|+S1?~<`!d;HI)rAre6E|w!EPvW`t@(s5WZA=xM80O9^7c3W0|ui;Ig& zR@1@M3W+(%(F8P82GwmhB%NakE8n@k308!x#PJ&eOUf@F)!Wsz75xCS5T4o>g%S4$ zkixQZV#NM5G)CTb(*FeLKuSVyg(~9Y-UN%`g50u)8NvA5^F6`Mj%zYk(*a2>R6nwCL7;*TI2&Xv^k}IH;sO3X|-8xX)?haVDlQxO$23$nK&$1^j({fwlcb5LAfgqi~VEw#ZVx&ph zxw%+3f<+;%fsyJAIDsQmYqcM z{=44z^mFA)SQ&dR81xE=AxUfn=TaoeE?s)zDk;*=HIK){1c2@HfYdwuvsR?(o)l1f zJ6Hg&Y2(hG*J3}K|Hj0regqc02lTNl1)I!W)v`69nm%AIY#G9)kOI#`O})IlvYXx? zU?>{!IILYVzT<8Cm_@*h+&7?WdTU3{wJ1*RgpU$ml_u+nax<&G;|Y9||FcHGw0$BI zrY~Sz4)zz?dpobp_3FOZ{8$_M~8-pHR zxBU<>1v1vkF(8POa*~qcifu9vg;K%7( z>)^IZ(1lR4NZiHY2{ZUwrNR=}WZbsk(!Wy?D3Mvob8(e4@zQwX`rled3#m*v(ltn?lQ2JBf{*5r3%U}}j4M2}dU(G9o&OF#Ro7%y*6?Vd1+ zk7=s&XOX+GAD;p}7n6bU3+$zJw(4=~NszDymL;%46P=@Rvq1u*a|pk)lY?{nf>w`Y z0V-C$TlD@2NHPt&|GWf$;3a?+vzn=K?;R3dZ52Le4hbhj*0`@F@2f#oYnrk&*!CzJ=S;O~s)*&uFFs-~_k#$r)zB*D*50ko#*|Muq3o&fjh?@$xe z?T+}re)%t)#L4+S;{SEm|4LfUfBf?Q^ZoxXzEVhV%5jKHHaJy{+r0qBBb6u0g%2!) F{uctL%I*LF diff --git a/docs/_build/html/_sources/basics.rst.txt b/docs/_build/html/_sources/basics.rst.txt deleted file mode 100644 index 7402b68db..000000000 --- a/docs/_build/html/_sources/basics.rst.txt +++ /dev/null @@ -1,214 +0,0 @@ -Basics -====== - -Initialization --------------- - -Before use Warp should be explicitly initialized with the ``wp.init()`` method as follows:: - - import warp as wp - - wp.init() - -Warp will print some startup information about the compute devices available, driver versions, and the location -for any generated kernel code, e.g.: - -.. code:: bat - - Warp 1.0.0 initialized: - CUDA Toolkit: 11.8, Driver: 12.1 - Devices: - "cpu" | AMD64 Family 25 Model 33 Stepping 0, AuthenticAMD - "cuda:0" | NVIDIA GeForce RTX 4080 (sm_89) - Kernel cache: C:\Users\mmacklin\AppData\Local\NVIDIA Corporation\warp\Cache\1.0.0 - - -Kernels -------- - -In Warp, compute kernels are defined as Python functions and annotated with the ``@wp.kernel`` decorator, as follows:: - - @wp.kernel - def simple_kernel(a: wp.array(dtype=wp.vec3), - b: wp.array(dtype=wp.vec3), - c: wp.array(dtype=float)): - - # get thread index - tid = wp.tid() - - # load two vec3s - x = a[tid] - y = b[tid] - - # compute the dot product between vectors - r = wp.dot(x, y) - - # write result back to memory - c[tid] = r - -Because Warp kernels are compiled to native C++/CUDA code, all the function input arguments must be statically typed. This allows -Warp to generate fast code that executes at essentially native speeds. Because kernels may be run on either the CPU -or GPU, they cannot access arbitrary global state from the Python environment. Instead they must read and write data -through their input parameters such as arrays. - -Warp kernels functions have a 1:1 correspondence with CUDA kernels, to launch a kernel with 1024 threads, we use -:func:`wp.launch() ` as follows:: - - wp.launch(kernel=simple_kernel, # kernel to launch - dim=1024, # number of threads - inputs=[a, b, c], # parameters - device="cuda") # execution device - -Inside the kernel we can retrieve the *thread index* of the each thread using the ``wp.tid()`` builtin function:: - - # get thread index - i = wp.tid() - -Kernels can be launched with 1D, 2D, 3D, or 4D grids of threads, e.g.: to launch a 2D grid of threads to process a 1024x1024 image we could write:: - - wp.launch(kernel=compute_image, - dim=(1024, 1024), - inputs=[img], - device="cuda") - -Then, inside the kernel we can retrieve a 2D thread index as follows:: - - # get thread index - i, j = wp.tid() - - # write out a color value for each pixel - color[i, j] = wp.vec3(r, g, b) - -.. _example-cache-management: - -Example: Changing the kernel cache directory -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -The following example illustrates how the location for generated and compiled -kernel code can be changed before and after calling ``wp.init()``. - -.. code:: python - - import os - - import warp as wp - - example_dir = os.path.dirname(os.path.realpath(__file__)) - - # set default cache directory before wp.init() - wp.config.kernel_cache_dir = os.path.join(example_dir, "tmp", "warpcache1") - - wp.init() - - print("+++ Current cache directory: ", wp.config.kernel_cache_dir) - - # change cache directory after wp.init() - wp.build.init_kernel_cache(os.path.join(example_dir, "tmp", "warpcache2")) - - print("+++ Current cache directory: ", wp.config.kernel_cache_dir) - - # clear kernel cache (forces fresh kernel builds every time) - wp.build.clear_kernel_cache() - - - @wp.kernel - def basic(x: wp.array(dtype=float)): - tid = wp.tid() - x[tid] = float(tid) - - - device = "cpu" - n = 10 - x = wp.zeros(n, dtype=float, device=device) - - wp.launch(kernel=basic, dim=n, inputs=[x], device=device) - print(x.numpy()) - -Arrays ------- - -Memory allocations are exposed via the ``wp.array`` type. Arrays wrap an underlying memory allocation that may live in -either host (CPU), or device (GPU) memory. Arrays are strongly typed and store a linear sequence of built-in values -(``float,``, ``int``, ``vec3``, ``matrix33``, etc). - -Arrays can be allocated similar to PyTorch:: - - # allocate an uninitialized array of vec3s - v = wp.empty(shape=n, dtype=wp.vec3, device="cuda") - - # allocate a zero-initialized array of quaternions - q = wp.zeros(shape=n, dtype=wp.quat, device="cuda") - - # allocate and initialize an array from a NumPy array - # will be automatically transferred to the specified device - a = np.ones((10, 3), dtype=np.float32) - v = wp.from_numpy(a, dtype=wp.vec3, device="cuda") - -By default, Warp arrays that are initialized from external data (e.g.: NumPy, Lists, Tuples) will create a copy the data to new memory for the -device specified. However, it is possible for arrays to alias external memory using the ``copy=False`` parameter to the -array constructor provided the input is contiguous and on the same device. See the :doc:`/modules/interoperability` -section for more details on sharing memory with external frameworks. - -To read GPU array data back to CPU memory we can use the ``array.numpy()`` method:: - - # bring data from device back to host - view = device_array.numpy() - -This will automatically synchronize with the GPU to ensure that any outstanding work has finished, and will -copy the array back to CPU memory where it is passed to NumPy. Calling ``array.numpy()`` on a CPU array will return -a zero-copy NumPy view onto the Warp data. - -User Functions --------------- - -Users can write their own functions using the ``@wp.func`` decorator, for example:: - - @wp.func - def square(x: float): - return x*x - -User functions can be called freely from within kernels inside the same module and accept arrays as inputs. - -Compilation Model ------------------ - -Warp uses a Python->C++/CUDA compilation model that generates kernel code from Python function definitions. All kernels belonging to a Python module are runtime compiled into dynamic libraries and PTX, the result is then cached between application restarts for fast startup times. - -Note that compilation is triggered on the first kernel launch for that module. Any kernels registered in the module with ``@wp.kernel`` will be included in the shared library. - -.. image:: ./img/compiler_pipeline.png - - -Language Details ----------------- - -To support GPU computation and differentiability, there are some differences from the CPython runtime. - -Built-in Types -^^^^^^^^^^^^^^ - -Warp supports a number of built-in math types similar to high-level shading languages, for example ``vec2, vec3, vec4, mat22, mat33, mat44, quat, array``. All built-in types have value semantics so that expressions such as ``a = b`` generate a copy of the variable b rather than a reference. - -Strong Typing -^^^^^^^^^^^^^ - -Unlike Python, in Warp all variables must be typed. Types are inferred from source expressions and function signatures using the Python typing extensions. All kernel parameters must be annotated with the appropriate type, for example: :: - - @wp.kernel - def simple_kernel(a: wp.array(dtype=vec3), - b: wp.array(dtype=vec3), - c: float): - -Tuple initialization is not supported, instead variables should be explicitly typed: :: - - # invalid - a = (1.0, 2.0, 3.0) - - # valid - a = wp.vec3(1.0, 2.0, 3.0) - - -Limitations and Unsupported Features -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -See :doc:`limitations` for a list of Warp limitations and unsupported features. diff --git a/docs/_build/html/_sources/configuration.rst.txt b/docs/_build/html/_sources/configuration.rst.txt deleted file mode 100644 index a19f228aa..000000000 --- a/docs/_build/html/_sources/configuration.rst.txt +++ /dev/null @@ -1,138 +0,0 @@ -Runtime Settings -================ - -Warp has settings at the global, module, and kernel level that can be used to fine-tune the compilation and verbosity -of Warp programs. In cases in which a setting can be changed at multiple levels (e.g ``enable_backward``), -the setting at the more-specific scope takes precedence. - -Global Settings ---------------- - -To change a setting, prepend ``wp.config.`` to the name of the variable and assign a value to it. -Some settings may be changed on the fly, while others need to be set prior to calling ``wp.init()`` to take effect. - -For example, the location of the user kernel cache can be changed with: - -.. code-block:: python - - import os - - import warp as wp - - example_dir = os.path.dirname(os.path.realpath(__file__)) - - # set default cache directory before wp.init() - wp.config.kernel_cache_dir = os.path.join(example_dir, "tmp", "warpcache1") - - wp.init() - - -Basic Global Settings -^^^^^^^^^^^^^^^^^^^^^ - -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -| Field | Type |Default Value| Description | -+====================+=========+=============+==========================================================================+ -|``verify_fp`` | Boolean | ``False`` | If ``True``, Warp will check that inputs and outputs are finite before | -| | | | and/or after various operations. **Has performance implications.** | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``verify_cuda`` | Boolean | ``False`` | If ``True``, Warp will check for CUDA errors after every launch and | -| | | | memory operation. CUDA error verification cannot be used during graph | -| | | | capture. **Has performance implications.** | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``print_launches`` | Boolean | ``False`` | If ``True``, Warp will print details of every kernel launch to standard | -| | | | out (e.g. launch dimensions, inputs, outputs, device, etc.). | -| | | | **Has performance implications.** | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``mode`` | String |``"release"``| Controls whether to compile Warp kernels in debug or release mode. | -| | | | Valid choices are ``"release"`` or ``"debug"``. | -| | | | **Has performance implications.** | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``verbose`` | Boolean | ``False`` | If ``True``, additional information will be printed to standard out | -| | | | during code generation, compilation, etc. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``quiet`` | Boolean | ``False`` | If ``True``, Warp module initialization messages will be disabled. | -| | | | This setting does not affect error messages and warnings. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``kernel_cache_dir``| String | ``None`` | The path to the directory used for the user kernel cache. Subdirectories | -| | | | named ``gen`` and ``bin`` will be created in this directory. If ``None``,| -| | | | a directory will be automatically determined using | -| | | | `appdirs.user_cache_directory `_ | -| | | | | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``enable_backward`` | Boolean | ``True`` | If ``True``, backward passes of kernels will be compiled by default. | -| | | | Disabling this setting can reduce kernel compilation times. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ - -Advanced Global Settings -^^^^^^^^^^^^^^^^^^^^^^^^ - -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -| Field | Type |Default Value| Description | -+====================+=========+=============+==========================================================================+ -|``cache_kernels`` | Boolean | ``True`` | If ``True``, kernels that have already been compiled from previous | -| | | | application launches will not be recompiled. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``cuda_output`` | String | ``None`` | The preferred CUDA output format for kernels. Valid choices are ``None``,| -| | | | ``"ptx"``, and ``"cubin"``. If ``None``, a format will be determined | -| | | | automatically. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``ptx_target_arch`` | Integer | 70 | The target architecture for PTX generation. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``llvm_cuda`` | Boolean | ``False`` | If ``True``, Clang/LLVM will be used to compile CUDA code instead of | -| | | | NVTRC. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ - -Module Settings ---------------- - -Module-level settings to control runtime compilation and code generation may be changed by passing a dictionary of -option pairs to ``wp.set_module_options()``. - -For example, compilation of backward passes for the kernel in an entire module can be disabled with: - -.. code:: python - - wp.set_module_options({"enable_backward": False}) - -The options for a module can also be queried using ``wp.get_module_options()``. - -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -| Field | Type |Default Value| Description | -+====================+=========+=============+==========================================================================+ -|``mode`` | String | Global | Controls whether to compile the module's kernels in debug or release | -| | | setting | mode by default. Valid choices are ``"release"`` or ``"debug"``. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``max_unroll`` | Integer | 16 | The maximum fixed-size loop to unroll. Note that ``max_unroll`` does not | -| | | | consider the total number of iterations in nested loops. This can result | -| | | | in a large amount of automatically generated code if each nested loop is | -| | | | below the ``max_unroll`` threshold. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``enable_backward`` | Boolean | Global | If ``True``, backward passes of kernels will be compiled by default. | -| | | setting | Valid choices are ``"release"`` or ``"debug"``. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``fast_math`` | Boolean | ``False`` | If ``True``, CUDA kernels will be compiled with the ``--use_fast_math`` | -| | | | compiler option, which enables some fast math operations that are faster | -| | | | but less accurate. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ -|``cuda_output`` | String | ``None`` | The preferred CUDA output format for kernels. Valid choices are ``None``,| -| | | | ``"ptx"``, and ``"cubin"``. If ``None``, a format will be determined | -| | | | automatically. The module-level setting takes precedence over the global | -| | | | setting. | -+--------------------+---------+-------------+--------------------------------------------------------------------------+ - -Kernel Settings ---------------- - -``enable_backward`` is currently the only setting that can also be configured on a per-kernel level. -Backward-pass compilation can be disabled by passing an argument into the ``@wp.kernel`` decorator -as in the following example: - -.. code-block:: python - - @wp.kernel(enable_backward=False) - def scale_2( - x: wp.array(dtype=float), - y: wp.array(dtype=float), - ): - y[0] = x[0] ** 2.0 diff --git a/docs/_build/html/_sources/debugging.rst.txt b/docs/_build/html/_sources/debugging.rst.txt deleted file mode 100644 index c006bd226..000000000 --- a/docs/_build/html/_sources/debugging.rst.txt +++ /dev/null @@ -1,86 +0,0 @@ -Debugging -========= - -Printing Values ---------------- - -Often one of the best debugging methods is to simply print values from kernels. Warp supports printing all built-in -types using the ``print()`` function, e.g.:: - - v = wp.vec3(1.0, 2.0, 3.0) - - print(v) - -In addition, formatted C-style printing is available through the ``wp.printf()`` function, e.g.:: - - x = 1.0 - i = 2 - - wp.printf("A float value %f, an int value: %d", x, i) - -.. note:: Formatted printing is only available for scalar types (e.g.: ``int`` and ``float``) not vector types. - -Printing Launches ------------------ - -For complex applications it can be difficult to understand the order-of-operations that lead to a bug. To help diagnose -these issues Warp supports a simple option to print out all launches and arguments to the console:: - - wp.config.print_launches = True - - -Step-Through Debugging ----------------------- - -It is possible to attach IDE debuggers such as Visual Studio to Warp processes to step through generated kernel code. -Users should first compile the kernels in debug mode by setting:: - - wp.config.mode = "debug" - -This setting ensures that line numbers, and debug symbols are generated correctly. After launching the Python process, -the debugger should be attached, and a breakpoint inserted into the generated code. - -.. note:: Generated kernel code is not a 1:1 correspondence with the original Python code, but individual operations can still be replayed and variables inspected. - -Also see :github:`warp/tests/test_debug.py` for an example of how to debug Warp kernel code running on the CPU. - -Generated Code --------------- - -The generated code for kernels is stored in a central cache location in the user's home directory, the cache location -is printed at startup when ``wp.init()`` is called, for example: - -.. code-block:: console - - Warp 0.8.1 initialized: - CUDA Toolkit: 11.8, Driver: 11.8 - Devices: - "cpu" | AMD64 Family 25 Model 33 Stepping 0, AuthenticAMD - "cuda:0" | NVIDIA GeForce RTX 3090 (sm_86) - "cuda:1" | NVIDIA GeForce RTX 2080 Ti (sm_75) - Kernel cache: C:\Users\LukasW\AppData\Local\NVIDIA Corporation\warp\Cache\0.8.1 - -The kernel cache has ``gen`` and ``bin`` folders that contain the generated C++/CUDA code and the compiled binaries -respectively. Occasionally it can be useful to inspect the generated code for debugging / profiling. - -Bounds Checking ---------------- - -Warp will perform bounds checking in debug build configurations to ensure that all array accesses lie within the defined -shape. - -CUDA Verification ------------------ - -It is possible to generate out-of-bounds memory access violations through poorly formed kernel code or inputs. In this -case the CUDA runtime will detect the violation and put the CUDA context into an error state. Subsequent kernel launches -may silently fail which can lead to hard to diagnose issues. - -If a CUDA error is suspected a simple verification method is to enable:: - - wp.config.verify_cuda = True - -This setting will check the CUDA context after every operation to ensure that it is still valid. If an error is -encountered it will raise an exception that often helps to narrow down the problematic kernel. - -.. note:: Verifying CUDA state at each launch requires synchronizing CPU and GPU which has a significant overhead. Users should ensure this setting is only used during debugging. diff --git a/docs/_build/html/_sources/faq.rst.txt b/docs/_build/html/_sources/faq.rst.txt deleted file mode 100644 index bcb924c51..000000000 --- a/docs/_build/html/_sources/faq.rst.txt +++ /dev/null @@ -1,112 +0,0 @@ -FAQ -=== - -How does Warp relate to other Python projects for GPU programming, e.g.: Numba, Taichi, cuPy, PyTorch, etc.? ------------------------------------------------------------------------------------------------------------- - -Warp is inspired by many of these projects, and is closely related to -Numba and Taichi which both expose kernel programming to Python. These -frameworks map to traditional GPU programming models, so many of the -high-level concepts are similar, however there are some functionality -and implementation differences. - -Compared to Numba, Warp supports a smaller subset of Python, but -offering auto-differentiation of kernel programs, which is useful for -machine learning. Compared to Taichi Warp uses C++/CUDA as an -intermediate representation, which makes it convenient to implement and -expose low-level routines. In addition, we are building in -data structures to support geometry processing (meshes, sparse volumes, -point clouds, USD data) as first-class citizens that are not exposed in -other runtimes. - -Warp does not offer a full tensor-based programming model like PyTorch -and JAX, but is designed to work well with these frameworks through data -sharing mechanisms like ``__cuda_array_interface__``. For computations -that map well to tensors (e.g.: neural-network inference) it makes sense -to use these existing tools. For problems with a lot of e.g.: sparsity, -conditional logic, heterogenous workloads (like the ones we often find in -simulation and graphics), then the kernel-based programming model like -the one in Warp are often more convenient since users have control over -individual threads. - -Does Warp support all of the Python language? ---------------------------------------------- - -No, Warp supports a subset of Python that maps well to the GPU. Our goal -is to not have any performance cliffs so that users can expect -consistently good behavior from kernels that is close to native code. -Examples of unsupported concepts that don’t map well to the GPU are -dynamic types, list comprehensions, exceptions, garbage collection, etc. - -When should I call ``wp.synchronize()``? ----------------------------------------- - -One of the common sources of confusion for new users is when calls to -``wp.synchronize()`` are necessary. The answer is “almost never”! -Synchronization is quite expensive, and should generally be avoided -unless necessary. Warp naturally takes care of synchronization between -operations (e.g.: kernel launches, device memory copies). - -For example, the following requires no manual synchronization, as the -conversion to NumPy will automatically synchronize: - -.. code:: python - - # run some kernels - wp.launch(kernel_1, dim, [array_x, array_y], device="cuda") - wp.launch(kernel_2, dim, [array_y, array_z], device="cuda") - - # bring data back to host (and implicitly synchronize) - x = array_z.numpy() - -The *only* case where manual synchronization is needed is when copies -are being performed back to CPU asynchronously, e.g.: - -.. code:: python - - # copy data back to cpu from gpu, all copies will happen asynchronously to Python - wp.copy(cpu_array_1, gpu_array_1) - wp.copy(cpu_array_2, gpu_array_2) - wp.copy(cpu_array_3, gpu_array_3) - - # ensure that the copies have finished - wp.synchronize() - - # return a numpy wrapper around the cpu arrays, note there is no implicit synchronization here - a1 = cpu_array_1.numpy() - a2 = cpu_array_2.numpy() - a3 = cpu_array_3.numpy() - -What happens when you differentiate a function like ``wp.abs(x)``? ------------------------------------------------------------------- - -Non-smooth functions such as ``y=|x|`` do not have a single unique -gradient at ``x=0``, rather they have what is known as a -``subgradient``, which is formally the convex hull of directional -derivatives at that point. The way that Warp (and most -auto-differentiation frameworks) handles these points is to pick an -arbitrary gradient from this set, e.g.: for ``wp.abs()``, it will -arbitrarily choose the gradient to be 1.0 at the origin. You can find -the implementation for these functions in ``warp/native/builtin.h``. - -Most optimizers (particularly ones that exploit stochasticity), are not -sensitive to the choice of which gradient to use from the subgradient, -although there are exceptions. - -Does Warp support multi-GPU programming? ----------------------------------------- - -Yes! Since version ``0.4.0`` we support allocating, launching, and -copying between multiple GPUs in a single process. We follow the naming -conventions of PyTorch and use aliases such as ``cuda:0``, ``cuda:1``, -``cpu`` to identify individual devices. - -Should I switch to Warp over IsaacGym / PhysX? ----------------------------------------------- - -Warp is not a replacement for IsaacGym, IsaacSim, or PhysX - while Warp -does offer some physical simulation capabilities this is primarily aimed -at developers who need differentiable physics, rather than a fully -featured physics engine. Warp is also integrated with IsaacGym and is -great for performing auxiliary tasks such as reward and observation -computations for reinforcement learning. diff --git a/docs/_build/html/_sources/index.rst.txt b/docs/_build/html/_sources/index.rst.txt deleted file mode 100644 index 1c7c8f690..000000000 --- a/docs/_build/html/_sources/index.rst.txt +++ /dev/null @@ -1,192 +0,0 @@ -NVIDIA Warp Documentation -========================= - -Warp is a Python framework for writing high-performance simulation and graphics code. Warp takes -regular Python functions and JIT compiles them to efficient kernel code that can run on the CPU or GPU. - -Warp is designed for spatial computing and comes with a rich set of primitives that make it easy to write -programs for physics simulation, perception, robotics, and geometry processing. In addition, Warp kernels -are differentiable and can be used as part of machine-learning pipelines with frameworks such as PyTorch and JAX. - -Below are some examples of simulations implemented using Warp: - -.. image:: ./img/header.png - -Quickstart -========== - -The easiest way is to install Warp is from PyPi: - -.. code-block:: sh - - $ pip install warp-lang - -Pre-built binary packages for Windows, Linux and macOS are also available on the `Releases `__ page. To install in your local Python environment extract the archive and run the following command from the root directory: - -.. code-block:: sh - - $ pip install . - -Basic example -------------- - -An example first program that computes the lengths of random 3D vectors is given below:: - - import warp as wp - import numpy as np - - wp.init() - - num_points = 1024 - - @wp.kernel - def length(points: wp.array(dtype=wp.vec3), - lengths: wp.array(dtype=float)): - - # thread index - tid = wp.tid() - - # compute distance of each point from origin - lengths[tid] = wp.length(points[tid]) - - - # allocate an array of 3d points - points = wp.array(np.random.rand(num_points, 3), dtype=wp.vec3) - lengths = wp.zeros(num_points, dtype=float) - - # launch kernel - wp.launch(kernel=length, - dim=len(points), - inputs=[points, lengths]) - - print(lengths) - -Additional examples -------------------- -The `examples `__ directory in -the Github repository contains a number of scripts that show how to -implement different simulation methods using the Warp API. Most examples -will generate USD files containing time-sampled animations in the -``examples/outputs`` directory. Before running examples users should -ensure that the ``usd-core`` package is installed using: - -:: - - pip install usd-core - -USD files can be viewed or rendered inside NVIDIA -`Omniverse `__, -Pixar's UsdView, and Blender. Note that Preview in macOS is not -recommended as it has limited support for time-sampled animations. - -Built-in unit tests can be run from the command-line as follows: - -:: - - python -m warp.tests - -Omniverse ---------- - -A Warp Omniverse extension is available in the extension registry inside -Omniverse Kit or USD Composer. - -Enabling the extension will automatically install and initialize the -Warp Python module inside the Kit Python environment. Please see the -`Omniverse Warp Documentation `__ -for more details on how to use Warp in Omniverse. - - -Learn More ----------- - -Please see the following resources for additional background on Warp: - -- `GTC 2022 - Presentation `__ -- `GTC 2021 - Presentation `__ -- `SIGGRAPH Asia 2021 Differentiable Simulation - Course `__ - -The underlying technology in Warp has been used in a number of research -projects at NVIDIA including the following publications: - -- Accelerated Policy Learning with Parallel Differentiable Simulation - - Xu, J., Makoviychuk, V., Narang, Y., Ramos, F., Matusik, W., Garg, - A., & Macklin, M. - `(2022) `__ -- DiSECt: Differentiable Simulator for Robotic Cutting - Heiden, E., - Macklin, M., Narang, Y., Fox, D., Garg, A., & Ramos, F - `(2021) `__ -- gradSim: Differentiable Simulation for System Identification and - Visuomotor Control - Murthy, J. Krishna, Miles Macklin, Florian - Golemo, Vikram Voleti, Linda Petrini, Martin Weiss, Breandan - Considine et - al. `(2021) `__ - -Citing ------- - -If you use Warp in your research please use the following citation: - -.. code:: bibtex - - @misc{warp2022, - title= {Warp: A High-performance Python Framework for GPU Simulation and Graphics}, - author = {Miles Macklin}, - month = {March}, - year = {2022}, - note= {NVIDIA GPU Technology Conference (GTC)}, - howpublished = {\url{https://github.com/nvidia/warp}} - } - -License -------- - -Warp is provided under the NVIDIA Source Code License (NVSCL), please see -`LICENSE.md `_ for the full license text. - -Please contact `omniverse-license-questions@nvidia.com `_ for -commercial licensing inquires. - -Full Table of Contents ----------------------- - -.. toctree:: - :maxdepth: 2 - :caption: User's Guide - - installation - basics - modules/devices - modules/interoperability - configuration - debugging - limitations - faq - -.. toctree:: - :maxdepth: 2 - :caption: Core Reference - - modules/runtime - modules/functions - -.. toctree:: - :maxdepth: 2 - :caption: Simulation Reference - - modules/sim - modules/sparse - modules/fem - -.. toctree:: - :hidden: - :caption: Project Links - - GitHub - PyPI - Discord - -:ref:`Full Index ` diff --git a/docs/_build/html/_sources/installation.rst.txt b/docs/_build/html/_sources/installation.rst.txt deleted file mode 100644 index 2d166887f..000000000 --- a/docs/_build/html/_sources/installation.rst.txt +++ /dev/null @@ -1,93 +0,0 @@ -Installation -============ - -The easiest way is to install Warp is from `PyPi `_: - -.. code-block:: sh - - $ pip install warp-lang - -Pre-built binary packages for Windows, Linux and macOS are also available on the `Releases `__ page. To install in your local Python environment extract the archive and run the following command from the root directory: - -.. code-block:: sh - - $ pip install . - -Dependencies ------------- - -Warp supports Python versions 3.7 or later and requires `NumPy `_ to be installed. - -The following optional dependencies are required to support certain features: - -* `usd-core `_: Required for some Warp examples, ``warp.sim.parse_usd()``, and ``warp.render.UsdRenderer``. -* `JAX `_: Required for JAX interoperability (see :ref:`jax-interop`). -* `PyTorch `_: Required for PyTorch interoperability (see :ref:`pytorch-interop`). -* `NVTX for Python `_: Required to use :class:`wp.ScopedTimer(use_nvtx=True) `. - -Building the Warp documentation requires: - -* `Sphinx `_ -* `Furo `_ -* `Sphinx-copybutton `_ - -Building from source --------------------- - -For developers who want to build the library themselves the following tools are required: - -* Microsoft Visual Studio (Windows), minimum version 2019 -* GCC (Linux), minimum version 7.2 -* `CUDA Toolkit `_, minimum version 11.5 -* `Git Large File Storage `_ - -If you are cloning from Windows, please first ensure that you have -enabled “Developer Mode” in Windows settings and symlinks in Git: - -.. code-block:: console - - $ git config --global core.symlinks true - -This will ensure symlinks inside ``exts/omni.warp.core`` work upon cloning. - -After cloning the repository, users should run: - -.. code-block:: console - - $ python build_lib.py - -This will generate the ``warp.dll`` / ``warp.so`` core library -respectively. When building manually, users should ensure that their -``CUDA_PATH`` environment variable is set, otherwise Warp will be built -without CUDA support. Alternatively, the path to the CUDA Toolkit can be -passed to the build command as ``--cuda_path="..."``. After building, the -Warp package should be installed using: - -.. code-block:: console - - $ pip install -e . - -Which ensures that subsequent modifications to the library will be -reflected in the Python package. - -Conda environments ------------------- - -Some modules, such as ``usd-core``, don't support the latest Python version. -To manage running Warp and other projects on different Python versions one can -make use of an environment management system such as -`Conda `_. - -**WARNING:** When building and running Warp in a different environment, make sure -the build environment has the same C++ runtime library version, or an older -one, than the execution environment. Otherwise Warp's shared libraries may end -up looking for a newer runtime library version than the one available in the -execution environment. For example on Linux this error could occur: - -``OSError: <...>/libstdc++.so.6: version `GLIBCXX_3.4.30' not found (required by <...>/warp/warp/bin/warp.so)`` - -This can be solved by installing a newer C++ runtime version in the runtime -conda environment using ``conda install -c conda-forge libstdcxx-ng=12.1`` or -newer. Or, the build environment's C++ toolchain can be downgraded using -``conda install -c conda-forge libstdcxx-ng=8.5``. Or, one can ``activate`` or -``deactivate`` conda environments as needed for building vs. running Warp. diff --git a/docs/_build/html/_sources/limitations.rst.txt b/docs/_build/html/_sources/limitations.rst.txt deleted file mode 100644 index 5640103fc..000000000 --- a/docs/_build/html/_sources/limitations.rst.txt +++ /dev/null @@ -1,56 +0,0 @@ -Limitations -=========== - -.. currentmodule:: warp - -This section summarizes various limitations and currently unsupported features in Warp. -Requests for new features can be made at `GitHub Discussions `_, -and issues can be opened at `GitHub Issues `_. - -Unsupported Features --------------------- - -To achieve good performance on GPUs some dynamic language features are not supported: - -* Lambda functions -* List comprehensions -* Exceptions -* Recursion -* Runtime evaluation of expressions, e.g.: eval() -* Dynamic structures such as lists, sets, dictionaries, etc. - -Kernels -------- - -* Strings cannot be passed into kernels. -* Short-circuit evaluation is not supported. -* :func:`wp.atomic_add() ` does not support ``wp.int64``. -* :func:`wp.tid() ` cannot be called from user functions. -* CUDA thread blocks use a fixed size 256 threads per block. - -Arrays ------- - -* Arrays can have a maximum of four dimensions. -* Each dimension of a Warp array cannot be greater than the maximum value representable by a 32-bit signed integer, - :math:`2^{31}-1`. -* There are currently no data types that support complex numbers. - -Structs -------- - -* Structs cannot have generic members, i.e. of type ``typing.Any``. - -Volumes -------- - -* The sparse-volume *topology* cannot be changed after the tiles for the :class:`Volume` have been allocated. - -Multiple Processes ------------------- - -* A CUDA context created in the parent process cannot be used in a *forked* child process. - Use the spawn start method instead, or avoid creating CUDA contexts in the parent process. -* There can be issues with using same user kernel cache directory when running with multiple processes. - A workaround is to use a separate cache directory for every process. - See :ref:`example-cache-management` for how the cache directory may be changed. diff --git a/docs/_build/html/_sources/modules/devices.rst.txt b/docs/_build/html/_sources/modules/devices.rst.txt deleted file mode 100644 index eda532d6f..000000000 --- a/docs/_build/html/_sources/modules/devices.rst.txt +++ /dev/null @@ -1,200 +0,0 @@ -.. _devices: - -Devices -======= - -Warp assigns unique string aliases to all supported compute devices in the system. There is currently a single CPU device exposed as ``"cpu"``. Each CUDA-capable GPU gets an alias of the form ``"cuda:i"``, where ``i`` is the CUDA device ordinal. This convention should be familiar to users of other popular frameworks like PyTorch. - -It is possible to explicitly target a specific device with each Warp API call using the ``device`` argument:: - - a = wp.zeros(n, device="cpu") - wp.launch(kernel, dim=a.size, inputs=[a], device="cpu") - - b = wp.zeros(n, device="cuda:0") - wp.launch(kernel, dim=b.size, inputs=[b], device="cuda:0") - - c = wp.zeros(n, device="cuda:1") - wp.launch(kernel, dim=c.size, inputs=[c], device="cuda:1") - -.. note:: - - A Warp CUDA device (``"cuda:i"``) corresponds to the primary CUDA context of device ``i``. This is compatible with frameworks like PyTorch and other software that uses the CUDA Runtime API. It makes interoperability easy, because GPU resources like memory can be shared with Warp. - -Default Device --------------- - -To simplify writing code, Warp has the concept of **default device**. When the ``device`` argument is omitted from a Warp API call, the default device will be used. - -During Warp initialization, the default device is set to be ``"cuda:0"`` if CUDA is available. Otherwise, the default device is ``"cpu"``. - -The function ``wp.set_device()`` can be used to change the default device:: - - wp.set_device("cpu") - a = wp.zeros(n) - wp.launch(kernel, dim=a.size, inputs=[a]) - - wp.set_device("cuda:0") - b = wp.zeros(n) - wp.launch(kernel, dim=b.size, inputs=[b]) - - wp.set_device("cuda:1") - c = wp.zeros(n) - wp.launch(kernel, dim=c.size, inputs=[c]) - -.. note:: - - For CUDA devices, ``wp.set_device()`` does two things: it sets the Warp default device and it makes the device's CUDA context current. This helps to minimize the number of CUDA context switches in blocks of code targeting a single device. - -For PyTorch users, this function is similar to ``torch.cuda.set_device()``. It is still possible to specify a different device in individual API calls, like in this snippet:: - - # set default device - wp.set_device("cuda:0") - - # use default device - a = wp.zeros(n) - - # use explicit devices - b = wp.empty(n, device="cpu") - c = wp.empty(n, device="cuda:1") - - # use default device - wp.launch(kernel, dim=a.size, inputs=[a]) - - wp.copy(b, a) - wp.copy(c, a) - -Scoped Devices --------------- - -Another way to manage the default device is using ``wp.ScopedDevice`` objects. They can be arbitrarily nested and restore the previous default device on exit:: - - with wp.ScopedDevice("cpu"): - # alloc and launch on "cpu" - a = wp.zeros(n) - wp.launch(kernel, dim=a.size, inputs=[a]) - - with wp.ScopedDevice("cuda:0"): - # alloc on "cuda:0" - b = wp.zeros(n) - - with wp.ScopedDevice("cuda:1"): - # alloc and launch on "cuda:1" - c = wp.zeros(n) - wp.launch(kernel, dim=c.size, inputs=[c]) - - # launch on "cuda:0" - wp.launch(kernel, dim=b.size, inputs=[b]) - -.. note:: - - For CUDA devices, ``wp.ScopedDevice`` makes the device's CUDA context current and restores the previous CUDA context on exit. This is handy when running Warp scripts as part of a bigger pipeline, because it avoids any side effects of changing the CUDA context in the enclosed code. - -Example: Using ``wp.ScopedDevice`` with multiple GPUs -~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ - -The following example shows how to allocate arrays and launch kernels on all available CUDA devices. - -.. code:: python - - import warp as wp - - wp.init() - - - @wp.kernel - def inc(a: wp.array(dtype=float)): - tid = wp.tid() - a[tid] = a[tid] + 1.0 - - - # get all CUDA devices - devices = wp.get_cuda_devices() - device_count = len(devices) - - # number of launches - iters = 1000 - - # list of arrays, one per device - arrs = [] - - # loop over all devices - for device in devices: - # use a ScopedDevice to set the target device - with wp.ScopedDevice(device): - # allocate array - a = wp.zeros(250 * 1024 * 1024, dtype=float) - arrs.append(a) - - # launch kernels - for _ in range(iters): - wp.launch(inc, dim=a.size, inputs=[a]) - - # synchronize all devices - wp.synchronize() - - # print results - for i in range(device_count): - print(f"{arrs[i].device} -> {arrs[i].numpy()}") - - -Current CUDA Device -------------------- - -Warp uses the device alias ``"cuda"`` to target the current CUDA device. This allows external code to manage the CUDA device on which to execute Warp scripts. It is analogous to the PyTorch ``"cuda"`` device, which should be familiar to Torch users and simplify interoperation. - -In this snippet, we use PyTorch to manage the current CUDA device and invoke a Warp kernel on that device:: - - def example_function(): - # create a Torch tensor on the current CUDA device - t = torch.arange(10, dtype=torch.float32, device="cuda") - - a = wp.from_torch(t) - - # launch a Warp kernel on the current CUDA device - wp.launch(kernel, dim=a.size, inputs=[a], device="cuda") - - # use Torch to set the current CUDA device and run example_function() on that device - torch.cuda.set_device(0) - example_function() - - # use Torch to change the current CUDA device and re-run example_function() on that device - torch.cuda.set_device(1) - example_function() - -.. note:: - - Using the device alias ``"cuda"`` can be problematic if the code runs in an environment where another part of the code can unpredictably change the CUDA context. Using an explicit CUDA device like ``"cuda:i"`` is recommended to avoid such issues. - -Device Synchronization ----------------------- - -CUDA kernel launches and memory operations can execute asynchronously. This allows for overlapping compute and memory operations on different devices. Warp allows synchronizing the host with outstanding asynchronous operations on a specific device:: - - wp.synchronize_device("cuda:1") - -The ``wp.synchronize_device()`` function offers more fine-grained synchronization than ``wp.synchronize()``, as the latter waits for *all* devices to complete their work. - -Custom CUDA Contexts --------------------- - -Warp is designed to work with arbitrary CUDA contexts so it can easily integrate into different workflows. - -Applications built on the CUDA Runtime API target the *primary context* of each device. The Runtime API hides CUDA context management under the hood. In Warp, device ``"cuda:i"`` represents the primary context of device ``i``, which aligns with the CUDA Runtime API. - -Applications built on the CUDA Driver API work with CUDA contexts directly and can create custom CUDA contexts on any device. Custom CUDA contexts can be created with specific affinity or interop features that benefit the application. Warp can work with these CUDA contexts as well. - -The special device alias ``"cuda"`` can be used to target the current CUDA context, whether this is a primary or custom context. - -In addition, Warp allows registering new device aliases for custom CUDA contexts, so that they can be explicitly targeted by name. If the ``CUcontext`` pointer is available, it can be used to create a new device alias like this:: - - wp.map_cuda_device("foo", ctypes.c_void_p(context_ptr)) - -Alternatively, if the custom CUDA context was made current by the application, the pointer can be omitted:: - - wp.map_cuda_device("foo") - -In either case, mapping the custom CUDA context allows us to target the context directly using the assigned alias:: - - with wp.ScopedDevice("foo"): - a = wp.zeros(n) - wp.launch(kernel, dim=a.size, inputs=[a]) diff --git a/docs/_build/html/_sources/modules/fem.rst.txt b/docs/_build/html/_sources/modules/fem.rst.txt deleted file mode 100644 index 359e42df9..000000000 --- a/docs/_build/html/_sources/modules/fem.rst.txt +++ /dev/null @@ -1,386 +0,0 @@ -warp.fem -===================== - -.. currentmodule:: warp.fem - -The ``warp.fem`` module is designed to facilitate solving physical systems described as differential -equations. For example, it can solve PDEs for diffusion, convection, fluid flow, and elasticity problems -using finite-element-based (FEM) Galerkin methods, and allows users to quickly experiment with various FEM -formulations and discretization schemes. - -Integrands ----------- - -The core functionality of the FEM toolkit is the ability to integrate constant, linear, and bilinear forms -over various domains and using arbitrary interpolation basis. - -The main mechanism is the :py:func:`.integrand` decorator, for instance: :: - - @integrand - def linear_form( - s: Sample, - v: Field, - ): - return v(s) - - - @integrand - def diffusion_form(s: Sample, u: Field, v: Field, nu: float): - return nu * wp.dot( - grad(u, s), - grad(v, s), - ) - -Integrands are normal warp kernels, meaning any usual warp function can be used. -However, they accept a few special parameters: - - - :class:`.Sample` contains information about the current integration sample point, such as the element index and coordinates in element. - - :class:`.Field` designates an abstract field, which will be replaced at call time by the actual field type: for instance a :class:`.DiscreteField`, :class:`.field.TestField` or :class:`.field.TrialField` defined over an arbitrary :class:`.FunctionSpace`. - A field `u` can be evaluated at a given sample `s` using the :func:`.inner` operator, i.e, ``inner(u, s)``, or as a shortcut using the usual call operator, ``u(s)``. - Several other operators are available, such as :func:`.grad`; see the :ref:`Operators` section. - - :class:`.Domain` designates an abstract integration domain. Several operators are also provided for domains, for example in the example below evaluating the normal at the current sample position: :: - - @integrand - def boundary_form( - s: Sample, - domain: Domain, - u: Field, - ): - nor = normal(domain, s) - return wp.dot(u(s), nor) - -Integrands cannot be used directly with :func:`warp.launch`, but must be called through :func:`.integrate` or :func:`.interpolate` instead. -The root integrand (`integrand` argument passed to :func:`integrate` or :func:`interpolate` call) will automatically get passed :class:`.Sample` and :class:`.Domain` parameters. -:class:`.Field` parameters must be passed as a dictionary in the `fields` argument of the launcher function, and all other standard Warp types arguments must be -passed as a dictionary in the `values` argument of the launcher function, for instance: :: - - integrate(diffusion_form, fields={"u": trial, "v": test}, values={"nu": viscosity}) - - -Basic workflow --------------- - -The typical steps for solving a linear PDE are as follow: - - - Define a :class:`.Geometry` (grid, mesh, etc). At the moment, 2D and 3D regular grids, triangle, quadrilateral, tetrahedron and hexahedron meshes are supported. - - Define one or more :class:`.FunctionSpace`, by equipping the geometry elements with shape functions. See :func:`.make_polynomial_space`. At the moment, continuous/discontinuous Lagrange (:math:`P_{k[d]}, Q_{k[d]}`) and Serendipity (:math:`S_k`) shape functions of order :math:`k \leq 3` are supported. - - Define an integration :class:`.GeometryDomain`, for instance the geometry's cells (:class:`.Cells`) or boundary sides (:class:`.BoundarySides`). - - Integrate linear forms to build the system's right-hand-side. Define a test function over the function space using :func:`.make_test`, - a :class:`.Quadrature` formula (or let the module choose one based on the function space degree), and call :func:`.integrate` with the linear form integrand. - The result is a :class:`warp.array` containing the integration result for each of the function space degrees of freedom. - - Integrate bilinear forms to build the system's left-hand-side. Define a trial function over the function space using :func:`.make_trial`, - then call :func:`.integrate` with the bilinear form integrand. - The result is a :class:`warp.sparse.BsrMatrix` containing the integration result for each pair of test and trial function space degrees of freedom. - Note that the trial and test functions do not have to be defined over the same function space, so that Mixed FEM is supported. - - Solve the resulting linear system using the solver of your choice - - -The following excerpt from the introductory example ``examples/fem/example_diffusion.py`` outlines this procedure: :: - - # Grid geometry - geo = Grid2D(n=50, cell_size=2) - - # Domain and function spaces - domain = Cells(geometry=geo) - scalar_space = make_polynomial_space(geo, degree=3) - - # Right-hand-side (forcing term) - test = make_test(space=scalar_space, domain=domain) - rhs = integrate(linear_form, fields={"v": test}) - - # Weakly-imposed boundary conditions on Y sides - boundary = BoundarySides(geo) - bd_test = make_test(space=scalar_space, domain=boundary) - bd_trial = make_trial(space=scalar_space, domain=boundary) - bd_matrix = integrate(y_mass_form, fields={"u": bd_trial, "v": bd_test}) - - # Diffusion form - trial = make_trial(space=scalar_space, domain=domain) - matrix = integrate(diffusion_form, fields={"u": trial, "v": test}, values={"nu": viscosity}) - - # Assemble linear system (add diffusion and boundary condition matrices) - bsr_axpy(x=bd_matrix, y=matrix, alpha=boundary_strength, beta=1) - - # Solve linear system using Conjugate Gradient - x = wp.zeros_like(rhs) - bsr_cg(matrix, b=rhs, x=x) - - -.. note:: - The :func:`.integrate` function does not check that the passed integrands are actually linear or bilinear forms; it is up to the user to ensure that they are. - To solve non-linear PDEs, one can use an iterative procedure and pass the current value of the studied function :class:`.DiscreteField` argument to the integrand, on which - arbitrary operations are permitted. However, the result of the form must remain linear in the test and trial fields. - -Introductory examples ---------------------- - -``warp.fem`` ships with a list of examples in the ``examples/fem`` directory illustrating common model problems. - - - ``example_diffusion.py``: 2D diffusion with homogenous Neumann and Dirichlet boundary conditions - * ``example_diffusion_3d.py``: 3D variant of the diffusion problem - - ``example_convection_diffusion.py``: 2D convection-diffusion using semi-Lagrangian advection - * ``example_diffusion_dg0.py``: 2D convection-diffusion using finite-volume and upwind transport - * ``example_diffusion_dg.py``: 2D convection-diffusion using Discontinuous Galerkin with upwind transport and Symmetric Interior Penalty - - ``example_stokes.py``: 2D incompressible Stokes flow using mixed :math:`P_k/P_{k-1}` or :math:`Q_k/P_{(k-1)d}` elements - - ``example_navier_stokes.py``: 2D Navier-Stokes flow using mixed :math:`P_k/P_{k-1}` elements - - ``example_mixed_elasticity.py``: 2D linear elasticity using mixed continuous/discontinuous :math:`S_k/P_{(k-1)d}` elements - - -Advanced usages ---------------- - -High-order (curved) geometries -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -It is possible to convert any :class:`.Geometry` (grids and explicit meshes) into a curved, high-order variant by deforming them -with an arbitrary-order displacement field using the :meth:`~.DiscreteField.make_deformed_geometry` method. -The process looks as follow: :: - - # Define a base geometry - base_geo = fem.Grid3D(res=resolution) - - # Define a displacement field on the base geometry - deformation_space = fem.make_polynomial_space(base_geo, degree=deformation_degree, dtype=wp.vec3) - deformation_field = deformation_space.make_field() - - # Populate the field value by interpolating an expression - fem.interpolate(deformation_field_expr, dest=deformation_field) - - # Construct the deformed geometry from the displacement field - deform_geo = deformation_field.make_deformed_geometry() - - # Define new function spaces on the deformed geometry - scalar_space = fem.make_polynomial_space(deformed_geo, degree=scalar_space_degree) - -See also ``example_deformed_geometry.py`` for a complete example. - -Particle-based quadrature -^^^^^^^^^^^^^^^^^^^^^^^^^ - -The :class:`.PicQuadrature` provides a way to define Particle-In-Cell quadratures from a set or arbitrary particles, -which can be helpful to develop MPM-like methods. -The particles are automatically bucketed to the geometry cells when the quadrature is initialized. -This is illustrated by the ``example_stokes_transfer.py`` and ``example_apic_fluid.py`` examples. - -Partitioning -^^^^^^^^^^^^ - -The FEM toolkit makes it possible to perform integration on a subset of the domain elements, -possibly re-indexing degrees of freedom so that the linear system contains the local ones only. -This is useful for distributed computation (see ``examples/fem/example_diffusion_mgpu.py``), or simply to limit the simulation domain to a subset of active cells (see ``examples/fem/example_stokes_transfer.py``). - -A partition of the simulation geometry can be defined using subclasses of :class:`.GeometryPartition` -such as :class:`.LinearGeometryPartition` or :class:`.ExplicitGeometryPartition`. - -Function spaces can then be partitioned according to the geometry partition using :func:`.make_space_partition`. -The resulting :class:`.SpacePartition` object allows translating between space-wide and partition-wide node indices, -and differentiating interior, frontier and exterior nodes. - -Memory management -^^^^^^^^^^^^^^^^^ - -Several ``warp.fem`` functions require allocating temporary buffers to perform their computations. -If such functions are called many times in a tight loop, those many allocations and de-allocations may degrade performance. -To overcome this issue, a :class:`.cache.TemporaryStore` object may be created to persist and re-use temporary allocations across calls, -either globally using :func:`set_default_temporary_store` or at a per-function granularity using the corresponding argument. - -.. _Operators: - -Operators ---------- -.. autofunction:: position(domain: Domain, s: Sample) -.. autofunction:: normal(domain: Domain, s: Sample) -.. autofunction:: lookup(domain: Domain, x) -.. autofunction:: measure(domain: Domain, s: Sample) -.. autofunction:: measure_ratio(domain: Domain, s: Sample) -.. autofunction:: deformation_gradient(domain: Domain, s: Sample) - -.. autofunction:: degree(f: Field) -.. autofunction:: inner(f: Field, s: Sample) -.. autofunction:: outer(f: Field, s: Sample) -.. autofunction:: grad(f: Field, s: Sample) -.. autofunction:: grad_outer(f: Field, s: Sample) -.. autofunction:: div(f: Field, s: Sample) -.. autofunction:: div_outer(f: Field, s: Sample) -.. autofunction:: at_node(f: Field, s: Sample) - -.. autofunction:: D(f: Field, s: Sample) -.. autofunction:: curl(f: Field, s: Sample) -.. autofunction:: jump(f: Field, s: Sample) -.. autofunction:: average(f: Field, s: Sample) -.. autofunction:: grad_jump(f: Field, s: Sample) -.. autofunction:: grad_average(f: Field, s: Sample) - -.. autofunction:: warp.fem.operator.operator - -Integration ------------ - -.. autofunction:: integrate -.. autofunction:: interpolate - -.. autofunction:: integrand - -.. class:: Sample - - Per-sample point context for evaluating fields and related operators in integrands. - -.. autoclass:: Field - -.. autoclass:: Domain - -Geometry --------- - -.. autoclass:: Grid2D - :show-inheritance: - -.. autoclass:: Trimesh2D - :show-inheritance: - -.. autoclass:: Quadmesh2D - :show-inheritance: - -.. autoclass:: Grid3D - :show-inheritance: - -.. autoclass:: Tetmesh - :show-inheritance: - -.. autoclass:: Hexmesh - :show-inheritance: - -.. autoclass:: LinearGeometryPartition - -.. autoclass:: ExplicitGeometryPartition - -.. autoclass:: Cells - :show-inheritance: - -.. autoclass:: Sides - :show-inheritance: - -.. autoclass:: BoundarySides - :show-inheritance: - -.. autoclass:: FrontierSides - :show-inheritance: - -.. autoclass:: Polynomial - :members: - -.. autoclass:: RegularQuadrature - :show-inheritance: - -.. autoclass:: NodalQuadrature - :show-inheritance: - -.. autoclass:: PicQuadrature - :show-inheritance: - -Function Spaces ---------------- - -.. autofunction:: make_polynomial_space - -.. autofunction:: make_polynomial_basis_space - -.. autofunction:: make_collocated_function_space - -.. autofunction:: make_space_partition - -.. autofunction:: make_space_restriction - -.. autoclass:: ElementBasis - :members: - -.. autoclass:: SymmetricTensorMapper - :show-inheritance: - -.. autoclass:: SkewSymmetricTensorMapper - :show-inheritance: - -Fields ------- - -.. autofunction:: make_test - -.. autofunction:: make_trial - -.. autofunction:: make_restriction - -Boundary Conditions -------------------- - -.. autofunction:: normalize_dirichlet_projector - -.. autofunction:: project_linear_system - -Memory management ------------------ - -.. autofunction:: set_default_temporary_store - -.. autofunction:: borrow_temporary - -.. autofunction:: borrow_temporary_like - - -Interfaces ----------- - -Interface classes are not meant to be constructed directly, but can be derived from extend the built-in functionality. - -.. autoclass:: Geometry - :members: cell_count, side_count, boundary_side_count - -.. autoclass:: GeometryPartition - :members: cell_count, side_count, boundary_side_count, frontier_side_count - -.. autoclass:: GeometryDomain - :members: ElementKind, element_kind, dimension, element_count - -.. autoclass:: Quadrature - :members: domain, total_point_count - -.. autoclass:: FunctionSpace - :members: dtype, topology, geometry, dimension, degree, trace, make_field - -.. autoclass:: SpaceTopology - :members: dimension, geometry, node_count, element_node_indices, trace - -.. autoclass:: BasisSpace - :members: topology, geometry, shape, node_positions - -.. autoclass:: warp.fem.space.shape.ShapeFunction - -.. autoclass:: SpacePartition - :members: node_count, owned_node_count, interior_node_count, space_node_indices - -.. autoclass:: SpaceRestriction - :members: node_count - -.. autoclass:: DofMapper - -.. autoclass:: FieldLike - -.. autoclass:: DiscreteField - :show-inheritance: - :members: dof_values, trace, make_deformed_geometry - -.. autoclass:: warp.fem.field.FieldRestriction - -.. autoclass:: warp.fem.field.SpaceField - :show-inheritance: - -.. autoclass:: warp.fem.field.TestField - :show-inheritance: - -.. autoclass:: warp.fem.field.TrialField - :show-inheritance: - -.. autoclass:: TemporaryStore - :members: clear - -.. autoclass:: warp.fem.cache.Temporary - :members: array, detach, release \ No newline at end of file diff --git a/docs/_build/html/_sources/modules/functions.rst.txt b/docs/_build/html/_sources/modules/functions.rst.txt deleted file mode 100644 index 5fe56ada3..000000000 --- a/docs/_build/html/_sources/modules/functions.rst.txt +++ /dev/null @@ -1,1992 +0,0 @@ -.. - Autogenerated File - Do not edit. Run build_docs.py to generate. - -.. functions: -.. currentmodule:: warp - -Kernel Reference -================ - -Scalar Types ------------- -.. class:: int8 -.. class:: uint8 -.. class:: int16 -.. class:: uint16 -.. class:: int32 -.. class:: uint32 -.. class:: int64 -.. class:: uint64 -.. class:: float16 -.. class:: float32 -.. class:: float64 -.. class:: bool - - -Vector Types ------------- -.. class:: vec2b -.. class:: vec2ub -.. class:: vec2s -.. class:: vec2us -.. class:: vec2i -.. class:: vec2ui -.. class:: vec2l -.. class:: vec2ul -.. class:: vec2h -.. class:: vec2f -.. class:: vec2d -.. class:: vec3b -.. class:: vec3ub -.. class:: vec3s -.. class:: vec3us -.. class:: vec3i -.. class:: vec3ui -.. class:: vec3l -.. class:: vec3ul -.. class:: vec3h -.. class:: vec3f -.. class:: vec3d -.. class:: vec4b -.. class:: vec4ub -.. class:: vec4s -.. class:: vec4us -.. class:: vec4i -.. class:: vec4ui -.. class:: vec4l -.. class:: vec4ul -.. class:: vec4h -.. class:: vec4f -.. class:: vec4d -.. class:: mat22h -.. class:: mat22f -.. class:: mat22d -.. class:: mat33h -.. class:: mat33f -.. class:: mat33d -.. class:: mat44h -.. class:: mat44f -.. class:: mat44d -.. class:: quath -.. class:: quatf -.. class:: quatd -.. class:: transformh -.. class:: transformf -.. class:: transformd -.. class:: spatial_vectorh -.. class:: spatial_vectorf -.. class:: spatial_vectord -.. class:: spatial_matrixh -.. class:: spatial_matrixf -.. class:: spatial_matrixd - -Generic Types -------------- -.. class:: Int -.. class:: Float -.. class:: Scalar -.. class:: Vector -.. class:: Matrix -.. class:: Quaternion -.. class:: Transformation -.. class:: Array - - -Scalar Math ---------------- -.. function:: min(x: Scalar, y: Scalar) -> Scalar - - Return the minimum of two scalars. - - -.. function:: min(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - Return the element-wise minimum of two vectors. - - -.. function:: min(v: Vector[Any,Scalar]) -> Scalar - :noindex: - :nocontentsentry: - - Return the minimum element of a vector ``v``. - - -.. function:: max(x: Scalar, y: Scalar) -> Scalar - - Return the maximum of two scalars. - - -.. function:: max(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - Return the element-wise maximum of two vectors. - - -.. function:: max(v: Vector[Any,Scalar]) -> Scalar - :noindex: - :nocontentsentry: - - Return the maximum element of a vector ``v``. - - -.. function:: clamp(x: Scalar, a: Scalar, b: Scalar) -> Scalar - - Clamp the value of ``x`` to the range [a, b]. - - -.. function:: abs(x: Scalar) -> Scalar - - Return the absolute value of ``x``. - - -.. function:: sign(x: Scalar) -> Scalar - - Return -1 if ``x`` < 0, return 1 otherwise. - - -.. function:: step(x: Scalar) -> Scalar - - Return 1.0 if ``x`` < 0.0, return 0.0 otherwise. - - -.. function:: nonzero(x: Scalar) -> Scalar - - Return 1.0 if ``x`` is not equal to zero, return 0.0 otherwise. - - -.. function:: sin(x: Float) -> Float - - Return the sine of ``x`` in radians. - - -.. function:: cos(x: Float) -> Float - - Return the cosine of ``x`` in radians. - - -.. function:: acos(x: Float) -> Float - - Return arccos of ``x`` in radians. Inputs are automatically clamped to [-1.0, 1.0]. - - -.. function:: asin(x: Float) -> Float - - Return arcsin of ``x`` in radians. Inputs are automatically clamped to [-1.0, 1.0]. - - -.. function:: sqrt(x: Float) -> Float - - Return the square root of ``x``, where ``x`` is positive. - - -.. function:: cbrt(x: Float) -> Float - - Return the cube root of ``x``. - - -.. function:: tan(x: Float) -> Float - - Return the tangent of ``x`` in radians. - - -.. function:: atan(x: Float) -> Float - - Return the arctangent of ``x`` in radians. - - -.. function:: atan2(y: Float, x: Float) -> Float - - Return the 2-argument arctangent, atan2, of the point ``(x, y)`` in radians. - - -.. function:: sinh(x: Float) -> Float - - Return the sinh of ``x``. - - -.. function:: cosh(x: Float) -> Float - - Return the cosh of ``x``. - - -.. function:: tanh(x: Float) -> Float - - Return the tanh of ``x``. - - -.. function:: degrees(x: Float) -> Float - - Convert ``x`` from radians into degrees. - - -.. function:: radians(x: Float) -> Float - - Convert ``x`` from degrees into radians. - - -.. function:: log(x: Float) -> Float - - Return the natural logarithm (base-e) of ``x``, where ``x`` is positive. - - -.. function:: log2(x: Float) -> Float - - Return the binary logarithm (base-2) of ``x``, where ``x`` is positive. - - -.. function:: log10(x: Float) -> Float - - Return the common logarithm (base-10) of ``x``, where ``x`` is positive. - - -.. function:: exp(x: Float) -> Float - - Return the value of the exponential function :math:`e^x`. - - -.. function:: pow(x: Float, y: Float) -> Float - - Return the result of ``x`` raised to power of ``y``. - - -.. function:: round(x: Float) -> Float - - Return the nearest integer value to ``x``, rounding halfway cases away from zero. - This is the most intuitive form of rounding in the colloquial sense, but can be slower than other options like :func:`warp.rint()`. - Differs from :func:`numpy.round()`, which behaves the same way as :func:`numpy.rint()`. - - -.. function:: rint(x: Float) -> Float - - Return the nearest integer value to ``x``, rounding halfway cases to nearest even integer. - It is generally faster than :func:`warp.round()`. Equivalent to :func:`numpy.rint()`. - - -.. function:: trunc(x: Float) -> Float - - Return the nearest integer that is closer to zero than ``x``. - In other words, it discards the fractional part of ``x``. - It is similar to casting ``float(int(x))``, but preserves the negative sign when x is in the range [-0.0, -1.0). - Equivalent to :func:`numpy.trunc()` and :func:`numpy.fix()`. - - -.. function:: floor(x: Float) -> Float - - Return the largest integer that is less than or equal to ``x``. - - -.. function:: ceil(x: Float) -> Float - - Return the smallest integer that is greater than or equal to ``x``. - - -.. function:: frac(x: Float) -> Float - - Retrieve the fractional part of x. - In other words, it discards the integer part of x and is equivalent to ``x - trunc(x)``. - - - - -Vector Math ---------------- -.. function:: dot(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Scalar - - Compute the dot product between two vectors. - - -.. function:: dot(x: Quaternion[Float], y: Quaternion[Float]) -> Scalar - :noindex: - :nocontentsentry: - - Compute the dot product between two quaternions. - - -.. function:: ddot(x: Matrix[Any,Any,Scalar], y: Matrix[Any,Any,Scalar]) -> Scalar - - Compute the double dot product between two matrices. - - -.. function:: argmin(v: Vector[Any,Scalar]) -> uint32 - - Return the index of the minimum element of a vector ``v``. [1]_ - - -.. function:: argmax(v: Vector[Any,Scalar]) -> uint32 - - Return the index of the maximum element of a vector ``v``. [1]_ - - -.. function:: outer(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Matrix[Any,Any,Scalar] - - Compute the outer product ``x*y^T`` for two vectors. - - -.. function:: cross(x: Vector[3,Scalar], y: Vector[3,Scalar]) -> Vector[3,Scalar] - - Compute the cross product of two 3D vectors. - - -.. function:: skew(x: Vector[3,Scalar]) - - Compute the skew-symmetric 3x3 matrix for a 3D vector ``x``. - - -.. function:: length(x: Vector[Any,Float]) -> Scalar - - Compute the length of a vector ``x``. - - -.. function:: length(x: Quaternion[Float]) -> Scalar - :noindex: - :nocontentsentry: - - Compute the length of a quaternion ``x``. - - -.. function:: length_sq(x: Vector[Any,Scalar]) -> Scalar - - Compute the squared length of a 2D vector ``x``. - - -.. function:: length_sq(x: Quaternion[Scalar]) -> Scalar - :noindex: - :nocontentsentry: - - Compute the squared length of a quaternion ``x``. - - -.. function:: normalize(x: Vector[Any,Float]) -> Vector[Any,Scalar] - - Compute the normalized value of ``x``. If ``length(x)`` is 0 then the zero vector is returned. - - -.. function:: normalize(x: Quaternion[Float]) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - Compute the normalized value of ``x``. If ``length(x)`` is 0, then the zero quaternion is returned. - - -.. function:: transpose(m: Matrix[Any,Any,Scalar]) - - Return the transpose of the matrix ``m``. - - -.. function:: inverse(m: Matrix[2,2,Float]) -> Matrix[Any,Any,Float] - - Return the inverse of a 2x2 matrix ``m``. - - -.. function:: inverse(m: Matrix[3,3,Float]) -> Matrix[Any,Any,Float] - :noindex: - :nocontentsentry: - - Return the inverse of a 3x3 matrix ``m``. - - -.. function:: inverse(m: Matrix[4,4,Float]) -> Matrix[Any,Any,Float] - :noindex: - :nocontentsentry: - - Return the inverse of a 4x4 matrix ``m``. - - -.. function:: determinant(m: Matrix[2,2,Float]) -> Scalar - - Return the determinant of a 2x2 matrix ``m``. - - -.. function:: determinant(m: Matrix[3,3,Float]) -> Scalar - :noindex: - :nocontentsentry: - - Return the determinant of a 3x3 matrix ``m``. - - -.. function:: determinant(m: Matrix[4,4,Float]) -> Scalar - :noindex: - :nocontentsentry: - - Return the determinant of a 4x4 matrix ``m``. - - -.. function:: trace(m: Matrix[Any,Any,Scalar]) -> Scalar - - Return the trace of the matrix ``m``. - - -.. function:: diag(d: Vector[Any,Scalar]) -> Matrix[Any,Any,Scalar] - - Returns a matrix with the components of the vector ``d`` on the diagonal. - - -.. function:: get_diag(m: Matrix[Any,Any,Scalar]) -> Vector[Any,Scalar] - - Returns a vector containing the diagonal elements of the square matrix ``m``. - - -.. function:: cw_mul(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - - Component-wise multiplication of two 2D vectors. - - -.. function:: cw_mul(x: Matrix[Any,Any,Scalar], y: Matrix[Any,Any,Scalar]) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - Component-wise multiplication of two 2D vectors. - - -.. function:: cw_div(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - - Component-wise division of two 2D vectors. - - -.. function:: cw_div(x: Matrix[Any,Any,Scalar], y: Matrix[Any,Any,Scalar]) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - Component-wise division of two 2D vectors. - - -.. function:: vector(w: Vector[3,Float], v: Vector[3,Float]) - - Construct a 6D screw vector from two 3D vectors. - - -.. function:: vector(*arg_types: Scalar, length: int32, dtype: Scalar) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - Construct a vector of with given length and dtype. - - -.. function:: matrix(pos: Vector[3,Float], rot: Quaternion[Float], scale: Vector[3,Float]) -> Matrix[Any,Any,Float] - - Construct a 4x4 transformation matrix that applies the transformations as - Translation(pos)*Rotation(rot)*Scale(scale) when applied to column vectors, i.e.: y = (TRS)*x - - -.. function:: matrix(*arg_types: Scalar, shape: Tuple[int, int], dtype: Scalar) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - Construct a matrix. If the positional ``arg_types`` are not given, then matrix will be zero-initialized. - - -.. function:: identity(n: int32, dtype: Scalar) -> Matrix[Any,Any,Scalar] - - Create an identity matrix with shape=(n,n) with the type given by ``dtype``. - - -.. function:: svd3(A: Matrix[3,3,Float], U: Matrix[3,3,Float], sigma: Vector[3,Float], V: Matrix[3,3,Scalar]) -> None - - Compute the SVD of a 3x3 matrix ``A``. The singular values are returned in ``sigma``, - while the left and right basis vectors are returned in ``U`` and ``V``. - - -.. function:: qr3(A: Matrix[3,3,Float], Q: Matrix[3,3,Float], R: Matrix[3,3,Float]) -> None - - Compute the QR decomposition of a 3x3 matrix ``A``. The orthogonal matrix is returned in ``Q``, - while the upper triangular matrix is returned in ``R``. - - -.. function:: eig3(A: Matrix[3,3,Float], Q: Matrix[3,3,Float], d: Vector[3,Float]) -> None - - Compute the eigendecomposition of a 3x3 matrix ``A``. The eigenvectors are returned as the columns of ``Q``, - while the corresponding eigenvalues are returned in ``d``. - - - - -Other ---------------- -.. function:: lower_bound(arr: Array[Scalar], value: Scalar) -> int - - Search a sorted array ``arr`` for the closest element greater than or equal to ``value``. - - -.. function:: lower_bound(arr: Array[Scalar], arr_begin: int32, arr_end: int32, value: Scalar) -> int - :noindex: - :nocontentsentry: - - Search a sorted array ``arr`` in the range [arr_begin, arr_end) for the closest element greater than or equal to ``value``. - - - - -Quaternion Math ---------------- -.. function:: quaternion() -> Quaternion[Float] - - Construct a zero-initialized quaternion. Quaternions are laid out as - [ix, iy, iz, r], where ix, iy, iz are the imaginary part, and r the real part. - - -.. function:: quaternion(x: Float, y: Float, z: Float, w: Float) -> Quaternion[Float] - :noindex: - :nocontentsentry: - - Create a quaternion using the supplied components (type inferred from component type). - - -.. function:: quaternion(i: Vector[3,Float], r: Float) -> Quaternion[Float] - :noindex: - :nocontentsentry: - - Create a quaternion using the supplied vector/scalar (type inferred from scalar type). - - -.. function:: quaternion(q: Quaternion[Float]) - :noindex: - :nocontentsentry: - - Construct a quaternion of type dtype from another quaternion of a different dtype. - - -.. function:: quat_identity() -> quatf - - Construct an identity quaternion with zero imaginary part and real part of 1.0 - - -.. function:: quat_from_axis_angle(axis: Vector[3,Float], angle: Float) -> Quaternion[Scalar] - - Construct a quaternion representing a rotation of angle radians around the given axis. - - -.. function:: quat_to_axis_angle(q: Quaternion[Float], axis: Vector[3,Float], angle: Float) -> None - - Extract the rotation axis and angle radians a quaternion represents. - - -.. function:: quat_from_matrix(m: Matrix[3,3,Float]) -> Quaternion[Scalar] - - Construct a quaternion from a 3x3 matrix. - - -.. function:: quat_rpy(roll: Float, pitch: Float, yaw: Float) -> Quaternion[Scalar] - - Construct a quaternion representing a combined roll (z), pitch (x), yaw rotations (y) in radians. - - -.. function:: quat_inverse(q: Quaternion[Float]) -> Quaternion[Scalar] - - Compute quaternion conjugate. - - -.. function:: quat_rotate(q: Quaternion[Float], p: Vector[3,Float]) -> Vector[3,Scalar] - - Rotate a vector by a quaternion. - - -.. function:: quat_rotate_inv(q: Quaternion[Float], p: Vector[3,Float]) -> Vector[3,Scalar] - - Rotate a vector by the inverse of a quaternion. - - -.. function:: quat_slerp(q0: Quaternion[Float], q1: Quaternion[Float], t: Float) -> Quaternion[Scalar] - - Linearly interpolate between two quaternions. - - -.. function:: quat_to_matrix(q: Quaternion[Float]) -> Matrix[3,3,Scalar] - - Convert a quaternion to a 3x3 rotation matrix. - - - - -Transformations ---------------- -.. function:: transformation(p: Vector[3,Float], q: Quaternion[Float]) -> Transformation[Scalar] - - Construct a rigid-body transformation with translation part ``p`` and rotation ``q``. - - -.. function:: transform_identity() -> transformf - - Construct an identity transform with zero translation and identity rotation. - - -.. function:: transform_get_translation(t: Transformation[Float]) -> Vector[3,Scalar] - - Return the translational part of a transform ``t``. - - -.. function:: transform_get_rotation(t: Transformation[Float]) -> Quaternion[Scalar] - - Return the rotational part of a transform ``t``. - - -.. function:: transform_multiply(a: Transformation[Float], b: Transformation[Float]) -> Transformation[Scalar] - - Multiply two rigid body transformations together. - - -.. function:: transform_point(t: Transformation[Scalar], p: Vector[3,Scalar]) -> Vector[3,Scalar] - - Apply the transform to a point ``p`` treating the homogenous coordinate as w=1 (translation and rotation). - - -.. function:: transform_point(m: Matrix[4,4,Scalar], p: Vector[3,Scalar]) -> Vector[3,Scalar] - :noindex: - :nocontentsentry: - - Apply the transform to a point ``p`` treating the homogenous coordinate as w=1. - The transformation is applied treating ``p`` as a column vector, e.g.: ``y = M*p``. - Note this is in contrast to some libraries, notably USD, which applies transforms to row vectors, ``y^T = p^T*M^T``. - If the transform is coming from a library that uses row-vectors, then users should transpose the transformation - matrix before calling this method. - - -.. function:: transform_vector(t: Transformation[Scalar], v: Vector[3,Scalar]) -> Vector[3,Scalar] - - Apply the transform to a vector ``v`` treating the homogenous coordinate as w=0 (rotation only). - - -.. function:: transform_vector(m: Matrix[4,4,Scalar], v: Vector[3,Scalar]) -> Vector[3,Scalar] - :noindex: - :nocontentsentry: - - Apply the transform to a vector ``v`` treating the homogenous coordinate as w=0. - The transformation is applied treating ``v`` as a column vector, e.g.: ``y = M*v`` - note this is in contrast to some libraries, notably USD, which applies transforms to row vectors, ``y^T = v^T*M^T``. - If the transform is coming from a library that uses row-vectors, then users should transpose the transformation - matrix before calling this method. - - -.. function:: transform_inverse(t: Transformation[Float]) -> Transformation[Float] - - Compute the inverse of the transformation ``t``. - - - - -Spatial Math ---------------- -.. function:: spatial_adjoint(r: Matrix[3,3,Float], s: Matrix[3,3,Float]) -> Matrix[6,6,Scalar] - - Construct a 6x6 spatial inertial matrix from two 3x3 diagonal blocks. - - -.. function:: spatial_dot(a: Vector[6,Float], b: Vector[6,Float]) -> Scalar - - Compute the dot product of two 6D screw vectors. - - -.. function:: spatial_cross(a: Vector[6,Float], b: Vector[6,Float]) -> Vector[6,Float] - - Compute the cross product of two 6D screw vectors. - - -.. function:: spatial_cross_dual(a: Vector[6,Float], b: Vector[6,Float]) -> Vector[6,Float] - - Compute the dual cross product of two 6D screw vectors. - - -.. function:: spatial_top(a: Vector[6,Float]) - - Return the top (first) part of a 6D screw vector. - - -.. function:: spatial_bottom(a: Vector[6,Float]) - - Return the bottom (second) part of a 6D screw vector. - - -.. function:: spatial_jacobian(S: Array[Vector[6,Float]], joint_parents: Array[int32], joint_qd_start: Array[int32], joint_start: int32, joint_count: int32, J_start: int32, J_out: Array[Float]) -> None - - -.. function:: spatial_mass(I_s: Array[Matrix[6,6,Float]], joint_start: int32, joint_count: int32, M_start: int32, M: Array[Float]) -> None - - - - -Utility ---------------- -.. function:: mlp(weights: Array[float32], bias: Array[float32], activation: Callable, index: int32, x: Array[float32], out: Array[float32]) -> None - - Evaluate a multi-layer perceptron (MLP) layer in the form: ``out = act(weights*x + bias)``. - - :param weights: A layer's network weights with dimensions ``(m, n)``. - :param bias: An array with dimensions ``(n)``. - :param activation: A ``wp.func`` function that takes a single scalar float as input and returns a scalar float as output - :param index: The batch item to process, typically each thread will process one item in the batch, in which case - index should be ``wp.tid()`` - :param x: The feature matrix with dimensions ``(n, b)`` - :param out: The network output with dimensions ``(m, b)`` - - :note: Feature and output matrices are transposed compared to some other frameworks such as PyTorch. - All matrices are assumed to be stored in flattened row-major memory layout (NumPy default). - - -.. function:: printf() -> None - - Allows printing formatted strings using C-style format specifiers. - - -.. function:: print(value: Any) -> None - - Print variable to stdout - - -.. function:: breakpoint() -> None - - Debugger breakpoint - - -.. function:: tid() -> int - - Return the current thread index for a 1D kernel launch. Note that this is the *global* index of the thread in the range [0, dim) - where dim is the parameter passed to kernel launch. This function may not be called from user-defined Warp functions. - - -.. function:: tid() -> Tuple[int, int] - :noindex: - :nocontentsentry: - - Return the current thread indices for a 2D kernel launch. Use ``i,j = wp.tid()`` syntax to retrieve the - coordinates inside the kernel thread grid. This function may not be called from user-defined Warp functions. - - -.. function:: tid() -> Tuple[int, int, int] - :noindex: - :nocontentsentry: - - Return the current thread indices for a 3D kernel launch. Use ``i,j,k = wp.tid()`` syntax to retrieve the - coordinates inside the kernel thread grid. This function may not be called from user-defined Warp functions. - - -.. function:: tid() -> Tuple[int, int, int, int] - :noindex: - :nocontentsentry: - - Return the current thread indices for a 4D kernel launch. Use ``i,j,k,l = wp.tid()`` syntax to retrieve the - coordinates inside the kernel thread grid. This function may not be called from user-defined Warp functions. - - -.. function:: select(cond: bool, arg1: Any, arg2: Any) - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: bool, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: int8, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: uint8, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: int16, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: uint16, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: int32, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: uint32, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: int64, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(cond: uint64, arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``cond`` is ``False`` then return ``arg1``, otherwise return ``arg2`` - - -.. function:: select(arr: Array[Any], arg1: Any, arg2: Any) - :noindex: - :nocontentsentry: - - Select between two arguments, if ``arr`` is null then return ``arg1``, otherwise return ``arg2`` - - -.. function:: atomic_add(a: Array[Any], i: int32, value: Any) - - Atomically add ``value`` onto ``a[i]``. - - -.. function:: atomic_add(a: Array[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j]``. - - -.. function:: atomic_add(a: Array[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j,k]``. - - -.. function:: atomic_add(a: Array[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j,k,l]``. - - -.. function:: atomic_add(a: FabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i]``. - - -.. function:: atomic_add(a: FabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j]``. - - -.. function:: atomic_add(a: FabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j,k]``. - - -.. function:: atomic_add(a: FabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j,k,l]``. - - -.. function:: atomic_add(a: IndexedFabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i]``. - - -.. function:: atomic_add(a: IndexedFabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j]``. - - -.. function:: atomic_add(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j,k]``. - - -.. function:: atomic_add(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically add ``value`` onto ``a[i,j,k,l]``. - - -.. function:: atomic_sub(a: Array[Any], i: int32, value: Any) - - Atomically subtract ``value`` onto ``a[i]``. - - -.. function:: atomic_sub(a: Array[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j]``. - - -.. function:: atomic_sub(a: Array[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j,k]``. - - -.. function:: atomic_sub(a: Array[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j,k,l]``. - - -.. function:: atomic_sub(a: FabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i]``. - - -.. function:: atomic_sub(a: FabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j]``. - - -.. function:: atomic_sub(a: FabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j,k]``. - - -.. function:: atomic_sub(a: FabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j,k,l]``. - - -.. function:: atomic_sub(a: IndexedFabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i]``. - - -.. function:: atomic_sub(a: IndexedFabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j]``. - - -.. function:: atomic_sub(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j,k]``. - - -.. function:: atomic_sub(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Atomically subtract ``value`` onto ``a[i,j,k,l]``. - - -.. function:: atomic_min(a: Array[Any], i: int32, value: Any) - - Compute the minimum of ``value`` and ``a[i]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: Array[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: Array[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j,k]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: Array[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: FabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: FabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: FabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j,k]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: FabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: IndexedFabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: IndexedFabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j,k]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_min(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the minimum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: Array[Any], i: int32, value: Any) - - Compute the maximum of ``value`` and ``a[i]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: Array[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: Array[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j,k]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: Array[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: FabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: FabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: FabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j,k]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: FabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: IndexedFabricArray[Any], i: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: IndexedFabricArray[Any], i: int32, j: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j,k]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: atomic_max(a: IndexedFabricArray[Any], i: int32, j: int32, k: int32, l: int32, value: Any) - :noindex: - :nocontentsentry: - - Compute the maximum of ``value`` and ``a[i,j,k,l]`` and atomically update the array. - -Note that for vectors and matrices the operation is only atomic on a per-component basis. - - -.. function:: lerp(a: Float, b: Float, t: Float) -> Float - - Linearly interpolate two values ``a`` and ``b`` using factor ``t``, computed as ``a*(1-t) + b*t`` - - -.. function:: lerp(a: Vector[Any,Float], b: Vector[Any,Float], t: Float) -> Vector[Any,Float] - :noindex: - :nocontentsentry: - - Linearly interpolate two values ``a`` and ``b`` using factor ``t``, computed as ``a*(1-t) + b*t`` - - -.. function:: lerp(a: Matrix[Any,Any,Float], b: Matrix[Any,Any,Float], t: Float) -> Matrix[Any,Any,Float] - :noindex: - :nocontentsentry: - - Linearly interpolate two values ``a`` and ``b`` using factor ``t``, computed as ``a*(1-t) + b*t`` - - -.. function:: lerp(a: Quaternion[Float], b: Quaternion[Float], t: Float) -> Quaternion[Float] - :noindex: - :nocontentsentry: - - Linearly interpolate two values ``a`` and ``b`` using factor ``t``, computed as ``a*(1-t) + b*t`` - - -.. function:: lerp(a: Transformation[Float], b: Transformation[Float], t: Float) -> Transformation[Float] - :noindex: - :nocontentsentry: - - Linearly interpolate two values ``a`` and ``b`` using factor ``t``, computed as ``a*(1-t) + b*t`` - - -.. function:: smoothstep(edge0: Float, edge1: Float, x: Float) -> Float - - Smoothly interpolate between two values ``edge0`` and ``edge1`` using a factor ``x``, - and return a result between 0 and 1 using a cubic Hermite interpolation after clamping. - - -.. function:: expect_near(arg1: Float, arg2: Float, tolerance: Float) -> None - - Prints an error to stdout if ``arg1`` and ``arg2`` are not closer than tolerance in magnitude - - -.. function:: expect_near(arg1: vec3f, arg2: vec3f, tolerance: float32) -> None - :noindex: - :nocontentsentry: - - Prints an error to stdout if any element of ``arg1`` and ``arg2`` are not closer than tolerance in magnitude - - - - -Geometry ---------------- -.. function:: bvh_query_aabb(id: uint64, lower: vec3f, upper: vec3f) -> bvh_query_t - - Construct an axis-aligned bounding box query against a BVH object. This query can be used to iterate over all bounds - inside a BVH. Returns an object that is used to track state during BVH traversal. - - :param id: The BVH identifier - :param lower: The lower bound of the bounding box in BVH space - :param upper: The upper bound of the bounding box in BVH space - - -.. function:: bvh_query_ray(id: uint64, start: vec3f, dir: vec3f) -> bvh_query_t - - Construct a ray query against a BVH object. This query can be used to iterate over all bounds - that intersect the ray. Returns an object that is used to track state during BVH traversal. - - :param id: The BVH identifier - :param start: The start of the ray in BVH space - :param dir: The direction of the ray in BVH space - - -.. function:: bvh_query_next(query: bvh_query_t, index: int32) -> bool - - Move to the next bound returned by the query. - The index of the current bound is stored in ``index``, returns ``False`` if there are no more overlapping bound. - - -.. function:: mesh_query_point(id: uint64, point: vec3f, max_dist: float32, inside: float32, face: int32, bary_u: float32, bary_v: float32) -> bool - - Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given ``point`` in space. Returns ``True`` if a point < ``max_dist`` is found. - - Identifies the sign of the distance using additional ray-casts to determine if the point is inside or outside. - This method is relatively robust, but does increase computational cost. - See below for additional sign determination methods. - - :param id: The mesh identifier - :param point: The point in space to query - :param max_dist: Mesh faces above this distance will not be considered by the query - :param inside: Returns a value < 0 if query point is inside the mesh, >=0 otherwise. - Note that mesh must be watertight for this to be robust - :param face: Returns the index of the closest face - :param bary_u: Returns the barycentric u coordinate of the closest point - :param bary_v: Returns the barycentric v coordinate of the closest point - - -.. function:: mesh_query_point_no_sign(id: uint64, point: vec3f, max_dist: float32, face: int32, bary_u: float32, bary_v: float32) -> bool - - Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given ``point`` in space. Returns ``True`` if a point < ``max_dist`` is found. - - This method does not compute the sign of the point (inside/outside) which makes it faster than other point query methods. - - :param id: The mesh identifier - :param point: The point in space to query - :param max_dist: Mesh faces above this distance will not be considered by the query - :param face: Returns the index of the closest face - :param bary_u: Returns the barycentric u coordinate of the closest point - :param bary_v: Returns the barycentric v coordinate of the closest point - - -.. function:: mesh_query_furthest_point_no_sign(id: uint64, point: vec3f, min_dist: float32, face: int32, bary_u: float32, bary_v: float32) -> bool - - Computes the furthest point on the mesh with identifier `id` to the given point in space. Returns ``True`` if a point > ``min_dist`` is found. - - This method does not compute the sign of the point (inside/outside). - - :param id: The mesh identifier - :param point: The point in space to query - :param min_dist: Mesh faces below this distance will not be considered by the query - :param face: Returns the index of the furthest face - :param bary_u: Returns the barycentric u coordinate of the furthest point - :param bary_v: Returns the barycentric v coordinate of the furthest point - - -.. function:: mesh_query_point_sign_normal(id: uint64, point: vec3f, max_dist: float32, inside: float32, face: int32, bary_u: float32, bary_v: float32, epsilon: float32) -> bool - - Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given ``point`` in space. Returns ``True`` if a point < ``max_dist`` is found. - - Identifies the sign of the distance (inside/outside) using the angle-weighted pseudo normal. - This approach to sign determination is robust for well conditioned meshes that are watertight and non-self intersecting. - It is also comparatively fast to compute. - - :param id: The mesh identifier - :param point: The point in space to query - :param max_dist: Mesh faces above this distance will not be considered by the query - :param inside: Returns a value < 0 if query point is inside the mesh, >=0 otherwise. - Note that mesh must be watertight for this to be robust - :param face: Returns the index of the closest face - :param bary_u: Returns the barycentric u coordinate of the closest point - :param bary_v: Returns the barycentric v coordinate of the closest point - :param epsilon: Epsilon treating distance values as equal, when locating the minimum distance vertex/face/edge, as a - fraction of the average edge length, also for treating closest point as being on edge/vertex default 1e-3 - - -.. function:: mesh_query_point_sign_winding_number(id: uint64, point: vec3f, max_dist: float32, inside: float32, face: int32, bary_u: float32, bary_v: float32, accuracy: float32, threshold: float32) -> bool - - Computes the closest point on the :class:`Mesh` with identifier ``id`` to the given point in space. Returns ``True`` if a point < ``max_dist`` is found. - - Identifies the sign using the winding number of the mesh relative to the query point. This method of sign determination is robust for poorly conditioned meshes - and provides a smooth approximation to sign even when the mesh is not watertight. This method is the most robust and accurate of the sign determination meshes - but also the most expensive. - - .. note:: The :class:`Mesh` object must be constructed with ``support_winding_number=True`` for this method to return correct results. - - :param id: The mesh identifier - :param point: The point in space to query - :param max_dist: Mesh faces above this distance will not be considered by the query - :param inside: Returns a value < 0 if query point is inside the mesh, >=0 otherwise. - Note that mesh must be watertight for this to be robust - :param face: Returns the index of the closest face - :param bary_u: Returns the barycentric u coordinate of the closest point - :param bary_v: Returns the barycentric v coordinate of the closest point - :param accuracy: Accuracy for computing the winding number with fast winding number method utilizing second-order dipole approximation, default 2.0 - :param threshold: The threshold of the winding number to be considered inside, default 0.5 - - -.. function:: mesh_query_ray(id: uint64, start: vec3f, dir: vec3f, max_t: float32, t: float32, bary_u: float32, bary_v: float32, sign: float32, normal: vec3f, face: int32) -> bool - - Computes the closest ray hit on the :class:`Mesh` with identifier ``id``, returns ``True`` if a point < ``max_t`` is found. - - :param id: The mesh identifier - :param start: The start point of the ray - :param dir: The ray direction (should be normalized) - :param max_t: The maximum distance along the ray to check for intersections - :param t: Returns the distance of the closest hit along the ray - :param bary_u: Returns the barycentric u coordinate of the closest hit - :param bary_v: Returns the barycentric v coordinate of the closest hit - :param sign: Returns a value > 0 if the hit ray hit front of the face, returns < 0 otherwise - :param normal: Returns the face normal - :param face: Returns the index of the hit face - - -.. function:: mesh_query_aabb(id: uint64, lower: vec3f, upper: vec3f) -> mesh_query_aabb_t - - Construct an axis-aligned bounding box query against a :class:`Mesh`. - This query can be used to iterate over all triangles inside a volume. - Returns an object that is used to track state during mesh traversal. - - :param id: The mesh identifier - :param lower: The lower bound of the bounding box in mesh space - :param upper: The upper bound of the bounding box in mesh space - - -.. function:: mesh_query_aabb_next(query: mesh_query_aabb_t, index: int32) -> bool - - Move to the next triangle overlapping the query bounding box. - The index of the current face is stored in ``index``, returns ``False`` if there are no more overlapping triangles. - - -.. function:: mesh_eval_position(id: uint64, face: int32, bary_u: float32, bary_v: float32) -> vec3f - - Evaluates the position on the :class:`Mesh` given a face index and barycentric coordinates. - - -.. function:: mesh_eval_velocity(id: uint64, face: int32, bary_u: float32, bary_v: float32) -> vec3f - - Evaluates the velocity on the :class:`Mesh` given a face index and barycentric coordinates. - - -.. function:: hash_grid_query(id: uint64, point: vec3f, max_dist: float32) -> hash_grid_query_t - - Construct a point query against a :class:`HashGrid`. This query can be used to iterate over all neighboring points within a fixed radius from the query point. Returns an object that is used to track state during neighbor traversal. - - -.. function:: hash_grid_query_next(query: hash_grid_query_t, index: int32) -> bool - - Move to the next point in the hash grid query. The index of the current neighbor is stored in ``index``, returns ``False`` - if there are no more neighbors. - - -.. function:: hash_grid_point_id(id: uint64, index: int32) -> int - - Return the index of a point in the :class:`HashGrid`. This can be used to reorder threads such that grid - traversal occurs in a spatially coherent order. - - Returns -1 if the :class:`HashGrid` has not been reserved. - - -.. function:: intersect_tri_tri(v0: vec3f, v1: vec3f, v2: vec3f, u0: vec3f, u1: vec3f, u2: vec3f) -> int - - Tests for intersection between two triangles (v0, v1, v2) and (u0, u1, u2) using Moller's method. Returns > 0 if triangles intersect. - - -.. function:: mesh_get(id: uint64) -> Mesh - - Retrieves the mesh given its index. [1]_ - - -.. function:: mesh_eval_face_normal(id: uint64, face: int32) -> vec3f - - Evaluates the face normal the mesh given a face index. - - -.. function:: mesh_get_point(id: uint64, index: int32) -> vec3f - - Returns the point of the mesh given a index. - - -.. function:: mesh_get_velocity(id: uint64, index: int32) -> vec3f - - Returns the velocity of the mesh given a index. - - -.. function:: mesh_get_index(id: uint64, index: int32) -> int - - Returns the point-index of the mesh given a face-vertex index. - - -.. function:: closest_point_edge_edge(p1: vec3f, q1: vec3f, p2: vec3f, q2: vec3f, epsilon: float32) -> vec3f - - Finds the closest points between two edges. Returns barycentric weights to the points on each edge, as well as the closest distance between the edges. - - :param p1: First point of first edge - :param q1: Second point of first edge - :param p2: First point of second edge - :param q2: Second point of second edge - :param epsilon: Zero tolerance for determining if points in an edge are degenerate. - :param out: vec3 output containing (s,t,d), where `s` in [0,1] is the barycentric weight for the first edge, `t` is the barycentric weight for the second edge, and `d` is the distance between the two edges at these two closest points. - - - - -Volumes ---------------- -.. function:: volume_sample_f(id: uint64, uvw: vec3f, sampling_mode: int32) -> float - - Sample the volume given by ``id`` at the volume local-space point ``uvw``. - Interpolation should be :attr:`warp.Volume.CLOSEST` or :attr:`wp.Volume.LINEAR.` - - -.. function:: volume_sample_grad_f(id: uint64, uvw: vec3f, sampling_mode: int32, grad: vec3f) -> float - - Sample the volume and its gradient given by ``id`` at the volume local-space point ``uvw``. - Interpolation should be :attr:`warp.Volume.CLOSEST` or :attr:`wp.Volume.LINEAR.` - - -.. function:: volume_lookup_f(id: uint64, i: int32, j: int32, k: int32) -> float - - Returns the value of voxel with coordinates ``i``, ``j``, ``k``. - If the voxel at this index does not exist, this function returns the background value - - -.. function:: volume_store_f(id: uint64, i: int32, j: int32, k: int32, value: float32) -> None - - Store ``value`` at the voxel with coordinates ``i``, ``j``, ``k``. - - -.. function:: volume_sample_v(id: uint64, uvw: vec3f, sampling_mode: int32) -> vec3f - - Sample the vector volume given by ``id`` at the volume local-space point ``uvw``. - Interpolation should be :attr:`warp.Volume.CLOSEST` or :attr:`wp.Volume.LINEAR.` - - -.. function:: volume_lookup_v(id: uint64, i: int32, j: int32, k: int32) -> vec3f - - Returns the vector value of voxel with coordinates ``i``, ``j``, ``k``. - If the voxel at this index does not exist, this function returns the background value. - - -.. function:: volume_store_v(id: uint64, i: int32, j: int32, k: int32, value: vec3f) -> None - - Store ``value`` at the voxel with coordinates ``i``, ``j``, ``k``. - - -.. function:: volume_sample_i(id: uint64, uvw: vec3f) -> int - - Sample the :class:`int32` volume given by ``id`` at the volume local-space point ``uvw``. - - -.. function:: volume_lookup_i(id: uint64, i: int32, j: int32, k: int32) -> int - - Returns the :class:`int32` value of voxel with coordinates ``i``, ``j``, ``k``. - If the voxel at this index does not exist, this function returns the background value. - - -.. function:: volume_store_i(id: uint64, i: int32, j: int32, k: int32, value: int32) -> None - - Store ``value`` at the voxel with coordinates ``i``, ``j``, ``k``. - - -.. function:: volume_index_to_world(id: uint64, uvw: vec3f) -> vec3f - - Transform a point ``uvw`` defined in volume index space to world space given the volume's intrinsic affine transformation. - - -.. function:: volume_world_to_index(id: uint64, xyz: vec3f) -> vec3f - - Transform a point ``xyz`` defined in volume world space to the volume's index space given the volume's intrinsic affine transformation. - - -.. function:: volume_index_to_world_dir(id: uint64, uvw: vec3f) -> vec3f - - Transform a direction ``uvw`` defined in volume index space to world space given the volume's intrinsic affine transformation. - - -.. function:: volume_world_to_index_dir(id: uint64, xyz: vec3f) -> vec3f - - Transform a direction ``xyz`` defined in volume world space to the volume's index space given the volume's intrinsic affine transformation. - - - - -Random ---------------- -.. function:: rand_init(seed: int32) -> uint32 - - Initialize a new random number generator given a user-defined seed. Returns a 32-bit integer representing the RNG state. - - -.. function:: rand_init(seed: int32, offset: int32) -> uint32 - :noindex: - :nocontentsentry: - - Initialize a new random number generator given a user-defined seed and an offset. - This alternative constructor can be useful in parallel programs, where a kernel as a whole should share a seed, - but each thread should generate uncorrelated values. In this case usage should be ``r = rand_init(seed, tid)`` - - -.. function:: randi(state: uint32) -> int - - Return a random integer in the range [0, 2^32). - - -.. function:: randi(state: uint32, min: int32, max: int32) -> int - :noindex: - :nocontentsentry: - - Return a random integer between [min, max). - - -.. function:: randf(state: uint32) -> float - - Return a random float between [0.0, 1.0). - - -.. function:: randf(state: uint32, min: float32, max: float32) -> float - :noindex: - :nocontentsentry: - - Return a random float between [min, max). - - -.. function:: randn(state: uint32) -> float - - Sample a normal distribution. - - -.. function:: sample_cdf(state: uint32, cdf: Array[float32]) -> int - - Inverse-transform sample a cumulative distribution function. - - -.. function:: sample_triangle(state: uint32) -> vec2f - - Uniformly sample a triangle. Returns sample barycentric coordinates. - - -.. function:: sample_unit_ring(state: uint32) -> vec2f - - Uniformly sample a ring in the xy plane. - - -.. function:: sample_unit_disk(state: uint32) -> vec2f - - Uniformly sample a disk in the xy plane. - - -.. function:: sample_unit_sphere_surface(state: uint32) -> vec3f - - Uniformly sample a unit sphere surface. - - -.. function:: sample_unit_sphere(state: uint32) -> vec3f - - Uniformly sample a unit sphere. - - -.. function:: sample_unit_hemisphere_surface(state: uint32) -> vec3f - - Uniformly sample a unit hemisphere surface. - - -.. function:: sample_unit_hemisphere(state: uint32) -> vec3f - - Uniformly sample a unit hemisphere. - - -.. function:: sample_unit_square(state: uint32) -> vec2f - - Uniformly sample a unit square. - - -.. function:: sample_unit_cube(state: uint32) -> vec3f - - Uniformly sample a unit cube. - - -.. function:: poisson(state: uint32, lam: float32) -> uint32 - - Generate a random sample from a Poisson distribution. - - :param state: RNG state - :param lam: The expected value of the distribution - - -.. function:: noise(state: uint32, x: float32) -> float - - Non-periodic Perlin-style noise in 1D. - - -.. function:: noise(state: uint32, xy: vec2f) -> float - :noindex: - :nocontentsentry: - - Non-periodic Perlin-style noise in 2D. - - -.. function:: noise(state: uint32, xyz: vec3f) -> float - :noindex: - :nocontentsentry: - - Non-periodic Perlin-style noise in 3D. - - -.. function:: noise(state: uint32, xyzt: vec4f) -> float - :noindex: - :nocontentsentry: - - Non-periodic Perlin-style noise in 4D. - - -.. function:: pnoise(state: uint32, x: float32, px: int32) -> float - - Periodic Perlin-style noise in 1D. - - -.. function:: pnoise(state: uint32, xy: vec2f, px: int32, py: int32) -> float - :noindex: - :nocontentsentry: - - Periodic Perlin-style noise in 2D. - - -.. function:: pnoise(state: uint32, xyz: vec3f, px: int32, py: int32, pz: int32) -> float - :noindex: - :nocontentsentry: - - Periodic Perlin-style noise in 3D. - - -.. function:: pnoise(state: uint32, xyzt: vec4f, px: int32, py: int32, pz: int32, pt: int32) -> float - :noindex: - :nocontentsentry: - - Periodic Perlin-style noise in 4D. - - -.. function:: curlnoise(state: uint32, xy: vec2f, octaves: uint32, lacunarity: float32, gain: float32) -> vec2f - - Divergence-free vector field based on the gradient of a Perlin noise function. [1]_ - - -.. function:: curlnoise(state: uint32, xyz: vec3f, octaves: uint32, lacunarity: float32, gain: float32) -> vec3f - :noindex: - :nocontentsentry: - - Divergence-free vector field based on the curl of three Perlin noise functions. [1]_ - - -.. function:: curlnoise(state: uint32, xyzt: vec4f, octaves: uint32, lacunarity: float32, gain: float32) -> vec3f - :noindex: - :nocontentsentry: - - Divergence-free vector field based on the curl of three Perlin noise functions. [1]_ - - - - -Operators ---------------- -.. function:: add(x: Scalar, y: Scalar) -> Scalar - - -.. function:: add(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: add(x: Quaternion[Scalar], y: Quaternion[Scalar]) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: add(x: Matrix[Any,Any,Scalar], y: Matrix[Any,Any,Scalar]) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: add(x: Transformation[Scalar], y: Transformation[Scalar]) -> Transformation[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: sub(x: Scalar, y: Scalar) -> Scalar - - -.. function:: sub(x: Vector[Any,Scalar], y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: sub(x: Matrix[Any,Any,Scalar], y: Matrix[Any,Any,Scalar]) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: sub(x: Quaternion[Scalar], y: Quaternion[Scalar]) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: sub(x: Transformation[Scalar], y: Transformation[Scalar]) -> Transformation[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: bit_and(x: Int, y: Int) -> Int - - -.. function:: bit_or(x: Int, y: Int) -> Int - - -.. function:: bit_xor(x: Int, y: Int) -> Int - - -.. function:: lshift(x: Int, y: Int) -> Int - - -.. function:: rshift(x: Int, y: Int) -> Int - - -.. function:: invert(x: Int) -> Int - - -.. function:: mul(x: Scalar, y: Scalar) -> Scalar - - -.. function:: mul(x: Vector[Any,Scalar], y: Scalar) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Scalar, y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Quaternion[Scalar], y: Scalar) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Scalar, y: Quaternion[Scalar]) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Quaternion[Scalar], y: Quaternion[Scalar]) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Scalar, y: Matrix[Any,Any,Scalar]) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Matrix[Any,Any,Scalar], y: Scalar) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Matrix[Any,Any,Scalar], y: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Matrix[Any,Any,Scalar], y: Matrix[Any,Any,Scalar]) - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Transformation[Scalar], y: Transformation[Scalar]) -> Transformation[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Scalar, y: Transformation[Scalar]) -> Transformation[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mul(x: Transformation[Scalar], y: Scalar) -> Transformation[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: mod(x: Scalar, y: Scalar) -> Scalar - - -.. function:: div(x: Scalar, y: Scalar) -> Scalar - - -.. function:: div(x: Vector[Any,Scalar], y: Scalar) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: div(x: Matrix[Any,Any,Scalar], y: Scalar) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: div(x: Quaternion[Scalar], y: Scalar) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: floordiv(x: Scalar, y: Scalar) -> Scalar - - -.. function:: pos(x: Scalar) -> Scalar - - -.. function:: pos(x: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: pos(x: Quaternion[Scalar]) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: pos(x: Matrix[Any,Any,Scalar]) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: neg(x: Scalar) -> Scalar - - -.. function:: neg(x: Vector[Any,Scalar]) -> Vector[Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: neg(x: Quaternion[Scalar]) -> Quaternion[Scalar] - :noindex: - :nocontentsentry: - - -.. function:: neg(x: Matrix[Any,Any,Scalar]) -> Matrix[Any,Any,Scalar] - :noindex: - :nocontentsentry: - - -.. function:: unot(b: bool) -> bool - - -.. function:: unot(b: int8) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(b: uint8) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(b: int16) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(b: uint16) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(b: int32) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(b: uint32) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(b: int64) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(b: uint64) -> bool - :noindex: - :nocontentsentry: - - -.. function:: unot(a: Array[Any]) -> bool - :noindex: - :nocontentsentry: - - -.. rubric:: Footnotes -.. [1] Note: function gradients not implemented for backpropagation. diff --git a/docs/_build/html/_sources/modules/interoperability.rst.txt b/docs/_build/html/_sources/modules/interoperability.rst.txt deleted file mode 100644 index 5e4472ccb..000000000 --- a/docs/_build/html/_sources/modules/interoperability.rst.txt +++ /dev/null @@ -1,146 +0,0 @@ -Interoperability -================ - -Warp can interop with other Python-based frameworks such as NumPy through standard interface protocols. - -NumPy ------ - -Warp arrays may be converted to a NumPy array through the ``warp.array.numpy()`` method. When the Warp array lives on -the ``cpu`` device this will return a zero-copy view onto the underlying Warp allocation. If the array lives on a -``cuda`` device then it will first be copied back to a temporary buffer and copied to NumPy. - -Warp CPU arrays also implement the ``__array_interface__`` protocol and so can be used to construct NumPy arrays -directly:: - - w = wp.array([1.0, 2.0, 3.0], dtype=float, device="cpu") - a = np.array(w) - print(a) - > [1. 2. 3.] - -.. _pytorch-interop: - -PyTorch -------- - -Warp provides helper functions to convert arrays to/from PyTorch. Please see the ``warp.torch`` module for more details. Example usage is shown below:: - - import warp.torch - - w = wp.array([1.0, 2.0, 3.0], dtype=float, device="cpu") - - # convert to Torch tensor - t = warp.to_torch(w) - - # convert from Torch tensor - w = warp.from_torch(t) - -These helper functions allow the conversion of Warp arrays to/from PyTorch tensors without copying the underlying data. -At the same time, if available, gradient arrays and tensors are converted to/from PyTorch autograd tensors, allowing the use of Warp arrays -in PyTorch autograd computations. - -Example: Optimization using ``warp.from_torch()`` -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -An example usage of minimizing a loss function over an array of 2D points written in Warp via PyTorch's Adam optimizer using ``warp.from_torch`` is as follows:: - - import warp as wp - import torch - - wp.init() - - @wp.kernel() - def loss(xs: wp.array(dtype=float, ndim=2), l: wp.array(dtype=float)): - tid = wp.tid() - wp.atomic_add(l, 0, xs[tid, 0] ** 2.0 + xs[tid, 1] ** 2.0) - - # indicate requires_grad so that Warp can accumulate gradients in the grad buffers - xs = torch.randn(100, 2, requires_grad=True) - l = torch.zeros(1, requires_grad=True) - opt = torch.optim.Adam([xs], lr=0.1) - - wp_xs = wp.from_torch(xs) - wp_l = wp.from_torch(l) - - tape = wp.Tape() - with tape: - # record the loss function kernel launch on the tape - wp.launch(loss, dim=len(xs), inputs=[wp_xs], outputs=[wp_l], device=wp_xs.device) - - for i in range(500): - tape.zero() - tape.backward(loss=wp_l) # compute gradients - # now xs.grad will be populated with the gradients computed by Warp - opt.step() # update xs (and thereby wp_xs) - - # these lines are only needed for evaluating the loss - # (the optimization just needs the gradient, not the loss value) - wp_l.zero_() - wp.launch(loss, dim=len(xs), inputs=[wp_xs], outputs=[wp_l], device=wp_xs.device) - print(f"{i}\tloss: {l.item()}") - -Example: Optimization using ``warp.to_torch`` -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -Less code is needed when we declare the optimization variables directly in Warp and use ``warp.to_torch`` to convert them to PyTorch tensors. -Here, we revisit the same example from above where now only a single conversion to a torch tensor is needed to supply Adam with the optimization variables:: - - import warp as wp - import numpy as np - import torch - - wp.init() - - @wp.kernel() - def loss(xs: wp.array(dtype=float, ndim=2), l: wp.array(dtype=float)): - tid = wp.tid() - wp.atomic_add(l, 0, xs[tid, 0] ** 2.0 + xs[tid, 1] ** 2.0) - - # initialize the optimization variables in Warp - xs = wp.array(np.random.randn(100, 2), dtype=wp.float32, requires_grad=True) - l = wp.zeros(1, dtype=wp.float32, requires_grad=True) - # just a single wp.to_torch call is needed, Adam optimizes using the Warp array gradients - opt = torch.optim.Adam([wp.to_torch(xs)], lr=0.1) - - tape = wp.Tape() - with tape: - wp.launch(loss, dim=len(xs), inputs=[xs], outputs=[l], device=xs.device) - - for i in range(500): - tape.zero() - tape.backward(loss=l) - opt.step() - - l.zero_() - wp.launch(loss, dim=len(xs), inputs=[xs], outputs=[l], device=xs.device) - print(f"{i}\tloss: {l.numpy()[0]}") - -.. automodule:: warp.torch - :members: - :undoc-members: - -CuPy/Numba ----------- - -Warp GPU arrays support the ``__cuda_array_interface__`` protocol for sharing data with other Python GPU frameworks. -Currently this is one-directional, so that Warp arrays can be used as input to any framework that also supports the -``__cuda_array_interface__`` protocol, but not the other way around. - -.. _jax-interop: - -JAX ---- - -Interoperability with JAX arrays is supported through the following methods. -Internally these use the DLPack protocol to exchange data in a zero-copy way with JAX. - -.. automodule:: warp.jax - :members: - :undoc-members: - -DLPack ------- - -.. automodule:: warp.dlpack - :members: - :undoc-members: diff --git a/docs/_build/html/_sources/modules/profiling.rst.txt b/docs/_build/html/_sources/modules/profiling.rst.txt deleted file mode 100644 index 315f72b23..000000000 --- a/docs/_build/html/_sources/modules/profiling.rst.txt +++ /dev/null @@ -1,44 +0,0 @@ -Profiling -========= - -``wp.ScopedTimer`` objects can be used to gain some basic insight into the performance of Warp applications:: - - with wp.ScopedTimer("grid build"): - self.grid.build(self.x, self.point_radius) - -This results in a printout at runtime to the standard output stream like:: - - grid build took 0.06 ms - -The ``wp.ScopedTimer`` object does not synchronize (e.g. by calling ``wp.synchronize()``) -upon exiting the ``with`` statement, so this can lead to misleading numbers if the body -of the ``with`` statement launches device kernels. - -When a ``wp.ScopedTimer`` object is passed ``use_nvtx=True`` as an argument, the timing functionality is replaced by calls -to ``nvtx.start_range()`` and ``nvtx.end_range()``:: - - with wp.ScopedTimer("grid build", use_nvtx=True, color="cyan"): - self.grid.build(self.x, self.point_radius) - -These range annotations can then be collected by a tool like `NVIDIA Nsight Systems `_ -for visualization on a timeline, e.g.:: - - nsys profile python warp_application.py - -This code snippet also demonstrates the use of the ``color`` argument to specify a color -for the range, which may be a number representing the ARGB value or a recognized string -(refer to `colors.py `_ for -additional color examples). -The `nvtx module `_ must be -installed in the Python environment for this capability to work. -An equivalent way to create an NVTX range without using ``wp.ScopedTimer`` is:: - - import nvtx - - with nvtx.annotate("grid build", color="cyan"): - self.grid.build(self.x, self.point_radius) - -This form may be more convenient if the user does not need to frequently switch -between timer and NVTX capabilities of ``wp.ScopedTimer``. - -.. autoclass:: warp.ScopedTimer diff --git a/docs/_build/html/_sources/modules/runtime.rst.txt b/docs/_build/html/_sources/modules/runtime.rst.txt deleted file mode 100644 index 766adf1c3..000000000 --- a/docs/_build/html/_sources/modules/runtime.rst.txt +++ /dev/null @@ -1,1491 +0,0 @@ -Runtime Reference -================= - -.. currentmodule:: warp - -This section describes the Warp Python runtime API, how to manage memory, launch kernels, and high-level functionality -for dealing with objects such as meshes and volumes. The APIs described in this section are intended to be used at -the *Python Scope* and run inside the CPython interpreter. For a comprehensive list of functions available at -the *Kernel Scope*, please see the :doc:`functions` section. - -Kernels -------- - -Kernels are launched with the :func:`wp.launch() ` function on a specific device (CPU/GPU):: - - wp.launch(simple_kernel, dim=1024, inputs=[a, b, c], device="cuda") - -Kernels may be launched with multi-dimensional grid bounds. In this case threads are not assigned a single index, -but a coordinate in an n-dimensional grid, e.g.:: - - wp.launch(complex_kernel, dim=(128, 128, 3), ...) - -Launches a 3D grid of threads with dimension 128 x 128 x 3. To retrieve the 3D index for each thread use the following syntax:: - - i,j,k = wp.tid() - -.. note:: - Currently kernels launched on CPU devices will be executed in serial. - Kernels launched on CUDA devices will be launched in parallel with a fixed block-size. - -.. note:: - Note that all the kernel inputs must live on the target device, or a runtime exception will be raised. - -.. autofunction:: launch - -Large Kernel Launches -##################### - -A limitation of Warp is that each dimension of the grid used to launch a kernel must be representable as a 32-bit -signed integer. Therefore, no single dimension of a grid should exceed :math:`2^{31}-1`. - -Warp also currently uses a fixed block size of 256 (CUDA) threads per block. -By default, Warp will try to process one element from the Warp grid in one CUDA thread. -This is not always possible for kernels launched with multi-dimensional grid bounds, as there are -`hardware limitations `_ -on CUDA block dimensions. - -Warp will automatically resort to using -`grid-stride loops `_ when -it is not possible for a CUDA thread to process only one element from the Warp grid -When this happens, some CUDA threads may process more than one element from the Warp grid. -Users can also set the ``max_blocks`` parameter to fine-tune the grid-striding behavior of kernels, even for kernels that are otherwise -able to process one Warp-grid element per CUDA thread. - -Runtime Kernel Specialization -############################# - -It is often desirable to specialize kernels for different types, constants, or functions. -We can achieve this through the use of runtime kernel specialization using Python closures. - -For example, we might require a variety of kernels that execute particular functions for each item in an array. -We might also want this function call to be valid for a variety of data types. Making use of closure and generics, we can generate -these kernels using a single kernel definition: :: - - def make_kernel(func, dtype): - def closure_kernel_fn(data: wp.array(dtype=dtype), out: wp.array(dtype=dtype)): - tid = wp.tid() - out[tid] = func(data[tid]) - - return wp.Kernel(closure_kernel_fn) - -In practice, we might use our kernel generator, ``make_kernel()`` as follows: :: - - @wp.func - def sqr(x: Any) -> Any: - return x * x - - @wp.func - def cube(x: Any) -> Any: - return sqr(x) * x - - sqr_float = make_kernel(sqr, wp.float32) - cube_double = make_kernel(cube, wp.float64) - - arr = [1.0, 2.0, 3.0] - N = len(arr) - - data_float = wp.array(arr, dtype=wp.float32, device=device) - data_double = wp.array(arr, dtype=wp.float64, device=device) - - out_float = wp.zeros(N, dtype=wp.float32, device=device) - out_double = wp.zeros(N, dtype=wp.float64, device=device) - - wp.launch(sqr_float, dim=N, inputs=[data_float], outputs=[out_float], device=device) - wp.launch(cube_double, dim=N, inputs=[data_double], outputs=[out_double], device=device) - -We can specialize kernel definitions over warp constants similarly. The following generates kernels that add a specified constant -to a generic-typed array value: :: - - def make_add_kernel(key, constant): - def closure_kernel_fn(data: wp.array(dtype=Any), out: wp.array(dtype=Any)): - tid = wp.tid() - out[tid] = data[tid] + constant - - return wp.Kernel(closure_kernel_fn, key=key) - - add_ones_int = make_add_kernel("add_one", wp.constant(1)) - add_ones_vec3 = make_add_kernel("add_ones_vec3", wp.constant(wp.vec3(1.0, 1.0, 1.0))) - - a = wp.zeros(2, dtype=int) - b = wp.zeros(2, dtype=wp.vec3) - - a_out = wp.zeros_like(a) - b_out = wp.zeros_like(b) - - wp.launch(add_ones_int, dim=a.size, inputs=[a], outputs=[a_out], device=device) - wp.launch(add_ones_vec3, dim=b.size, inputs=[b], outputs=[b_out], device=device) - - -Arrays ------- - -Arrays are the fundamental memory abstraction in Warp; they are created through the following global constructors: :: - - wp.empty(shape=1024, dtype=wp.vec3, device="cpu") - wp.zeros(shape=1024, dtype=float, device="cuda") - wp.full(shape=1024, value=10, dtype=int, device="cuda") - - -Arrays can also be constructed directly from ``numpy`` ndarrays as follows: :: - - r = np.random.rand(1024) - - # copy to Warp owned array - a = wp.array(r, dtype=float, device="cpu") - - # return a Warp array wrapper around the NumPy data (zero-copy) - a = wp.array(r, dtype=float, copy=False, device="cpu") - - # return a Warp copy of the array data on the GPU - a = wp.array(r, dtype=float, device="cuda") - -Note that for multi-dimensional data the ``dtype`` parameter must be specified explicitly, e.g.: :: - - r = np.random.rand((1024, 3)) - - # initialize as an array of vec3 objects - a = wp.array(r, dtype=wp.vec3, device="cuda") - -If the shapes are incompatible, an error will be raised. - - -Arrays can be moved between devices using the ``array.to()`` method: :: - - host_array = wp.array(a, dtype=float, device="cpu") - - # allocate and copy to GPU - device_array = host_array.to("cuda") - -Additionally, arrays can be copied directly between memory spaces: :: - - src_array = wp.array(a, dtype=float, device="cpu") - dest_array = wp.empty_like(host_array) - - # copy from source CPU buffer to GPU - wp.copy(dest_array, src_array) - -.. autoclass:: array - :members: - :undoc-members: - -Multi-dimensional Arrays -######################## - -Multi-dimensional arrays can be constructed by passing a tuple of sizes for each dimension, e.g.: the following constructs a 2d array of size 1024x16:: - - wp.zeros(shape=(1024, 16), dtype=float, device="cuda") - -When passing multi-dimensional arrays to kernels users must specify the expected array dimension inside the kernel signature, -e.g. to pass a 2d array to a kernel the number of dims is specified using the ``ndim=2`` parameter:: - - @wp.kernel - def test(input: wp.array(dtype=float, ndim=2)): - -Type-hint helpers are provided for common array sizes, e.g.: ``array2d()``, ``array3d()``, which are equivalent to calling ``array(..., ndim=2)```, etc. To index a multi-dimensional array use a the following kernel syntax:: - - # returns a float from the 2d array - value = input[i,j] - -To create an array slice use the following syntax, where the number of indices is less than the array dimensions:: - - # returns an 1d array slice representing a row of the 2d array - row = input[i] - -Slice operators can be concatenated, e.g.: ``s = array[i][j][k]``. Slices can be passed to ``wp.func`` user functions provided -the function also declares the expected array dimension. Currently only single-index slicing is supported. - -.. note:: - Currently Warp limits arrays to 4 dimensions maximum. This is in addition to the contained datatype, which may be 1-2 dimensional for vector and matrix types such as ``vec3``, and ``mat33``. - - -The following construction methods are provided for allocating zero-initialized and empty (non-initialized) arrays: - -.. autofunction:: zeros -.. autofunction:: zeros_like -.. autofunction:: full -.. autofunction:: full_like -.. autofunction:: empty -.. autofunction:: empty_like -.. autofunction:: copy -.. autofunction:: clone - -Matrix Multiplication -##################### - -Warp 2D array multiplication is built on NVIDIA's CUTLASS library, which enables fast matrix multiplication of large arrays on the GPU. - -If no GPU is detected, matrix multiplication falls back to Numpy's implementation on the CPU. - -Matrix multiplication is fully differentiable, and can be recorded on the tape like so:: - - tape = wp.Tape() - with tape: - wp.matmul(A, B, C, D, device=device) - wp.launch(loss_kernel, dim=(m, n), inputs=[D, loss], device=device) - - tape.backward(loss=loss) - A_grad = A.grad.numpy() - -Using the ``@`` operator (``D = A @ B``) will default to the same CUTLASS algorithm used in ``wp.matmul``. - -.. autofunction:: matmul - -Data Types ----------- - -Scalar Types -############ - -The following scalar storage types are supported for array structures: - -+---------+------------------------+ -| bool | boolean | -+---------+------------------------+ -| int8 | signed byte | -+---------+------------------------+ -| uint8 | unsigned byte | -+---------+------------------------+ -| int16 | signed short | -+---------+------------------------+ -| uint16 | unsigned short | -+---------+------------------------+ -| int32 | signed integer | -+---------+------------------------+ -| uint32 | unsigned integer | -+---------+------------------------+ -| int64 | signed long integer | -+---------+------------------------+ -| uint64 | unsigned long integer | -+---------+------------------------+ -| float32 | single precision float | -+---------+------------------------+ -| float64 | double precision float | -+---------+------------------------+ - -Warp supports ``float`` and ``int`` as aliases for ``wp.float32`` and ``wp.int32`` respectively. - -.. _vec: - -Vectors -####### - -Warp provides built-in math and geometry types for common simulation and graphics problems. -A full reference for operators and functions for these types is available in the :doc:`/modules/functions`. - -Warp supports vectors of numbers with an arbitrary length/numeric type. The built in concrete types are as follows: - -+-----------------------+------------------------------------------------+ -| vec2 vec3 vec4 | 2d, 3d, 4d vector of default precision floats | -+-----------------------+------------------------------------------------+ -| vec2f vec3f vec4f | 2d, 3d, 4d vector of single precision floats | -+-----------------------+------------------------------------------------+ -| vec2d vec3d vec4d | 2d, 3d, 4d vector of double precision floats | -+-----------------------+------------------------------------------------+ -| vec2h vec3h vec4h | 2d, 3d, 4d vector of half precision floats | -+-----------------------+------------------------------------------------+ -| vec2ub vec3ub vec4ub | 2d, 3d, 4d vector of half precision floats | -+-----------------------+------------------------------------------------+ -| spatial_vector | 6d vector of single precision floats | -+-----------------------+------------------------------------------------+ -| spatial_vectorf | 6d vector of single precision floats | -+-----------------------+------------------------------------------------+ -| spatial_vectord | 6d vector of double precision floats | -+-----------------------+------------------------------------------------+ -| spatial_vectorh | 6d vector of half precision floats | -+-----------------------+------------------------------------------------+ - -Vectors support most standard linear algebra operations, e.g.: :: - - @wp.kernel - def compute( ... ): - - # basis vectors - a = wp.vec3(1.0, 0.0, 0.0) - b = wp.vec3(0.0, 1.0, 0.0) - - # take the cross product - c = wp.cross(a, b) - - # compute - r = wp.dot(c, c) - - ... - - -It's possible to declare additional vector types with different lengths and data types. This is done in outside of kernels in *Python scope* using ``warp.types.vector()``, for example: :: - - # declare a new vector type for holding 5 double precision floats: - vec5d = wp.types.vector(length=5, dtype=wp.float64) - -Once declared, the new type can be used when allocating arrays or inside kernels: :: - - # create an array of vec5d - arr = wp.zeros(10, dtype=vec5d) - - # use inside a kernel - @wp.kernel - def compute( ... ): - - # zero initialize a custom named vector type - v = vec5d() - ... - - # component-wise initialize a named vector type - v = vec5d(wp.float64(1.0), - wp.float64(2.0), - wp.float64(3.0), - wp.float64(4.0), - wp.float64(5.0)) - ... - -In addition, it's possible to directly create *anonymously* typed instances of these vectors without declaring their type in advance. In this case the type will be inferred by the constructor arguments. For example: :: - - @wp.kernel - def compute( ... ): - - # zero initialize vector of 5 doubles: - v = wp.vector(dtype=wp.float64, length=5) - - # scalar initialize a vector of 5 doubles to the same value: - v = wp.vector(wp.float64(1.0), length=5) - - # component-wise initialize a vector of 5 doubles - v = wp.vector(wp.float64(1.0), - wp.float64(2.0), - wp.float64(3.0), - wp.float64(4.0), - wp.float64(5.0)) - - -These can be used with all the standard vector arithmetic operators, e.g.: ``+``, ``-``, scalar multiplication, and can also be transformed using matrices with compatible dimensions, potentially returning vectors with a different length. - -.. _mat: - -Matrices -######## - -Matrices with arbitrary shapes/numeric types are also supported. The built in concrete matrix types are as follows: - -+--------------------------+-----------------------------------------------------+ -| mat22 mat33 mat44 | 2,3 and 4d square matrix of default precision | -+--------------------------+-----------------------------------------------------+ -| mat22f mat33f mat44f | 2,3 and 4d square matrix of single precision floats | -+--------------------------+-----------------------------------------------------+ -| mat22d mat33d mat44d | 2,3 and 4d square matrix of double precision floats | -+--------------------------+-----------------------------------------------------+ -| mat22h mat33h mat44h | 2,3 and 4d square matrix of half precision floats | -+--------------------------+-----------------------------------------------------+ -| spatial_matrix | 6x6 matrix of single precision floats | -+--------------------------+-----------------------------------------------------+ -| spatial_matrixf | 6x6 matrix of single precision floats | -+--------------------------+-----------------------------------------------------+ -| spatial_matrixd | 6x6 matrix of double precision floats | -+--------------------------+-----------------------------------------------------+ -| spatial_matrixh | 6x6 matrix of half precision floats | -+--------------------------+-----------------------------------------------------+ - -Matrices are stored in row-major format and support most standard linear algebra operations: :: - - @wp.kernel - def compute( ... ): - - # initialize matrix - m = wp.mat22(1.0, 2.0, - 3.0, 4.0) - - # compute inverse - minv = wp.inverse(m) - - # transform vector - v = minv * wp.vec2(0.5, 0.3) - - ... - - -In a similar manner to vectors, it's possible to declare new matrix types with arbitrary shapes and data types using ``wp.types.matrix()``, for example: :: - - # declare a new 3x2 half precision float matrix type: - mat32h = wp.types.matrix(shape=(3,2), dtype=wp.float64) - - # create an array of this type - a = wp.zeros(10, dtype=mat32h) - -These can be used inside a kernel: :: - - @wp.kernel - def compute( ... ): - ... - - # initialize a mat32h matrix - m = mat32h(wp.float16(1.0), wp.float16(2.0), - wp.float16(3.0), wp.float16(4.0), - wp.float16(5.0), wp.float16(6.0)) - - # declare a 2 component half precision vector - v2 = wp.vec2h(wp.float16(1.0), wp.float16(1.0)) - - # multiply by the matrix, returning a 3 component vector: - v3 = m * v2 - ... - -It's also possible to directly create anonymously typed instances inside kernels where the type is inferred from constructor arguments as follows: :: - - @wp.kernel - def compute( ... ): - ... - - # create a 3x2 half precision matrix from components (row major ordering): - m = wp.matrix( - wp.float16(1.0), wp.float16(2.0), - wp.float16(1.0), wp.float16(2.0), - wp.float16(1.0), wp.float16(2.0), - shape=(3,2)) - - # zero initialize a 3x2 half precision matrix: - m = wp.matrix(wp.float16(0.0),shape=(3,2)) - - # create a 5x5 double precision identity matrix: - m = wp.identity(n=5, dtype=wp.float64) - -As with vectors, you can do standard matrix arithmetic with these variables, along with multiplying matrices with compatible shapes and potentially returning a matrix with a new shape. - -.. _quat: - -Quaternions -########### - -Warp supports quaternions with the layout ``i, j, k, w`` where ``w`` is the real part. Here are the built in concrete quaternion types: - -+-----------------+-----------------------------------------------+ -| quat | Default precision floating point quaternion | -+-----------------+-----------------------------------------------+ -| quatf | Single precision floating point quaternion | -+-----------------+-----------------------------------------------+ -| quatd | Double precision floating point quaternion | -+-----------------+-----------------------------------------------+ -| quath | Half precision floating point quaternion | -+-----------------+-----------------------------------------------+ - -Quaternions can be used to transform vectors as follows: :: - - @wp.kernel - def compute( ... ): - ... - - # construct a 30 degree rotation around the x-axis - q = wp.quat_from_axis_angle(wp.vec3(1.0, 0.0, 0.0), wp.degrees(30.0)) - - # rotate an axis by this quaternion - v = wp.quat_rotate(q, wp.vec3(0.0, 1.0, 0.0)) - - -As with vectors and matrices, you can declare quaternion types with an arbitrary numeric type like so: :: - - quatd = wp.types.quaternion(dtype=wp.float64) - -You can also create identity quaternion and anonymously typed instances inside a kernel like so: :: - - @wp.kernel - def compute( ... ): - ... - - # create a double precision identity quaternion: - qd = wp.quat_identity(dtype=wp.float64) - - # precision defaults to wp.float32 so this creates a single precision identity quaternion: - qf = wp.quat_identity() - - # create a half precision quaternion from components, or a vector/scalar: - qh = wp.quaternion(wp.float16(0.0), - wp.float16(0.0), - wp.float16(0.0), - wp.float16(1.0)) - - - qh = wp.quaternion( - wp.vector(wp.float16(0.0),wp.float16(0.0),wp.float16(0.0)), - wp.float16(1.0)) - -.. _transform: - -Transforms -########## - -Transforms are 7d vectors of floats representing a spatial rigid body transformation in format (p, q) where p is a 3d vector, and q is a quaternion. - -+-----------------+--------------------------------------------+ -| transform | Default precision floating point transform | -+-----------------+--------------------------------------------+ -| transformf | Single precision floating point transform | -+-----------------+--------------------------------------------+ -| transformd | Double precision floating point transform | -+-----------------+--------------------------------------------+ -| transformh | Half precision floating point transform | -+-----------------+--------------------------------------------+ - -Transforms can be constructed inside kernels from translation and rotation parts: :: - - @wp.kernel - def compute( ... ): - ... - - # create a transform from a vector/quaternion: - t = wp.transform( - wp.vec3(1.0, 2.0, 3.0), - wp.quat_from_axis_angle(0.0, 1.0, 0.0, wp.degrees(30.0))) - - # transform a point - p = wp.transform_point(t, wp.vec3(10.0, 0.5, 1.0)) - - # transform a vector (ignore translation) - p = wp.transform_vector(t, wp.vec3(10.0, 0.5, 1.0)) - - -As with vectors and matrices, you can declare transform types with an arbitrary numeric type using ``wp.types.transformation()``, for example: :: - - transformd = wp.types.transformation(dtype=wp.float64) - -You can also create identity transforms and anonymously typed instances inside a kernel like so: :: - - @wp.kernel - def compute( ... ): - - # create double precision identity transform: - qd = wp.transform_identity(dtype=wp.float64) - -Structs -####### - -Users can define custom structure types using the ``@wp.struct`` decorator as follows:: - - @wp.struct - class MyStruct: - - param1: int - param2: float - param3: wp.array(dtype=wp.vec3) - -Struct attributes must be annotated with their respective type. They can be constructed in Python scope and then passed to kernels as arguments:: - - @wp.kernel - def compute(args: MyStruct): - - tid = wp.tid() - - print(args.param1) - print(args.param2) - print(args.param3[tid]) - - # construct an instance of the struct in Python - s = MyStruct() - s.param1 = 10 - s.param2 = 2.5 - s.param3 = wp.zeros(shape=10, dtype=wp.vec3) - - # pass to our compute kernel - wp.launch(compute, dim=10, inputs=[s]) - -An array of structs can be zero-initialized as follows:: - - a = wp.zeros(shape=10, dtype=MyStruct) - -An array of structs can also be initialized from a list of struct objects:: - - a = wp.array([MyStruct(), MyStruct(), MyStruct()], dtype=MyStruct) - -Example: Using a custom struct in gradient computation -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -.. code:: python - - import numpy as np - - import warp as wp - - wp.init() - - - @wp.struct - class TestStruct: - x: wp.vec3 - a: wp.array(dtype=wp.vec3) - b: wp.array(dtype=wp.vec3) - - - @wp.kernel - def test_kernel(s: TestStruct): - tid = wp.tid() - - s.b[tid] = s.a[tid] + s.x - - - @wp.kernel - def loss_kernel(s: TestStruct, loss: wp.array(dtype=float)): - tid = wp.tid() - - v = s.b[tid] - wp.atomic_add(loss, 0, float(tid + 1) * (v[0] + 2.0 * v[1] + 3.0 * v[2])) - - - # create struct - ts = TestStruct() - - # set members - ts.x = wp.vec3(1.0, 2.0, 3.0) - ts.a = wp.array(np.array([[1.0, 2.0, 3.0], [4.0, 5.0, 6.0]]), dtype=wp.vec3, requires_grad=True) - ts.b = wp.zeros(2, dtype=wp.vec3, requires_grad=True) - - loss = wp.zeros(1, dtype=float, requires_grad=True) - - tape = wp.Tape() - with tape: - wp.launch(test_kernel, dim=2, inputs=[ts]) - wp.launch(loss_kernel, dim=2, inputs=[ts, loss]) - - tape.backward(loss) - - print(loss) - print(tape.gradients[ts].a) - - -Type Conversions -################ - -Warp is particularly strict regarding type conversions and does not perform *any* implicit conversion between numeric types. -The user is responsible for ensuring types for most arithmetic operators match, e.g.: ``x = float(0.0) + int(4)`` will result in an error. -This can be surprising for users that are accustomed to C-style conversions but avoids a class of common bugs that result from implicit conversions. - -.. note:: - Warp does not currently perform implicit type conversions between numeric types. - Users should explicitly cast variables to compatible types using constructors like - ``int()``, ``float()``, ``wp.float16()``, ``wp.uint8()``, etc. - -Constants ---------- - -In general, Warp kernels cannot access variables in the global Python interpreter state. One exception to this is for compile-time constants, which may be declared globally (or as class attributes) and folded into the kernel definition. - -Constants are defined using the ``wp.constant()`` function. An example is shown below:: - - TYPE_SPHERE = wp.constant(0) - TYPE_CUBE = wp.constant(1) - TYPE_CAPSULE = wp.constant(2) - - @wp.kernel - def collide(geometry: wp.array(dtype=int)): - - t = geometry[wp.tid()] - - if (t == TYPE_SPHERE): - print("sphere") - if (t == TYPE_CUBE): - print("cube") - if (t == TYPE_CAPSULE): - print("capsule") - - -.. autoclass:: constant - - -Operators ----------- - -Boolean Operators -################# - -+--------------+--------------------------------------+ -| a and b | True if a and b are True | -+--------------+--------------------------------------+ -| a or b | True if a or b is True | -+--------------+--------------------------------------+ -| not a | True if a is False, otherwise False | -+--------------+--------------------------------------+ - -.. note:: - Expressions such as ``if (a and b):`` currently do not perform short-circuit evaluation. - In this case ``b`` will also be evaluated even when ``a`` is ``False``. - Users should take care to ensure that secondary conditions are safe to evaluate (e.g.: do not index out of bounds) in all cases. - - -Comparison Operators -#################### - -+----------+---------------------------------------+ -| a > b | True if a strictly greater than b | -+----------+---------------------------------------+ -| a < b | True if a strictly less than b | -+----------+---------------------------------------+ -| a >= b | True if a greater than or equal to b | -+----------+---------------------------------------+ -| a <= b | True if a less than or equal to b | -+----------+---------------------------------------+ -| a == b | True if a equals b | -+----------+---------------------------------------+ -| a != b | True if a not equal to b | -+----------+---------------------------------------+ - -Arithmetic Operators -#################### - -+-----------+--------------------------+ -| a + b | Addition | -+-----------+--------------------------+ -| a - b | Subtraction | -+-----------+--------------------------+ -| a * b | Multiplication | -+-----------+--------------------------+ -| a / b | Floating point division | -+-----------+--------------------------+ -| a // b | Floored division | -+-----------+--------------------------+ -| a ** b | Exponentiation | -+-----------+--------------------------+ -| a % b | Modulus | -+-----------+--------------------------+ - -.. note:: - Since implicit conversions are not performed arguments types to operators should match. - Users should use type constructors, e.g.: ``float()``, ``int()``, ``wp.int64()``, etc. to cast variables - to the correct type. Also note that the multiplication expression ``a * b`` is used to represent scalar - multiplication and matrix multiplication. The ``@`` operator is not currently supported. - -Graphs ------------ - -Launching kernels from Python introduces significant additional overhead compared to C++ or native programs. -To address this, Warp exposes the concept of `CUDA graphs `_ -to allow recording large batches of kernels and replaying them with very little CPU overhead. - -To record a series of kernel launches use the :func:`wp.capture_begin() ` and -:func:`wp.capture_end() ` API as follows: - -.. code:: python - - # begin capture - wp.capture_begin() - - try: - # record launches - for i in range(100): - wp.launch(kernel=compute1, inputs=[a, b], device="cuda") - finally: - # end capture and return a graph object - graph = wp.capture_end() - -We strongly recommend the use of the the try-finally pattern when capturing graphs because -:func:`wp.capture_begin ` disables Python garbage collection so that Warp objects are not -garbage-collected during graph capture (CUDA does not allow memory to be deallocated during graph capture). -:func:`wp.capture_end ` reenables garbage collection. - -Once a graph has been constructed it can be executed: :: - - wp.capture_launch(graph) - -Note that only launch calls are recorded in the graph, any Python executed outside of the kernel code will not be recorded. -Typically it is only beneficial to use CUDA graphs when the graph will be reused or launched multiple times. - -.. autofunction:: capture_begin -.. autofunction:: capture_end -.. autofunction:: capture_launch - -Bounding Value Hierarchies (BVH) --------------------------------- - -The :class:`wp.Bvh ` class can be used to create a BVH for a group of bounding volumes. This object can then be traversed -to determine which parts are intersected by a ray using :func:`bvh_query_ray` and which parts are fully contained -within a certain bounding volume using :func:`bvh_query_aabb`. - -The following snippet demonstrates how to create a :class:`wp.Bvh ` object from 100 random bounding volumes: - -.. code:: python - - rng = np.random.default_rng(123) - - num_bounds = 100 - lowers = rng.random(size=(num_bounds, 3)) * 5.0 - uppers = lowers + rng.random(size=(num_bounds, 3)) * 5.0 - - device_lowers = wp.array(lowers, dtype=wp.vec3, device="cuda:0") - device_uppers = wp.array(uppers, dtype=wp.vec3, device="cuda:0") - - bvh = wp.Bvh(device_lowers, device_uppers) - -.. autoclass:: Bvh - :members: - -Example: BVH Ray Traversal -########################## - -An example of performing a ray traversal on the data structure is as follows: - -.. code:: python - - @wp.kernel - def bvh_query_ray( - bvh_id: wp.uint64, - start: wp.vec3, - dir: wp.vec3, - bounds_intersected: wp.array(dtype=wp.bool), - ): - query = wp.bvh_query_ray(bvh_id, start, dir) - bounds_nr = wp.int32(0) - - while wp.bvh_query_next(query, bounds_nr): - # The ray intersects the volume with index bounds_nr - bounds_intersected[bounds_nr] = True - - - bounds_intersected = wp.zeros(shape=(num_bounds), dtype=wp.bool, device="cuda:0") - query_start = wp.vec3(0.0, 0.0, 0.0) - query_dir = wp.normalize(wp.vec3(1.0, 1.0, 1.0)) - - wp.launch( - kernel=bvh_query_ray, - dim=1, - inputs=[bvh.id, query_start, query_dir, bounds_intersected], - device="cuda:0", - ) - -The Warp kernel ``bvh_query_ray`` is launched with a single thread, provided the unique :class:`uint64` -identifier of the :class:`wp.Bvh ` object, parameters describing the ray, and an array to store the results. -In ``bvh_query_ray``, :func:`wp.bvh_query_ray() ` is called once to obtain an object that is stored in the -variable ``query``. An integer is also allocated as ``bounds_nr`` to store the volume index of the traversal. -A while statement is used for the actual traversal using :func:`wp.bvh_query_next() `, -which returns ``True`` as long as there are intersecting bounds. - -Example: BVH Volume Traversal -############################# - -Similar to the ray-traversal example, we can perform volume traversal to find the volumes that are fully contained -within a specified bounding box. - -.. code:: python - - @wp.kernel - def bvh_query_aabb( - bvh_id: wp.uint64, - lower: wp.vec3, - upper: wp.vec3, - bounds_intersected: wp.array(dtype=wp.bool), - ): - query = wp.bvh_query_aabb(bvh_id, lower, upper) - bounds_nr = wp.int32(0) - - while wp.bvh_query_next(query, bounds_nr): - # The volume with index bounds_nr is fully contained - # in the (lower,upper) bounding box - bounds_intersected[bounds_nr] = True - - - bounds_intersected = wp.zeros(shape=(num_bounds), dtype=wp.bool, device="cuda:0") - query_lower = wp.vec3(4.0, 4.0, 4.0) - query_upper = wp.vec3(6.0, 6.0, 6.0) - - wp.launch( - kernel=bvh_query_aabb, - dim=1, - inputs=[bvh.id, query_lower, query_upper, bounds_intersected], - device="cuda:0", - ) - -The kernel is nearly identical to the ray-traversal example, except we obtain ``query`` using -:func:`wp.bvh_query_aabb() `. - -Meshes ------- - -Warp provides a ``wp.Mesh`` class to manage triangle mesh data. To create a mesh users provide a points, indices and optionally a velocity array:: - - mesh = wp.Mesh(points, indices, velocities) - -.. note:: - Mesh objects maintain references to their input geometry buffers. All buffers should live on the same device. - -Meshes can be passed to kernels using their ``id`` attribute which uniquely identifies the mesh by a unique ``uint64`` value. -Once inside a kernel you can perform geometric queries against the mesh such as ray-casts or closest point lookups:: - - @wp.kernel - def raycast(mesh: wp.uint64, - ray_origin: wp.array(dtype=wp.vec3), - ray_dir: wp.array(dtype=wp.vec3), - ray_hit: wp.array(dtype=wp.vec3)): - - tid = wp.tid() - - t = float(0.0) # hit distance along ray - u = float(0.0) # hit face barycentric u - v = float(0.0) # hit face barycentric v - sign = float(0.0) # hit face sign - n = wp.vec3() # hit face normal - f = int(0) # hit face index - - color = wp.vec3() - - # ray cast against the mesh - if wp.mesh_query_ray(mesh, ray_origin[tid], ray_dir[tid], 1.e+6, t, u, v, sign, n, f): - - # if we got a hit then set color to the face normal - color = n*0.5 + wp.vec3(0.5, 0.5, 0.5) - - ray_hit[tid] = color - - -Users may update mesh vertex positions at runtime simply by modifying the points buffer. -After modifying point locations users should call ``Mesh.refit()`` to rebuild the bounding volume hierarchy (BVH) structure and ensure that queries work correctly. - -.. note:: - Updating Mesh topology (indices) at runtime is not currently supported. Users should instead recreate a new Mesh object. - -.. autoclass:: Mesh - :members: - -Hash Grids ----------- - -Many particle-based simulation methods such as the Discrete Element Method (DEM), or Smoothed Particle Hydrodynamics (SPH), involve iterating over spatial neighbors to compute force interactions. Hash grids are a well-established data structure to accelerate these nearest neighbor queries, and particularly well-suited to the GPU. - -To support spatial neighbor queries Warp provides a ``HashGrid`` object that may be created as follows:: - - grid = wp.HashGrid(dim_x=128, dim_y=128, dim_z=128, device="cuda") - - grid.build(points=p, radius=r) - -``p`` is an array of ``wp.vec3`` point positions, and ``r`` is the radius to use when building the grid. -Neighbors can then be iterated over inside the kernel code using :func:`wp.hash_grid_query() ` -and :func:`wp.hash_grid_query_next() ` as follows: - -.. code:: python - - @wp.kernel - def sum(grid : wp.uint64, - points: wp.array(dtype=wp.vec3), - output: wp.array(dtype=wp.vec3), - radius: float): - - tid = wp.tid() - - # query point - p = points[tid] - - # create grid query around point - query = wp.hash_grid_query(grid, p, radius) - index = int(0) - - sum = wp.vec3() - - while(wp.hash_grid_query_next(query, index)): - - neighbor = points[index] - - # compute distance to neighbor point - dist = wp.length(p-neighbor) - if (dist <= radius): - sum += neighbor - - output[tid] = sum - -.. note:: - The ``HashGrid`` query will give back all points in *cells* that fall inside the query radius. - When there are hash conflicts it means that some points outside of query radius will be returned, and users should - check the distance themselves inside their kernels. The reason the query doesn't do the check itself for each - returned point is because it's common for kernels to compute the distance themselves, so it would redundant to - check/compute the distance twice. - - -.. autoclass:: HashGrid - :members: - -Volumes -------- - -Sparse volumes are incredibly useful for representing grid data over large domains, such as signed distance fields -(SDFs) for complex objects, or velocities for large-scale fluid flow. Warp supports reading sparse volumetric grids -stored using the `NanoVDB `_ standard. Users can access voxels directly -or use built-in closest-point or trilinear interpolation to sample grid data from world or local space. - -Volume objects can be created directly from Warp arrays containing a NanoVDB grid, from the contents of a -standard ``.nvdb`` file using :func:`load_from_nvdb() `, -or from a dense 3D NumPy array using :func:`load_from_numpy() `. - -Volumes can also be created using :func:`allocate() ` or -:func:`allocate_by_tiles() `. The values for a Volume object can be modified in a Warp -kernel using :func:`wp.volume_store_f() `, :func:`wp.volume_store_v() `, and -:func:`wp.volume_store_i() `. - -.. note:: - Warp does not currently support modifying the topology of sparse volumes at runtime. - -Below we give an example of creating a Volume object from an existing NanoVDB file:: - - # open NanoVDB file on disk - file = open("mygrid.nvdb", "rb") - - # create Volume object - volume = wp.Volume.load_from_nvdb(file, device="cpu") - -.. note:: - Files written by the NanoVDB library, commonly marked by the ``.nvdb`` extension, can contain multiple grids with - various compression methods, but a :class:`Volume` object represents a single NanoVDB grid therefore only files with - a single grid are supported. NanoVDB's uncompressed and zip-compressed file formats are supported. - -To sample the volume inside a kernel we pass a reference to it by ID, and use the built-in sampling modes:: - - @wp.kernel - def sample_grid(volume: wp.uint64, - points: wp.array(dtype=wp.vec3), - samples: wp.array(dtype=float)): - - tid = wp.tid() - - # load sample point in world-space - p = points[tid] - - # transform position to the volume's local-space - q = wp.volume_world_to_index(volume, p) - - # sample volume with trilinear interpolation - f = wp.volume_sample_f(volume, q, wp.Volume.LINEAR) - - # write result - samples[tid] = f - -.. autoclass:: Volume - :members: - :undoc-members: - -.. seealso:: `Reference `__ for the volume functions available in kernels. - -Differentiability ------------------ - -By default, Warp generates a forward and backward (adjoint) version of each kernel definition. -Buffers that participate in the chain of computation should be created with ``requires_grad=True``, for example:: - - a = wp.zeros(1024, dtype=wp.vec3, device="cuda", requires_grad=True) - -The ``wp.Tape`` class can then be used to record kernel launches, and replay them to compute the gradient of a scalar loss function with respect to the kernel inputs:: - - tape = wp.Tape() - - # forward pass - with tape: - wp.launch(kernel=compute1, inputs=[a, b], device="cuda") - wp.launch(kernel=compute2, inputs=[c, d], device="cuda") - wp.launch(kernel=loss, inputs=[d, l], device="cuda") - - # reverse pass - tape.backward(l) - -After the backward pass has completed, the gradients with respect to the inputs are available via a mapping in the :class:`wp.Tape ` object:: - - # gradient of loss with respect to input a - print(tape.gradients[a]) - -Note that gradients are accumulated on the participating buffers, so if you wish to reuse the same buffers for multiple backward passes you should first zero the gradients:: - - tape.zero() - -.. note:: - - Warp uses a source-code transformation approach to auto-differentiation. - In this approach, the backwards pass must keep a record of intermediate values computed during the forward pass. - This imposes some restrictions on what kernels can do and still be differentiable: - - * Dynamic loops should not mutate any previously declared local variable. This means the loop must be side-effect free. - A simple way to ensure this is to move the loop body into a separate function. - Static loops that are unrolled at compile time do not have this restriction and can perform any computation. - - * Kernels should not overwrite any previously used array values except to perform simple linear add/subtract operations (e.g. via :func:`wp.atomic_add() `) - -.. autoclass:: Tape - :members: - -Jacobians -######### - -To compute the Jacobian matrix :math:`J\in\mathbb{R}^{m\times n}` of a multi-valued function :math:`f: \mathbb{R}^n \to \mathbb{R}^m`, we can evaluate an entire row of the Jacobian in parallel by finding the Jacobian-vector product :math:`J^\top \mathbf{e}`. The vector :math:`\mathbf{e}\in\mathbb{R}^m` selects the indices in the output buffer to differentiate with respect to. -In Warp, instead of passing a scalar loss buffer to the ``tape.backward()`` method, we pass a dictionary ``grads`` mapping from the function output array to the selection vector :math:`\mathbf{e}` having the same type:: - - # compute the Jacobian for a function of single output - jacobian = np.empty((output_dim, input_dim), dtype=np.float32) - tape = wp.Tape() - with tape: - output_buffer = launch_kernels_to_be_differentiated(input_buffer) - for output_index in range(output_dim): - # select which row of the Jacobian we want to compute - select_index = np.zeros(output_dim) - select_index[output_index] = 1.0 - e = wp.array(select_index, dtype=wp.float32) - # pass input gradients to the output buffer to apply selection - tape.backward(grads={output_buffer: e}) - q_grad_i = tape.gradients[input_buffer] - jacobian[output_index, :] = q_grad_i.numpy() - tape.zero() - -When we run simulations independently in parallel, the Jacobian corresponding to the entire system dynamics is a block-diagonal matrix. In this case, we can compute the Jacobian in parallel for all environments by choosing a selection vector that has the output indices active for all environment copies. For example, to get the first rows of the Jacobians of all environments, :math:`\mathbf{e}=[\begin{smallmatrix}1 & 0 & 0 & \dots & 1 & 0 & 0 & \dots\end{smallmatrix}]^\top`, to compute the second rows, :math:`\mathbf{e}=[\begin{smallmatrix}0 & 1 & 0 & \dots & 0 & 1 & 0 & \dots\end{smallmatrix}]^\top`, etc.:: - - # compute the Jacobian for a function over multiple environments in parallel - jacobians = np.empty((num_envs, output_dim, input_dim), dtype=np.float32) - tape = wp.Tape() - with tape: - output_buffer = launch_kernels_to_be_differentiated(input_buffer) - for output_index in range(output_dim): - # select which row of the Jacobian we want to compute - select_index = np.zeros(output_dim) - select_index[output_index] = 1.0 - # assemble selection vector for all environments (can be precomputed) - e = wp.array(np.tile(select_index, num_envs), dtype=wp.float32) - tape.backward(grads={output_buffer: e}) - q_grad_i = tape.gradients[input_buffer] - jacobians[:, output_index, :] = q_grad_i.numpy().reshape(num_envs, input_dim) - tape.zero() - - -Custom Gradient Functions -######################### - -Warp supports custom gradient function definitions for user-defined Warp functions. -This allows users to define code that should replace the automatically generated derivatives. - -To differentiate a function :math:`h(x) = f(g(x))` that has a nested call to function :math:`g(x)`, the chain rule is evaluated in the automatic differentiation of :math:`h(x)`: - -.. math:: - - h^\prime(x) = f^\prime({\color{green}{\underset{\textrm{replay}}{g(x)}}}) {\color{blue}{\underset{\textrm{grad}}{g^\prime(x)}}} - -This implies that a function to be compatible with the autodiff engine needs to provide an implementation of its forward version -:math:`\color{green}{g(x)}`, which we refer to as "replay" function (that matches the original function definition by default), -and its derivative :math:`\color{blue}{g^\prime(x)}`, referred to as "grad". - -Both the replay and the grad implementations can be customized by the user. They are defined as follows: - -.. list-table:: Customizing the replay and grad versions of function ``myfunc`` - :widths: 100 - :header-rows: 0 - - * - Forward Function - * - .. code-block:: python - - @wp.func - def myfunc(in1: InType1, ..., inN: InTypeN) -> OutType1, ..., OutTypeM: - return out1, ..., outM - - * - Custom Replay Function - * - .. code-block:: python - - @wp.func_replay(myfunc) - def replay_myfunc(in1: InType1, ..., inN: InTypeN) -> OutType1, ..., OutTypeM: - # Custom forward computations to be executed in the backward pass of a - # function calling `myfunc` go here - # Ensure the output variables match the original forward definition - return out1, ..., outM - - * - Custom Grad Function - * - .. code-block:: python - - @wp.func_grad(myfunc) - def adj_myfunc(in1: InType1, ..., inN: InTypeN, adj_out1: OutType1, ..., adj_outM: OutTypeM): - # Custom adjoint code goes here - # Update the partial derivatives for the inputs as follows: - wp.adjoint[in1] += ... - ... - wp.adjoint[inN] += ... - -.. note:: It is currently not possible to define custom replay or grad functions for functions that - have generic arguments, e.g. ``Any`` or ``wp.array(dtype=Any)``. Replay or grad functions that - themselves use generic arguments are also not yet supported. - -Example 1: Custom Grad Function -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -In the following, we define a Warp function ``safe_sqrt`` that computes the square root of a number:: - - @wp.func - def safe_sqrt(x: float): - return wp.sqrt(x) - -To evaluate this function, we define a kernel that applies ``safe_sqrt`` to an array of input values:: - - @wp.kernel - def run_safe_sqrt(xs: wp.array(dtype=float), output: wp.array(dtype=float)): - i = wp.tid() - output[i] = safe_sqrt(xs[i]) - -Calling the kernel for an array of values ``[1.0, 2.0, 0.0]`` yields the expected outputs, the gradients are finite except for the zero input:: - - xs = wp.array([1.0, 2.0, 0.0], dtype=wp.float32, requires_grad=True) - ys = wp.zeros_like(xs) - tape = wp.Tape() - with tape: - wp.launch(run_safe_sqrt, dim=len(xs), inputs=[xs], outputs=[ys]) - tape.backward(grads={ys: wp.array(np.ones(len(xs)), dtype=wp.float32)}) - print("ys ", ys) - print("xs.grad", xs.grad) - - # ys [1. 1.4142135 0. ] - # xs.grad [0.5 0.35355338 inf] - -It is often desired to catch nonfinite gradients in the computation graph as they may cause the entire gradient computation to be nonfinite. -To do so, we can define a custom gradient function that replaces the adjoint function for ``safe_sqrt`` which is automatically generated by -decorating the custom gradient code via ``@wp.func_grad(safe_sqrt)``:: - - @wp.func_grad(safe_sqrt) - def adj_safe_sqrt(x: float, adj_ret: float): - if x > 0.0: - wp.adjoint[x] += 1.0 / (2.0 * wp.sqrt(x)) * adj_ret - -.. note:: The function signature of the custom grad code consists of the input arguments of the forward function plus the adjoint variables of the - forward function outputs. To access and modify the partial derivatives of the input arguments, we use the ``wp.adjoint`` dictionary. - The keys of this dictionary are the input arguments of the forward function, and the values are the partial derivatives of the forward function - output with respect to the input argument. - - -Example 2: Custom Replay Function -^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ - -In the following, we increment an array index in each thread via :func:`wp.atomic_add() ` and compute -the square root of an input array at the incremented index:: - - @wp.kernel - def test_add(counter: wp.array(dtype=int), input: wp.array(dtype=float), output: wp.array(dtype=float)): - idx = wp.atomic_add(counter, 0, 1) - output[idx] = wp.sqrt(input[idx]) - - def main(): - dim = 16 - use_reversible_increment = False - input = wp.array(np.arange(1, dim + 1), dtype=wp.float32, requires_grad=True) - counter = wp.zeros(1, dtype=wp.int32) - thread_ids = wp.zeros(dim, dtype=wp.int32) - output = wp.zeros(dim, dtype=wp.float32, requires_grad=True) - tape = wp.Tape() - with tape: - if use_reversible_increment: - wp.launch(test_add_diff, dim, inputs=[counter, thread_ids, input], outputs=[output]) - else: - wp.launch(test_add, dim, inputs=[counter, input], outputs=[output]) - - print("counter: ", counter.numpy()) - print("thread_ids: ", thread_ids.numpy()) - print("input: ", input.numpy()) - print("output: ", output.numpy()) - - tape.backward(grads={ - output: wp.array(np.ones(dim), dtype=wp.float32) - }) - print("input.grad: ", input.grad.numpy()) - - if __name__ == "__main__": - main() - -The output of the above code is: - -.. code-block:: js - - counter: [8] - thread_ids: [0 0 0 0 0 0 0 0] - input: [1. 2. 3. 4. 5. 6. 7. 8.] - output: [1. 1.4142135 1.7320508 2. 2.236068 2.4494898 2.6457512 2.828427] - input.grad: [4. 0. 0. 0. 0. 0. 0. 0.] - -The gradient of the input is incorrect because the backward pass involving the atomic operation ``wp.atomic_add()`` does not know which thread ID corresponds -to which input value. -The index returned by the adjoint of ``wp.atomic_add()`` is always zero so that the gradient the first entry of the input array, -i.e. :math:`\frac{1}{2\sqrt{1}} = 0.5`, is accumulated ``dim`` times (hence ``input.grad[0] == 4.0`` and all other entries zero). - -To fix this, we define a new Warp function ``reversible_increment()`` with a custom *replay* definition that stores the thread ID in a separate array:: - - @wp.func - def reversible_increment( - buf: wp.array(dtype=int), - buf_index: int, - value: int, - thread_values: wp.array(dtype=int), - tid: int - ): - next_index = wp.atomic_add(buf, buf_index, value) - # store which thread ID corresponds to which index for the backward pass - thread_values[tid] = next_index - return next_index - - - @wp.func_replay(reversible_increment) - def replay_reversible_increment( - buf: wp.array(dtype=int), - buf_index: int, - value: int, - thread_values: wp.array(dtype=int), - tid: int - ): - return thread_values[tid] - - -Instead of running ``reversible_increment()``, the custom replay code in ``replay_reversible_increment()`` is now executed -during forward phase in the backward pass of the function calling ``reversible_increment()``. -We first stored the array index to each thread ID in the forward pass, and now we retrieve the array index for each thread ID in the backward pass. -That way, the backward pass can reproduce the same addition operation as in the forward pass with exactly the same operands per thread. - -.. warning:: The function signature of the custom replay code must match the forward function signature. - -To use our function we write the following kernel:: - - @wp.kernel - def test_add_diff( - counter: wp.array(dtype=int), - thread_ids: wp.array(dtype=int), - input: wp.array(dtype=float), - output: wp.array(dtype=float) - ): - tid = wp.tid() - idx = reversible_increment(counter, 0, 1, thread_ids, tid) - output[idx] = wp.sqrt(input[idx]) - -Running the ``test_add_diff`` kernel via the previous ``main`` function with ``use_reversible_increment = True``, we now compute correct gradients -for the input array: - -.. code-block:: js - - counter: [8] - thread_ids: [0 1 2 3 4 5 6 7] - input: [1. 2. 3. 4. 5. 6. 7. 8.] - output: [1. 1.4142135 1.7320508 2. 2.236068 2.4494898 2.6457512 2.828427 ] - input.grad: [0.5 0.35355338 0.28867513 0.25 0.2236068 0.20412414 0.18898225 0.17677669] - -Custom Native Functions ------------------------ - -Users may insert native C++/CUDA code in Warp kernels using ``@func_native`` decorated functions. -These accept native code as strings that get compiled after code generation, and are called within ``@wp.kernel`` functions. -For example:: - - snippet = """ - __shared__ int s[128]; - - s[tid] = d[tid]; - __syncthreads(); - d[tid] = s[N - tid - 1]; - """ - - @wp.func_native(snippet) - def reverse(d: wp.array(dtype=int), N: int, tid: int): - ... - - @wp.kernel - def reverse_kernel(d: wp.array(dtype=int), N: int): - tid = wp.tid() - reverse(d, N, tid) - - N = 128 - x = wp.array(np.arange(N, dtype=int), dtype=int, device=device) - - wp.launch(kernel=reverse_kernel, dim=N, inputs=[x, N], device=device) - -Notice the use of shared memory here: the Warp library does not expose shared memory as a feature, but the CUDA compiler will -readily accept the above snippet. This means CUDA features not exposed in Warp are still accessible in Warp scripts. -Warp kernels meant for the CPU won't be able to leverage CUDA features of course, but this same mechanism supports pure C++ snippets as well. - -Please bear in mind the following: the thread index in your snippet should be computed in a ``@wp.kernel`` and passed to your snippet, -as in the above example. This means your ``@wp.func_native`` function signature should include the variables used in your snippet, -as well as a thread index of type ``int``. The function body itself should be stubbed with ``...`` (the snippet will be inserted during compilation). - -Should you wish to record your native function on the tape and then subsequently rewind the tape, you must include an adjoint snippet -alongside your snippet as an additional input to the decorator, as in the following example:: - - snippet = """ - out[tid] = a * x[tid] + y[tid]; - """ - adj_snippet = """ - adj_a = x[tid] * adj_out[tid]; - adj_x[tid] = a * adj_out[tid]; - adj_y[tid] = adj_out[tid]; - """ - - @wp.func_native(snippet, adj_snippet) - def saxpy( - a: wp.float32, - x: wp.array(dtype=wp.float32), - y: wp.array(dtype=wp.float32), - out: wp.array(dtype=wp.float32), - tid: int, - ): - ... - - @wp.kernel - def saxpy_kernel( - a: wp.float32, - x: wp.array(dtype=wp.float32), - y: wp.array(dtype=wp.float32), - out: wp.array(dtype=wp.float32) - ): - tid = wp.tid() - saxpy(a, x, y, out, tid) - - N = 128 - a = 2.0 - x = wp.array(np.arange(N, dtype=np.float32), dtype=wp.float32, device=device, requires_grad=True) - y = wp.zeros_like(x1) - out = wp.array(np.arange(N, dtype=np.float32), dtype=wp.float32, device=device) - adj_out = wp.array(np.ones(N, dtype=np.float32), dtype=wp.float32, device=device) - - tape = wp.Tape() - - with tape: - wp.launch(kernel=saxpy_kernel, dim=N, inputs=[a, x, y], outputs=[out], device=device) - - tape.backward(grads={out: adj_out}) - -Profiling ---------- - -``wp.ScopedTimer`` objects can be used to gain some basic insight into the performance of Warp applications: - -.. code:: python - - with wp.ScopedTimer("grid build"): - self.grid.build(self.x, self.point_radius) - -This results in a printout at runtime to the standard output stream like: - -.. code:: console - - grid build took 0.06 ms - -The ``wp.ScopedTimer`` object does not synchronize (e.g. by calling ``wp.synchronize()``) -upon exiting the ``with`` statement, so this can lead to misleading numbers if the body -of the ``with`` statement launches device kernels. - -When a ``wp.ScopedTimer`` object is passed ``use_nvtx=True`` as an argument, the timing functionality is replaced by calls -to ``nvtx.start_range()`` and ``nvtx.end_range()``: - -.. code:: python - - with wp.ScopedTimer("grid build", use_nvtx=True, color="cyan"): - self.grid.build(self.x, self.point_radius) - -These range annotations can then be collected by a tool like `NVIDIA Nsight Systems `_ -for visualization on a timeline, e.g.: - -.. code:: console - - $ nsys profile python warp_application.py - -This code snippet also demonstrates the use of the ``color`` argument to specify a color -for the range, which may be a number representing the ARGB value or a recognized string -(refer to `colors.py `_ for -additional color examples). -The `nvtx module `_ must be -installed in the Python environment for this capability to work. -An equivalent way to create an NVTX range without using ``wp.ScopedTimer`` is: - -.. code:: python - - import nvtx - - with nvtx.annotate("grid build", color="cyan"): - self.grid.build(self.x, self.point_radius) - -This form may be more convenient if the user does not need to frequently switch -between timer and NVTX capabilities of ``wp.ScopedTimer``. - -.. autoclass:: warp.ScopedTimer diff --git a/docs/_build/html/_sources/modules/sim.rst.txt b/docs/_build/html/_sources/modules/sim.rst.txt deleted file mode 100644 index bec52af0b..000000000 --- a/docs/_build/html/_sources/modules/sim.rst.txt +++ /dev/null @@ -1,157 +0,0 @@ -warp.sim -==================== - -.. currentmodule:: warp.sim - -.. - .. toctree:: - :maxdepth: 2 - -Warp includes a simulation module ``warp.sim`` that includes many common physical simulation models, and integrators for explicit and implicit time-stepping. - -.. note:: The simulation model is under construction and should be expected to change rapidly, please treat this section as work in progress. - - -Model ------ - -.. autoclass:: ModelBuilder - :members: - -.. autoclass:: Model - :members: - -.. autoclass:: JointAxis - :members: - -.. autoclass:: Mesh - :members: - -.. autoclass:: SDF - :members: - -.. _Joint types: - -Joint types -^^^^^^^^^^^^^^ - -.. data:: JOINT_PRISMATIC - - Prismatic (slider) joint - -.. data:: JOINT_REVOLUTE - - Revolute (hinge) joint - -.. data:: JOINT_BALL - - Ball (spherical) joint with quaternion state representation - -.. data:: JOINT_FIXED - - Fixed (static) joint - -.. data:: JOINT_FREE - - Free (floating) joint - -.. data:: JOINT_COMPOUND - - Compound joint with 3 rotational degrees of freedom - -.. data:: JOINT_UNIVERSAL - - Universal joint with 2 rotational degrees of freedom - -.. data:: JOINT_DISTANCE - - Distance joint that keeps two bodies at a distance within its joint limits (only supported in :class:`XPBDIntegrator` at the moment) - -.. data:: JOINT_D6 - - Generic D6 joint with up to 3 translational and 3 rotational degrees of freedom - -.. _Joint modes: - -Joint modes -^^^^^^^^^^^^^^ - -Joint modes control the behavior of joint axes and can be used to implement joint position or velocity drives. - -.. data:: JOINT_MODE_LIMIT - - No target or velocity control is applied, the joint is limited to its joint limits - -.. data:: JOINT_MODE_TARGET_POSITION - - The joint is driven to a target position - -.. data:: JOINT_MODE_TARGET_VELOCITY - - The joint is driven to a target velocity - -State --------------- - -.. autoclass:: State - :members: - -.. _FK-IK: - -Forward / Inverse Kinematics ----------------------------- - -Articulated rigid-body mechanisms are kinematically described by the joints that connect the bodies as well as the relative relative transform from the parent and child body to the respective anchor frames of the joint in the parent and child body: - -.. image:: /img/joint_transforms.png - :width: 400 - :align: center - -.. list-table:: Variable names in the kernels from articulation.py - :widths: 10 90 - :header-rows: 1 - - * - Symbol - - Description - * - x_wp - - World transform of the parent body (stored at :attr:`State.body_q`) - * - x_wc - - World transform of the child body (stored at :attr:`State.body_q`) - * - x_pj - - Transform from the parent body to the joint parent anchor frame (defined by :attr:`Model.joint_X_p`) - * - x_cj - - Transform from the child body to the joint child anchor frame (defined by :attr:`Model.joint_X_c`) - * - x_j - - Joint transform from the joint parent anchor frame to the joint child anchor frame - -In the forward kinematics, the joint transform is determined by the joint coordinates (generalized joint positions :attr:`State.body_q` and velocities :attr:`State.body_qd`). -Given the parent body's world transform :math:`x_{wp}` and the joint transform :math:`x_{j}`, the child body's world transform :math:`x_{wc}` is computed as: - -.. math:: - x_{wc} = x_{wp} \cdot x_{pj} \cdot x_{j} \cdot x_{cj}^{-1}. - -.. autofunction:: eval_fk - -.. autofunction:: eval_ik - -Integrators --------------- - -.. autoclass:: SemiImplicitIntegrator - :members: - -.. autoclass:: XPBDIntegrator - :members: - -Importers --------------- - -Warp sim supports the loading of simulation models from URDF, MuJoCo (MJCF), and USD Physics files. - -.. autofunction:: parse_urdf - -.. autofunction:: parse_mjcf - -.. autofunction:: parse_usd - -.. autofunction:: resolve_usd_from_url \ No newline at end of file diff --git a/docs/_build/html/_sources/modules/sparse.rst.txt b/docs/_build/html/_sources/modules/sparse.rst.txt deleted file mode 100644 index 42fb05ba1..000000000 --- a/docs/_build/html/_sources/modules/sparse.rst.txt +++ /dev/null @@ -1,19 +0,0 @@ -warp.sparse -=============================== - -.. currentmodule:: warp.sparse - -.. - .. toctree:: - :maxdepth: 2 - -Warp includes a sparse linear algebra module ``warp.sparse`` that implements some common operations for manipulating sparse matrices that arise in simulation. - -Sparse Matrices -------------------------- - -Currently `warp.sparse` supports Block Sparse Row (BSR) matrices, the BSR format can also be used to represent Compressed Sparse Row (CSR) matrices as a special case with a 1x1 block size. - -.. automodule:: warp.sparse - :members: - diff --git a/docs/_build/html/_static/basic.css b/docs/_build/html/_static/basic.css deleted file mode 100644 index 30fee9d0f..000000000 --- a/docs/_build/html/_static/basic.css +++ /dev/null @@ -1,925 +0,0 @@ -/* - * basic.css - * ~~~~~~~~~ - * - * Sphinx stylesheet -- basic theme. - * - * :copyright: Copyright 2007-2023 by the Sphinx team, see AUTHORS. - * :license: BSD, see LICENSE for details. - * - */ - -/* -- main layout ----------------------------------------------------------- */ - -div.clearer { - clear: both; -} - -div.section::after { - display: block; - content: ''; - clear: left; -} - -/* -- relbar ---------------------------------------------------------------- */ - -div.related { - width: 100%; - font-size: 90%; -} - -div.related h3 { - display: none; -} - -div.related ul { - margin: 0; - padding: 0 0 0 10px; - list-style: none; -} - -div.related li { - display: inline; -} - -div.related li.right { - float: right; - margin-right: 5px; -} - -/* -- sidebar --------------------------------------------------------------- */ - -div.sphinxsidebarwrapper { - padding: 10px 5px 0 10px; -} - -div.sphinxsidebar { - float: left; - width: 230px; - margin-left: -100%; - font-size: 90%; - word-wrap: break-word; - overflow-wrap : break-word; -} - -div.sphinxsidebar ul { - list-style: none; -} - -div.sphinxsidebar ul ul, -div.sphinxsidebar ul.want-points { - margin-left: 20px; - list-style: square; -} - -div.sphinxsidebar ul ul { - margin-top: 0; - margin-bottom: 0; -} - -div.sphinxsidebar form { - margin-top: 10px; -} - -div.sphinxsidebar input { - border: 1px solid #98dbcc; - font-family: sans-serif; - font-size: 1em; -} - -div.sphinxsidebar #searchbox form.search { - overflow: hidden; -} - -div.sphinxsidebar #searchbox input[type="text"] { - float: left; - width: 80%; - padding: 0.25em; - box-sizing: border-box; -} - -div.sphinxsidebar #searchbox input[type="submit"] { - float: left; - width: 20%; - border-left: none; - padding: 0.25em; - box-sizing: border-box; -} - - -img { - border: 0; - max-width: 100%; -} - -/* -- search page ----------------------------------------------------------- */ - -ul.search { - margin: 10px 0 0 20px; - padding: 0; -} - -ul.search li { - padding: 5px 0 5px 20px; - background-image: url(file.png); - background-repeat: no-repeat; - background-position: 0 7px; -} - -ul.search li a { - font-weight: bold; -} - -ul.search li p.context { - color: #888; - margin: 2px 0 0 30px; - text-align: left; -} - -ul.keywordmatches li.goodmatch a { - font-weight: bold; -} - -/* -- index page ------------------------------------------------------------ */ - -table.contentstable { - width: 90%; - margin-left: auto; - margin-right: auto; -} - -table.contentstable p.biglink { - line-height: 150%; -} - -a.biglink { - font-size: 1.3em; -} - -span.linkdescr { - font-style: italic; - padding-top: 5px; - font-size: 90%; -} - -/* -- general index --------------------------------------------------------- */ - -table.indextable { - width: 100%; -} - -table.indextable td { - text-align: left; - vertical-align: top; -} - -table.indextable ul { - margin-top: 0; - margin-bottom: 0; - list-style-type: none; -} - -table.indextable > tbody > tr > td > ul { - padding-left: 0em; -} - -table.indextable tr.pcap { - height: 10px; -} - -table.indextable tr.cap { - margin-top: 10px; - background-color: #f2f2f2; -} - -img.toggler { - margin-right: 3px; - margin-top: 3px; - cursor: pointer; -} - -div.modindex-jumpbox { - border-top: 1px solid #ddd; - border-bottom: 1px solid #ddd; - margin: 1em 0 1em 0; - padding: 0.4em; -} - -div.genindex-jumpbox { - border-top: 1px solid #ddd; - border-bottom: 1px solid #ddd; - margin: 1em 0 1em 0; - padding: 0.4em; -} - -/* -- domain module index --------------------------------------------------- */ - -table.modindextable td { - padding: 2px; - border-collapse: collapse; -} - -/* -- general body styles --------------------------------------------------- */ - -div.body { - min-width: 360px; - max-width: 800px; -} - -div.body p, div.body dd, div.body li, div.body blockquote { - -moz-hyphens: auto; - -ms-hyphens: auto; - -webkit-hyphens: auto; - hyphens: auto; -} - -a.headerlink { - visibility: hidden; -} - -a:visited { - color: #551A8B; -} - -h1:hover > a.headerlink, -h2:hover > a.headerlink, -h3:hover > a.headerlink, -h4:hover > a.headerlink, -h5:hover > a.headerlink, -h6:hover > a.headerlink, -dt:hover > a.headerlink, -caption:hover > a.headerlink, -p.caption:hover > a.headerlink, -div.code-block-caption:hover > a.headerlink { - visibility: visible; -} - -div.body p.caption { - text-align: inherit; -} - -div.body td { - text-align: left; -} - -.first { - margin-top: 0 !important; -} - -p.rubric { - margin-top: 30px; - font-weight: bold; -} - -img.align-left, figure.align-left, .figure.align-left, object.align-left { - clear: left; - float: left; - margin-right: 1em; -} - -img.align-right, figure.align-right, .figure.align-right, object.align-right { - clear: right; - float: right; - margin-left: 1em; -} - -img.align-center, figure.align-center, .figure.align-center, object.align-center { - display: block; - margin-left: auto; - margin-right: auto; -} - -img.align-default, figure.align-default, .figure.align-default { - display: block; - margin-left: auto; - margin-right: auto; -} - -.align-left { - text-align: left; -} - -.align-center { - text-align: center; -} - -.align-default { - text-align: center; -} - -.align-right { - text-align: right; -} - -/* -- sidebars -------------------------------------------------------------- */ - -div.sidebar, -aside.sidebar { - margin: 0 0 0.5em 1em; - border: 1px solid #ddb; - padding: 7px; - background-color: #ffe; - width: 40%; - float: right; - clear: right; - overflow-x: auto; -} - -p.sidebar-title { - font-weight: bold; -} - -nav.contents, -aside.topic, -div.admonition, div.topic, blockquote { - clear: left; -} - -/* -- topics ---------------------------------------------------------------- */ - -nav.contents, -aside.topic, -div.topic { - border: 1px solid #ccc; - padding: 7px; - margin: 10px 0 10px 0; -} - -p.topic-title { - font-size: 1.1em; - font-weight: bold; - margin-top: 10px; -} - -/* -- admonitions ----------------------------------------------------------- */ - -div.admonition { - margin-top: 10px; - margin-bottom: 10px; - padding: 7px; -} - -div.admonition dt { - font-weight: bold; -} - -p.admonition-title { - margin: 0px 10px 5px 0px; - font-weight: bold; -} - -div.body p.centered { - text-align: center; - margin-top: 25px; -} - -/* -- content of sidebars/topics/admonitions -------------------------------- */ - -div.sidebar > :last-child, -aside.sidebar > :last-child, -nav.contents > :last-child, -aside.topic > :last-child, -div.topic > :last-child, -div.admonition > :last-child { - margin-bottom: 0; -} - -div.sidebar::after, -aside.sidebar::after, -nav.contents::after, -aside.topic::after, -div.topic::after, -div.admonition::after, -blockquote::after { - display: block; - content: ''; - clear: both; -} - -/* -- tables ---------------------------------------------------------------- */ - -table.docutils { - margin-top: 10px; - margin-bottom: 10px; - border: 0; - border-collapse: collapse; -} - -table.align-center { - margin-left: auto; - margin-right: auto; -} - -table.align-default { - margin-left: auto; - margin-right: auto; -} - -table caption span.caption-number { - font-style: italic; -} - -table caption span.caption-text { -} - -table.docutils td, table.docutils th { - padding: 1px 8px 1px 5px; - border-top: 0; - border-left: 0; - border-right: 0; - border-bottom: 1px solid #aaa; -} - -th { - text-align: left; - padding-right: 5px; -} - -table.citation { - border-left: solid 1px gray; - margin-left: 1px; -} - -table.citation td { - border-bottom: none; -} - -th > :first-child, -td > :first-child { - margin-top: 0px; -} - -th > :last-child, -td > :last-child { - margin-bottom: 0px; -} - -/* -- figures --------------------------------------------------------------- */ - -div.figure, figure { - margin: 0.5em; - padding: 0.5em; -} - -div.figure p.caption, figcaption { - padding: 0.3em; -} - -div.figure p.caption span.caption-number, -figcaption span.caption-number { - font-style: italic; -} - -div.figure p.caption span.caption-text, -figcaption span.caption-text { -} - -/* -- field list styles ----------------------------------------------------- */ - -table.field-list td, table.field-list th { - border: 0 !important; -} - -.field-list ul { - margin: 0; - padding-left: 1em; -} - -.field-list p { - margin: 0; -} - -.field-name { - -moz-hyphens: manual; - -ms-hyphens: manual; - -webkit-hyphens: manual; - hyphens: manual; -} - -/* -- hlist styles ---------------------------------------------------------- */ - -table.hlist { - margin: 1em 0; -} - -table.hlist td { - vertical-align: top; -} - -/* -- object description styles --------------------------------------------- */ - -.sig { - font-family: 'Consolas', 'Menlo', 'DejaVu Sans Mono', 'Bitstream Vera Sans Mono', monospace; -} - -.sig-name, code.descname { - background-color: transparent; - font-weight: bold; -} - -.sig-name { - font-size: 1.1em; -} - -code.descname { - font-size: 1.2em; -} - -.sig-prename, code.descclassname { - background-color: transparent; -} - -.optional { - font-size: 1.3em; -} - -.sig-paren { - font-size: larger; -} - -.sig-param.n { - font-style: italic; -} - -/* C++ specific styling */ - -.sig-inline.c-texpr, -.sig-inline.cpp-texpr { - font-family: unset; -} - -.sig.c .k, .sig.c .kt, -.sig.cpp .k, .sig.cpp .kt { - color: #0033B3; -} - -.sig.c .m, -.sig.cpp .m { - color: #1750EB; -} - -.sig.c .s, .sig.c .sc, -.sig.cpp .s, .sig.cpp .sc { - color: #067D17; -} - - -/* -- other body styles ----------------------------------------------------- */ - -ol.arabic { - list-style: decimal; -} - -ol.loweralpha { - list-style: lower-alpha; -} - -ol.upperalpha { - list-style: upper-alpha; -} - -ol.lowerroman { - list-style: lower-roman; -} - -ol.upperroman { - list-style: upper-roman; -} - -:not(li) > ol > li:first-child > :first-child, -:not(li) > ul > li:first-child > :first-child { - margin-top: 0px; -} - -:not(li) > ol > li:last-child > :last-child, -:not(li) > ul > li:last-child > :last-child { - margin-bottom: 0px; -} - -ol.simple ol p, -ol.simple ul p, -ul.simple ol p, -ul.simple ul p { - margin-top: 0; -} - -ol.simple > li:not(:first-child) > p, -ul.simple > li:not(:first-child) > p { - margin-top: 0; -} - -ol.simple p, -ul.simple p { - margin-bottom: 0; -} - -aside.footnote > span, -div.citation > span { - float: left; -} -aside.footnote > span:last-of-type, -div.citation > span:last-of-type { - padding-right: 0.5em; -} -aside.footnote > p { - margin-left: 2em; -} -div.citation > p { - margin-left: 4em; -} -aside.footnote > p:last-of-type, -div.citation > p:last-of-type { - margin-bottom: 0em; -} -aside.footnote > p:last-of-type:after, -div.citation > p:last-of-type:after { - content: ""; - clear: both; -} - -dl.field-list { - display: grid; - grid-template-columns: fit-content(30%) auto; -} - -dl.field-list > dt { - font-weight: bold; - word-break: break-word; - padding-left: 0.5em; - padding-right: 5px; -} - -dl.field-list > dd { - padding-left: 0.5em; - margin-top: 0em; - margin-left: 0em; - margin-bottom: 0em; -} - -dl { - margin-bottom: 15px; -} - -dd > :first-child { - margin-top: 0px; -} - -dd ul, dd table { - margin-bottom: 10px; -} - -dd { - margin-top: 3px; - margin-bottom: 10px; - margin-left: 30px; -} - -.sig dd { - margin-top: 0px; - margin-bottom: 0px; -} - -.sig dl { - margin-top: 0px; - margin-bottom: 0px; -} - -dl > dd:last-child, -dl > dd:last-child > :last-child { - margin-bottom: 0; -} - -dt:target, span.highlighted { - background-color: #fbe54e; -} - -rect.highlighted { - fill: #fbe54e; -} - -dl.glossary dt { - font-weight: bold; - font-size: 1.1em; -} - -.versionmodified { - font-style: italic; -} - -.system-message { - background-color: #fda; - padding: 5px; - border: 3px solid red; -} - -.footnote:target { - background-color: #ffa; -} - -.line-block { - display: block; - margin-top: 1em; - margin-bottom: 1em; -} - -.line-block .line-block { - margin-top: 0; - margin-bottom: 0; - margin-left: 1.5em; -} - -.guilabel, .menuselection { - font-family: sans-serif; -} - -.accelerator { - text-decoration: underline; -} - -.classifier { - font-style: oblique; -} - -.classifier:before { - font-style: normal; - margin: 0 0.5em; - content: ":"; - display: inline-block; -} - -abbr, acronym { - border-bottom: dotted 1px; - cursor: help; -} - -.translated { - background-color: rgba(207, 255, 207, 0.2) -} - -.untranslated { - background-color: rgba(255, 207, 207, 0.2) -} - -/* -- code displays --------------------------------------------------------- */ - -pre { - overflow: auto; - overflow-y: hidden; /* fixes display issues on Chrome browsers */ -} - -pre, div[class*="highlight-"] { - clear: both; -} - -span.pre { - -moz-hyphens: none; - -ms-hyphens: none; - -webkit-hyphens: none; - hyphens: none; - white-space: nowrap; -} - -div[class*="highlight-"] { - margin: 1em 0; -} - -td.linenos pre { - border: 0; - background-color: transparent; - color: #aaa; -} - -table.highlighttable { - display: block; -} - -table.highlighttable tbody { - display: block; -} - -table.highlighttable tr { - display: flex; -} - -table.highlighttable td { - margin: 0; - padding: 0; -} - -table.highlighttable td.linenos { - padding-right: 0.5em; -} - -table.highlighttable td.code { - flex: 1; - overflow: hidden; -} - -.highlight .hll { - display: block; -} - -div.highlight pre, -table.highlighttable pre { - margin: 0; -} - -div.code-block-caption + div { - margin-top: 0; -} - -div.code-block-caption { - margin-top: 1em; - padding: 2px 5px; - font-size: small; -} - -div.code-block-caption code { - background-color: transparent; -} - -table.highlighttable td.linenos, -span.linenos, -div.highlight span.gp { /* gp: Generic.Prompt */ - user-select: none; - -webkit-user-select: text; /* Safari fallback only */ - -webkit-user-select: none; /* Chrome/Safari */ - -moz-user-select: none; /* Firefox */ - -ms-user-select: none; /* IE10+ */ -} - -div.code-block-caption span.caption-number { - padding: 0.1em 0.3em; - font-style: italic; -} - -div.code-block-caption span.caption-text { -} - -div.literal-block-wrapper { - margin: 1em 0; -} - -code.xref, a code { - background-color: transparent; - font-weight: bold; -} - -h1 code, h2 code, h3 code, h4 code, h5 code, h6 code { - background-color: transparent; -} - -.viewcode-link { - float: right; -} - -.viewcode-back { - float: right; - font-family: sans-serif; -} - -div.viewcode-block:target { - margin: -1px -10px; - padding: 0 10px; -} - -/* -- math display ---------------------------------------------------------- */ - -img.math { - vertical-align: middle; -} - -div.body div.math p { - text-align: center; -} - -span.eqno { - float: right; -} - -span.eqno a.headerlink { - position: absolute; - z-index: 1; -} - -div.math:hover a.headerlink { - visibility: visible; -} - -/* -- printout stylesheet --------------------------------------------------- */ - -@media print { - div.document, - div.documentwrapper, - div.bodywrapper { - margin: 0 !important; - width: 100%; - } - - div.sphinxsidebar, - div.related, - div.footer, - #top-link { - display: none; - } -} \ No newline at end of file diff --git a/docs/_build/html/_static/check-solid.svg b/docs/_build/html/_static/check-solid.svg deleted file mode 100644 index 92fad4b5c..000000000 --- a/docs/_build/html/_static/check-solid.svg +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/docs/_build/html/_static/clipboard.min.js b/docs/_build/html/_static/clipboard.min.js deleted file mode 100644 index 54b3c4638..000000000 --- a/docs/_build/html/_static/clipboard.min.js +++ /dev/null @@ -1,7 +0,0 @@ -/*! - * clipboard.js v2.0.8 - * https://clipboardjs.com/ - * - * Licensed MIT © Zeno Rocha - */ -!function(t,e){"object"==typeof exports&&"object"==typeof module?module.exports=e():"function"==typeof define&&define.amd?define([],e):"object"==typeof exports?exports.ClipboardJS=e():t.ClipboardJS=e()}(this,function(){return n={686:function(t,e,n){"use strict";n.d(e,{default:function(){return o}});var e=n(279),i=n.n(e),e=n(370),u=n.n(e),e=n(817),c=n.n(e);function a(t){try{return document.execCommand(t)}catch(t){return}}var f=function(t){t=c()(t);return a("cut"),t};var l=function(t){var e,n,o,r=1 - - - - diff --git a/docs/_build/html/_static/copybutton.css b/docs/_build/html/_static/copybutton.css deleted file mode 100644 index f1916ec7d..000000000 --- a/docs/_build/html/_static/copybutton.css +++ /dev/null @@ -1,94 +0,0 @@ -/* Copy buttons */ -button.copybtn { - position: absolute; - display: flex; - top: .3em; - right: .3em; - width: 1.7em; - height: 1.7em; - opacity: 0; - transition: opacity 0.3s, border .3s, background-color .3s; - user-select: none; - padding: 0; - border: none; - outline: none; - border-radius: 0.4em; - /* The colors that GitHub uses */ - border: #1b1f2426 1px solid; - background-color: #f6f8fa; - color: #57606a; -} - -button.copybtn.success { - border-color: #22863a; - color: #22863a; -} - -button.copybtn svg { - stroke: currentColor; - width: 1.5em; - height: 1.5em; - padding: 0.1em; -} - -div.highlight { - position: relative; -} - -/* Show the copybutton */ -.highlight:hover button.copybtn, button.copybtn.success { - opacity: 1; -} - -.highlight button.copybtn:hover { - background-color: rgb(235, 235, 235); -} - -.highlight button.copybtn:active { - background-color: rgb(187, 187, 187); -} - -/** - * A minimal CSS-only tooltip copied from: - * https://codepen.io/mildrenben/pen/rVBrpK - * - * To use, write HTML like the following: - * - *

    Short

    - */ - .o-tooltip--left { - position: relative; - } - - .o-tooltip--left:after { - opacity: 0; - visibility: hidden; - position: absolute; - content: attr(data-tooltip); - padding: .2em; - font-size: .8em; - left: -.2em; - background: grey; - color: white; - white-space: nowrap; - z-index: 2; - border-radius: 2px; - transform: translateX(-102%) translateY(0); - transition: opacity 0.2s cubic-bezier(0.64, 0.09, 0.08, 1), transform 0.2s cubic-bezier(0.64, 0.09, 0.08, 1); -} - -.o-tooltip--left:hover:after { - display: block; - opacity: 1; - visibility: visible; - transform: translateX(-100%) translateY(0); - transition: opacity 0.2s cubic-bezier(0.64, 0.09, 0.08, 1), transform 0.2s cubic-bezier(0.64, 0.09, 0.08, 1); - transition-delay: .5s; -} - -/* By default the copy button shouldn't show up when printing a page */ -@media print { - button.copybtn { - display: none; - } -} diff --git a/docs/_build/html/_static/copybutton.js b/docs/_build/html/_static/copybutton.js deleted file mode 100644 index ff4aa329a..000000000 --- a/docs/_build/html/_static/copybutton.js +++ /dev/null @@ -1,248 +0,0 @@ -// Localization support -const messages = { - 'en': { - 'copy': 'Copy', - 'copy_to_clipboard': 'Copy to clipboard', - 'copy_success': 'Copied!', - 'copy_failure': 'Failed to copy', - }, - 'es' : { - 'copy': 'Copiar', - 'copy_to_clipboard': 'Copiar al portapapeles', - 'copy_success': '¡Copiado!', - 'copy_failure': 'Error al copiar', - }, - 'de' : { - 'copy': 'Kopieren', - 'copy_to_clipboard': 'In die Zwischenablage kopieren', - 'copy_success': 'Kopiert!', - 'copy_failure': 'Fehler beim Kopieren', - }, - 'fr' : { - 'copy': 'Copier', - 'copy_to_clipboard': 'Copier dans le presse-papier', - 'copy_success': 'Copié !', - 'copy_failure': 'Échec de la copie', - }, - 'ru': { - 'copy': 'Скопировать', - 'copy_to_clipboard': 'Скопировать в буфер', - 'copy_success': 'Скопировано!', - 'copy_failure': 'Не удалось скопировать', - }, - 'zh-CN': { - 'copy': '复制', - 'copy_to_clipboard': '复制到剪贴板', - 'copy_success': '复制成功!', - 'copy_failure': '复制失败', - }, - 'it' : { - 'copy': 'Copiare', - 'copy_to_clipboard': 'Copiato negli appunti', - 'copy_success': 'Copiato!', - 'copy_failure': 'Errore durante la copia', - } -} - -let locale = 'en' -if( document.documentElement.lang !== undefined - && messages[document.documentElement.lang] !== undefined ) { - locale = document.documentElement.lang -} - -let doc_url_root = DOCUMENTATION_OPTIONS.URL_ROOT; -if (doc_url_root == '#') { - doc_url_root = ''; -} - -/** - * SVG files for our copy buttons - */ -let iconCheck = ` - ${messages[locale]['copy_success']} - - -` - -// If the user specified their own SVG use that, otherwise use the default -let iconCopy = ``; -if (!iconCopy) { - iconCopy = ` - ${messages[locale]['copy_to_clipboard']} - - - -` -} - -/** - * Set up copy/paste for code blocks - */ - -const runWhenDOMLoaded = cb => { - if (document.readyState != 'loading') { - cb() - } else if (document.addEventListener) { - document.addEventListener('DOMContentLoaded', cb) - } else { - document.attachEvent('onreadystatechange', function() { - if (document.readyState == 'complete') cb() - }) - } -} - -const codeCellId = index => `codecell${index}` - -// Clears selected text since ClipboardJS will select the text when copying -const clearSelection = () => { - if (window.getSelection) { - window.getSelection().removeAllRanges() - } else if (document.selection) { - document.selection.empty() - } -} - -// Changes tooltip text for a moment, then changes it back -// We want the timeout of our `success` class to be a bit shorter than the -// tooltip and icon change, so that we can hide the icon before changing back. -var timeoutIcon = 2000; -var timeoutSuccessClass = 1500; - -const temporarilyChangeTooltip = (el, oldText, newText) => { - el.setAttribute('data-tooltip', newText) - el.classList.add('success') - // Remove success a little bit sooner than we change the tooltip - // So that we can use CSS to hide the copybutton first - setTimeout(() => el.classList.remove('success'), timeoutSuccessClass) - setTimeout(() => el.setAttribute('data-tooltip', oldText), timeoutIcon) -} - -// Changes the copy button icon for two seconds, then changes it back -const temporarilyChangeIcon = (el) => { - el.innerHTML = iconCheck; - setTimeout(() => {el.innerHTML = iconCopy}, timeoutIcon) -} - -const addCopyButtonToCodeCells = () => { - // If ClipboardJS hasn't loaded, wait a bit and try again. This - // happens because we load ClipboardJS asynchronously. - if (window.ClipboardJS === undefined) { - setTimeout(addCopyButtonToCodeCells, 250) - return - } - - // Add copybuttons to all of our code cells - const COPYBUTTON_SELECTOR = 'div.highlight pre'; - const codeCells = document.querySelectorAll(COPYBUTTON_SELECTOR) - codeCells.forEach((codeCell, index) => { - const id = codeCellId(index) - codeCell.setAttribute('id', id) - - const clipboardButton = id => - `` - codeCell.insertAdjacentHTML('afterend', clipboardButton(id)) - }) - -function escapeRegExp(string) { - return string.replace(/[.*+?^${}()|[\]\\]/g, '\\$&'); // $& means the whole matched string -} - -/** - * Removes excluded text from a Node. - * - * @param {Node} target Node to filter. - * @param {string} exclude CSS selector of nodes to exclude. - * @returns {DOMString} Text from `target` with text removed. - */ -function filterText(target, exclude) { - const clone = target.cloneNode(true); // clone as to not modify the live DOM - if (exclude) { - // remove excluded nodes - clone.querySelectorAll(exclude).forEach(node => node.remove()); - } - return clone.innerText; -} - -// Callback when a copy button is clicked. Will be passed the node that was clicked -// should then grab the text and replace pieces of text that shouldn't be used in output -function formatCopyText(textContent, copybuttonPromptText, isRegexp = false, onlyCopyPromptLines = true, removePrompts = true, copyEmptyLines = true, lineContinuationChar = "", hereDocDelim = "") { - var regexp; - var match; - - // Do we check for line continuation characters and "HERE-documents"? - var useLineCont = !!lineContinuationChar - var useHereDoc = !!hereDocDelim - - // create regexp to capture prompt and remaining line - if (isRegexp) { - regexp = new RegExp('^(' + copybuttonPromptText + ')(.*)') - } else { - regexp = new RegExp('^(' + escapeRegExp(copybuttonPromptText) + ')(.*)') - } - - const outputLines = []; - var promptFound = false; - var gotLineCont = false; - var gotHereDoc = false; - const lineGotPrompt = []; - for (const line of textContent.split('\n')) { - match = line.match(regexp) - if (match || gotLineCont || gotHereDoc) { - promptFound = regexp.test(line) - lineGotPrompt.push(promptFound) - if (removePrompts && promptFound) { - outputLines.push(match[2]) - } else { - outputLines.push(line) - } - gotLineCont = line.endsWith(lineContinuationChar) & useLineCont - if (line.includes(hereDocDelim) & useHereDoc) - gotHereDoc = !gotHereDoc - } else if (!onlyCopyPromptLines) { - outputLines.push(line) - } else if (copyEmptyLines && line.trim() === '') { - outputLines.push(line) - } - } - - // If no lines with the prompt were found then just use original lines - if (lineGotPrompt.some(v => v === true)) { - textContent = outputLines.join('\n'); - } - - // Remove a trailing newline to avoid auto-running when pasting - if (textContent.endsWith("\n")) { - textContent = textContent.slice(0, -1) - } - return textContent -} - - -var copyTargetText = (trigger) => { - var target = document.querySelector(trigger.attributes['data-clipboard-target'].value); - - // get filtered text - let exclude = '.linenos'; - - let text = filterText(target, exclude); - return formatCopyText(text, '>>> |\\.\\.\\. |\\$ ', true, true, true, true, '', '') -} - - // Initialize with a callback so we can modify the text before copy - const clipboard = new ClipboardJS('.copybtn', {text: copyTargetText}) - - // Update UI with error/success messages - clipboard.on('success', event => { - clearSelection() - temporarilyChangeTooltip(event.trigger, messages[locale]['copy'], messages[locale]['copy_success']) - temporarilyChangeIcon(event.trigger) - }) - - clipboard.on('error', event => { - temporarilyChangeTooltip(event.trigger, messages[locale]['copy'], messages[locale]['copy_failure']) - }) -} - -runWhenDOMLoaded(addCopyButtonToCodeCells) \ No newline at end of file diff --git a/docs/_build/html/_static/copybutton_funcs.js b/docs/_build/html/_static/copybutton_funcs.js deleted file mode 100644 index dbe1aaad7..000000000 --- a/docs/_build/html/_static/copybutton_funcs.js +++ /dev/null @@ -1,73 +0,0 @@ -function escapeRegExp(string) { - return string.replace(/[.*+?^${}()|[\]\\]/g, '\\$&'); // $& means the whole matched string -} - -/** - * Removes excluded text from a Node. - * - * @param {Node} target Node to filter. - * @param {string} exclude CSS selector of nodes to exclude. - * @returns {DOMString} Text from `target` with text removed. - */ -export function filterText(target, exclude) { - const clone = target.cloneNode(true); // clone as to not modify the live DOM - if (exclude) { - // remove excluded nodes - clone.querySelectorAll(exclude).forEach(node => node.remove()); - } - return clone.innerText; -} - -// Callback when a copy button is clicked. Will be passed the node that was clicked -// should then grab the text and replace pieces of text that shouldn't be used in output -export function formatCopyText(textContent, copybuttonPromptText, isRegexp = false, onlyCopyPromptLines = true, removePrompts = true, copyEmptyLines = true, lineContinuationChar = "", hereDocDelim = "") { - var regexp; - var match; - - // Do we check for line continuation characters and "HERE-documents"? - var useLineCont = !!lineContinuationChar - var useHereDoc = !!hereDocDelim - - // create regexp to capture prompt and remaining line - if (isRegexp) { - regexp = new RegExp('^(' + copybuttonPromptText + ')(.*)') - } else { - regexp = new RegExp('^(' + escapeRegExp(copybuttonPromptText) + ')(.*)') - } - - const outputLines = []; - var promptFound = false; - var gotLineCont = false; - var gotHereDoc = false; - const lineGotPrompt = []; - for (const line of textContent.split('\n')) { - match = line.match(regexp) - if (match || gotLineCont || gotHereDoc) { - promptFound = regexp.test(line) - lineGotPrompt.push(promptFound) - if (removePrompts && promptFound) { - outputLines.push(match[2]) - } else { - outputLines.push(line) - } - gotLineCont = line.endsWith(lineContinuationChar) & useLineCont - if (line.includes(hereDocDelim) & useHereDoc) - gotHereDoc = !gotHereDoc - } else if (!onlyCopyPromptLines) { - outputLines.push(line) - } else if (copyEmptyLines && line.trim() === '') { - outputLines.push(line) - } - } - - // If no lines with the prompt were found then just use original lines - if (lineGotPrompt.some(v => v === true)) { - textContent = outputLines.join('\n'); - } - - // Remove a trailing newline to avoid auto-running when pasting - if (textContent.endsWith("\n")) { - textContent = textContent.slice(0, -1) - } - return textContent -} diff --git a/docs/_build/html/_static/custom.css b/docs/_build/html/_static/custom.css deleted file mode 100644 index 52a770bbb..000000000 --- a/docs/_build/html/_static/custom.css +++ /dev/null @@ -1,37 +0,0 @@ -/* hides the TOC caption from the main page since we already have an H1 heading */ -.section .caption-text { - display: none; -} - -/* note title text in white */ -.admonition p.admonition-title { - color: white; - font-weight: 700; -} - -/* .admonition.note { - background: #e5f4d8; -} */ - -/* left align tables */ -table.docutils { - margin-left: 1em; - font-family: monospace; -} - -/* inline code snippets #E74C3C, var(--color-link), #4e9a06 */ -code.literal { - color: #4e9a06; - font-family: monospace; - font-size: var(--font-size-normal); -} - -.sidebar-brand-text { - text-align: center; - margin: 0 0; -} - - - -/* normalize size across Firefox / Chrome */ -html { font-size: 100%; } diff --git a/docs/_build/html/_static/debug.css b/docs/_build/html/_static/debug.css deleted file mode 100644 index 74d4aec33..000000000 --- a/docs/_build/html/_static/debug.css +++ /dev/null @@ -1,69 +0,0 @@ -/* - This CSS file should be overridden by the theme authors. It's - meant for debugging and developing the skeleton that this theme provides. -*/ -body { - font-family: -apple-system, "Segoe UI", Roboto, Helvetica, Arial, sans-serif, - "Apple Color Emoji", "Segoe UI Emoji"; - background: lavender; -} -.sb-announcement { - background: rgb(131, 131, 131); -} -.sb-announcement__inner { - background: black; - color: white; -} -.sb-header { - background: lightskyblue; -} -.sb-header__inner { - background: royalblue; - color: white; -} -.sb-header-secondary { - background: lightcyan; -} -.sb-header-secondary__inner { - background: cornflowerblue; - color: white; -} -.sb-sidebar-primary { - background: lightgreen; -} -.sb-main { - background: blanchedalmond; -} -.sb-main__inner { - background: antiquewhite; -} -.sb-header-article { - background: lightsteelblue; -} -.sb-article-container { - background: snow; -} -.sb-article-main { - background: white; -} -.sb-footer-article { - background: lightpink; -} -.sb-sidebar-secondary { - background: lightgoldenrodyellow; -} -.sb-footer-content { - background: plum; -} -.sb-footer-content__inner { - background: palevioletred; -} -.sb-footer { - background: pink; -} -.sb-footer__inner { - background: salmon; -} -.sb-article { - background: white; -} diff --git a/docs/_build/html/_static/doctools.js b/docs/_build/html/_static/doctools.js deleted file mode 100644 index d06a71d75..000000000 --- a/docs/_build/html/_static/doctools.js +++ /dev/null @@ -1,156 +0,0 @@ -/* - * doctools.js - * ~~~~~~~~~~~ - * - * Base JavaScript utilities for all Sphinx HTML documentation. - * - * :copyright: Copyright 2007-2023 by the Sphinx team, see AUTHORS. - * :license: BSD, see LICENSE for details. - * - */ -"use strict"; - -const BLACKLISTED_KEY_CONTROL_ELEMENTS = new Set([ - "TEXTAREA", - "INPUT", - "SELECT", - "BUTTON", -]); - -const _ready = (callback) => { - if (document.readyState !== "loading") { - callback(); - } else { - document.addEventListener("DOMContentLoaded", callback); - } -}; - -/** - * Small JavaScript module for the documentation. - */ -const Documentation = { - init: () => { - Documentation.initDomainIndexTable(); - Documentation.initOnKeyListeners(); - }, - - /** - * i18n support - */ - TRANSLATIONS: {}, - PLURAL_EXPR: (n) => (n === 1 ? 0 : 1), - LOCALE: "unknown", - - // gettext and ngettext don't access this so that the functions - // can safely bound to a different name (_ = Documentation.gettext) - gettext: (string) => { - const translated = Documentation.TRANSLATIONS[string]; - switch (typeof translated) { - case "undefined": - return string; // no translation - case "string": - return translated; // translation exists - default: - return translated[0]; // (singular, plural) translation tuple exists - } - }, - - ngettext: (singular, plural, n) => { - const translated = Documentation.TRANSLATIONS[singular]; - if (typeof translated !== "undefined") - return translated[Documentation.PLURAL_EXPR(n)]; - return n === 1 ? singular : plural; - }, - - addTranslations: (catalog) => { - Object.assign(Documentation.TRANSLATIONS, catalog.messages); - Documentation.PLURAL_EXPR = new Function( - "n", - `return (${catalog.plural_expr})` - ); - Documentation.LOCALE = catalog.locale; - }, - - /** - * helper function to focus on search bar - */ - focusSearchBar: () => { - document.querySelectorAll("input[name=q]")[0]?.focus(); - }, - - /** - * Initialise the domain index toggle buttons - */ - initDomainIndexTable: () => { - const toggler = (el) => { - const idNumber = el.id.substr(7); - const toggledRows = document.querySelectorAll(`tr.cg-${idNumber}`); - if (el.src.substr(-9) === "minus.png") { - el.src = `${el.src.substr(0, el.src.length - 9)}plus.png`; - toggledRows.forEach((el) => (el.style.display = "none")); - } else { - el.src = `${el.src.substr(0, el.src.length - 8)}minus.png`; - toggledRows.forEach((el) => (el.style.display = "")); - } - }; - - const togglerElements = document.querySelectorAll("img.toggler"); - togglerElements.forEach((el) => - el.addEventListener("click", (event) => toggler(event.currentTarget)) - ); - togglerElements.forEach((el) => (el.style.display = "")); - if (DOCUMENTATION_OPTIONS.COLLAPSE_INDEX) togglerElements.forEach(toggler); - }, - - initOnKeyListeners: () => { - // only install a listener if it is really needed - if ( - !DOCUMENTATION_OPTIONS.NAVIGATION_WITH_KEYS && - !DOCUMENTATION_OPTIONS.ENABLE_SEARCH_SHORTCUTS - ) - return; - - document.addEventListener("keydown", (event) => { - // bail for input elements - if (BLACKLISTED_KEY_CONTROL_ELEMENTS.has(document.activeElement.tagName)) return; - // bail with special keys - if (event.altKey || event.ctrlKey || event.metaKey) return; - - if (!event.shiftKey) { - switch (event.key) { - case "ArrowLeft": - if (!DOCUMENTATION_OPTIONS.NAVIGATION_WITH_KEYS) break; - - const prevLink = document.querySelector('link[rel="prev"]'); - if (prevLink && prevLink.href) { - window.location.href = prevLink.href; - event.preventDefault(); - } - break; - case "ArrowRight": - if (!DOCUMENTATION_OPTIONS.NAVIGATION_WITH_KEYS) break; - - const nextLink = document.querySelector('link[rel="next"]'); - if (nextLink && nextLink.href) { - window.location.href = nextLink.href; - event.preventDefault(); - } - break; - } - } - - // some keyboard layouts may need Shift to get / - switch (event.key) { - case "/": - if (!DOCUMENTATION_OPTIONS.ENABLE_SEARCH_SHORTCUTS) break; - Documentation.focusSearchBar(); - event.preventDefault(); - } - }); - }, -}; - -// quick alias for translations -const _ = Documentation.gettext; - -_ready(Documentation.init); diff --git a/docs/_build/html/_static/documentation_options.js b/docs/_build/html/_static/documentation_options.js deleted file mode 100644 index a2012ad39..000000000 --- a/docs/_build/html/_static/documentation_options.js +++ /dev/null @@ -1,13 +0,0 @@ -const DOCUMENTATION_OPTIONS = { - VERSION: '1.0.0-beta.5', - LANGUAGE: 'en', - COLLAPSE_INDEX: false, - BUILDER: 'html', - FILE_SUFFIX: '.html', - LINK_SUFFIX: '.html', - HAS_SOURCE: true, - SOURCELINK_SUFFIX: '.txt', - NAVIGATION_WITH_KEYS: false, - SHOW_SEARCH_SUMMARY: true, - ENABLE_SEARCH_SHORTCUTS: true, -}; \ No newline at end of file diff --git a/docs/_build/html/_static/file.png b/docs/_build/html/_static/file.png deleted file mode 100644 index a858a410e4faa62ce324d814e4b816fff83a6fb3..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 286 zcmV+(0pb3MP)s`hMrGg#P~ix$^RISR_I47Y|r1 z_CyJOe}D1){SET-^Amu_i71Lt6eYfZjRyw@I6OQAIXXHDfiX^GbOlHe=Ae4>0m)d(f|Me07*qoM6N<$f}vM^LjV8( diff --git a/docs/_build/html/_static/language_data.js b/docs/_build/html/_static/language_data.js deleted file mode 100644 index 250f5665f..000000000 --- a/docs/_build/html/_static/language_data.js +++ /dev/null @@ -1,199 +0,0 @@ -/* - * language_data.js - * ~~~~~~~~~~~~~~~~ - * - * This script contains the language-specific data used by searchtools.js, - * namely the list of stopwords, stemmer, scorer and splitter. - * - * :copyright: Copyright 2007-2023 by the Sphinx team, see AUTHORS. - * :license: BSD, see LICENSE for details. - * - */ - -var stopwords = ["a", "and", "are", "as", "at", "be", "but", "by", "for", "if", "in", "into", "is", "it", "near", "no", "not", "of", "on", "or", "such", "that", "the", "their", "then", "there", "these", "they", "this", "to", "was", "will", "with"]; - - -/* Non-minified version is copied as a separate JS file, is available */ - -/** - * Porter Stemmer - */ -var Stemmer = function() { - - var step2list = { - ational: 'ate', - tional: 'tion', - enci: 'ence', - anci: 'ance', - izer: 'ize', - bli: 'ble', - alli: 'al', - entli: 'ent', - eli: 'e', - ousli: 'ous', - ization: 'ize', - ation: 'ate', - ator: 'ate', - alism: 'al', - iveness: 'ive', - fulness: 'ful', - ousness: 'ous', - aliti: 'al', - iviti: 'ive', - biliti: 'ble', - logi: 'log' - }; - - var step3list = { - icate: 'ic', - ative: '', - alize: 'al', - iciti: 'ic', - ical: 'ic', - ful: '', - ness: '' - }; - - var c = "[^aeiou]"; // consonant - var v = "[aeiouy]"; // vowel - var C = c + "[^aeiouy]*"; // consonant sequence - var V = v + "[aeiou]*"; // vowel sequence - - var mgr0 = "^(" + C + ")?" + V + C; // [C]VC... is m>0 - var meq1 = "^(" + C + ")?" + V + C + "(" + V + ")?$"; // [C]VC[V] is m=1 - var mgr1 = "^(" + C + ")?" + V + C + V + C; // [C]VCVC... is m>1 - var s_v = "^(" + C + ")?" + v; // vowel in stem - - this.stemWord = function (w) { - var stem; - var suffix; - var firstch; - var origword = w; - - if (w.length < 3) - return w; - - var re; - var re2; - var re3; - var re4; - - firstch = w.substr(0,1); - if (firstch == "y") - w = firstch.toUpperCase() + w.substr(1); - - // Step 1a - re = /^(.+?)(ss|i)es$/; - re2 = /^(.+?)([^s])s$/; - - if (re.test(w)) - w = w.replace(re,"$1$2"); - else if (re2.test(w)) - w = w.replace(re2,"$1$2"); - - // Step 1b - re = /^(.+?)eed$/; - re2 = /^(.+?)(ed|ing)$/; - if (re.test(w)) { - var fp = re.exec(w); - re = new RegExp(mgr0); - if (re.test(fp[1])) { - re = /.$/; - w = w.replace(re,""); - } - } - else if (re2.test(w)) { - var fp = re2.exec(w); - stem = fp[1]; - re2 = new RegExp(s_v); - if (re2.test(stem)) { - w = stem; - re2 = /(at|bl|iz)$/; - re3 = new RegExp("([^aeiouylsz])\\1$"); - re4 = new RegExp("^" + C + v + "[^aeiouwxy]$"); - if (re2.test(w)) - w = w + "e"; - else if (re3.test(w)) { - re = /.$/; - w = w.replace(re,""); - } - else if (re4.test(w)) - w = w + "e"; - } - } - - // Step 1c - re = /^(.+?)y$/; - if (re.test(w)) { - var fp = re.exec(w); - stem = fp[1]; - re = new RegExp(s_v); - if (re.test(stem)) - w = stem + "i"; - } - - // Step 2 - re = /^(.+?)(ational|tional|enci|anci|izer|bli|alli|entli|eli|ousli|ization|ation|ator|alism|iveness|fulness|ousness|aliti|iviti|biliti|logi)$/; - if (re.test(w)) { - var fp = re.exec(w); - stem = fp[1]; - suffix = fp[2]; - re = new RegExp(mgr0); - if (re.test(stem)) - w = stem + step2list[suffix]; - } - - // Step 3 - re = /^(.+?)(icate|ative|alize|iciti|ical|ful|ness)$/; - if (re.test(w)) { - var fp = re.exec(w); - stem = fp[1]; - suffix = fp[2]; - re = new RegExp(mgr0); - if (re.test(stem)) - w = stem + step3list[suffix]; - } - - // Step 4 - re = /^(.+?)(al|ance|ence|er|ic|able|ible|ant|ement|ment|ent|ou|ism|ate|iti|ous|ive|ize)$/; - re2 = /^(.+?)(s|t)(ion)$/; - if (re.test(w)) { - var fp = re.exec(w); - stem = fp[1]; - re = new RegExp(mgr1); - if (re.test(stem)) - w = stem; - } - else if (re2.test(w)) { - var fp = re2.exec(w); - stem = fp[1] + fp[2]; - re2 = new RegExp(mgr1); - if (re2.test(stem)) - w = stem; - } - - // Step 5 - re = /^(.+?)e$/; - if (re.test(w)) { - var fp = re.exec(w); - stem = fp[1]; - re = new RegExp(mgr1); - re2 = new RegExp(meq1); - re3 = new RegExp("^" + C + v + "[^aeiouwxy]$"); - if (re.test(stem) || (re2.test(stem) && !(re3.test(stem)))) - w = stem; - } - re = /ll$/; - re2 = new RegExp(mgr1); - if (re.test(w) && re2.test(w)) { - re = /.$/; - w = w.replace(re,""); - } - - // and turn initial Y back to y - if (firstch == "y") - w = firstch.toLowerCase() + w.substr(1); - return w; - } -} - diff --git a/docs/_build/html/_static/logo-dark-mode.png b/docs/_build/html/_static/logo-dark-mode.png deleted file mode 100644 index ce0016561a8ad6995fdb5729fcb78b9cadb56829..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 8504 zcmeHLc{r3^*dJ0#$xM%7Foj#lO^g^ z6fKs**h+}8M~vkg>fNsI`{%u`@BQz6=9;;l=bYdDyU+bQ_c`Z&CdN=-iu75j0RU|MtoxkZyI8;I+)M@lz!@88V&QFs^#gi%ksJwbc%XNH2Ofy`CpZEC{=K8g zmUsG<_D2o+Tt|kV&*bthV#G$&5Yp$&t05?uPb*Fbf-FOty zf56QuJB-?r(nC~7KYu%5wR-NyYOI;g40y%(7USXi{D#!3f{ejnI;oHT~t z!(F-}r!CRHSNg70;z9Gmi#c%P5Mp4-qul#EA)}%d#&1BSQ&~z9ANBMlTyHz|`gTm- ze{(-zkIh}Ekj9S<&*0_Ay7+?{`lr6{1Wf8qaHQfzzqH>c0wtMZCc*4$pMR_&sgAsz z2S$(HK4;hB8l62aapEP<+xv04%=cNH-^H)+%2ibey#fMU3e@%?a!fRL=j`B}noZCX z1_BESnuUQ`gRHOtN=%wOc!bn-TTVGBw6W=Pz_H4q-gP`=VM9t zXSN~-p7-j~?ZZZ@TzDw_cAN)(gX!5?RQRfedR>l5_e+~(J0{ec)KM~)ZJH4-p_uZ+ z;$h2W?r*1`TlEYxZHtm_pKvzF54xWG&7GofZn9^-UPtsA^$})LIEPcq&|70q?SlujM{l&%26=N>{tupP@I=?!SV4%Q}xRPp=lry_f8hCBLE z4=YxxwT(G-#_=ARpInXhYSlt>b#S(s)gM#r-CjuHxX}kPPq%=Rol+uKh*5RvN;Sm# z8~LgiGVYh45lM=B(t6Vb{2rO_5yf12-B^_XLiu&PJJ(&GDs}$E;GvbyLoadGQ$iW*}Oow#h+>qDEzBU?QY1JUe67{ee`uuSs=4 z-*0}n1O;I{2ejh-DTYuk;J6b$r?XCUHGwKBlJ)#!y7c)2w(sU9+YQpgOYVE-z;;UI zsx#kpy1rb$L-BomYI?OGb82Uvl{sZhj-Qn8Q_MCk#i^i&>_v}mPJUZ^`=j4BG;o%u z_|9;FaJoZu-g{m1ehtST!%#}nLpkj`!V`SYR80>R28dg$@!fJxJm)B^xZ;=)cNkl` zd*;sVc`9tr_`Y4mvc7TRz?gwWn{v^ll(yD1ZeYJ}?K64ULb=_Xkn?a8t|uxZIdh*w z3V&gP+@V67>j)~n8G)klybZ1@u9zQIIb|}?_Dx@m?a2;&7BE%h<*_KST`z8`otP!! zE(r02=)6GN3rC&<&o-S%u{7D^|6NoN&U2r8vmnx)ku#~3Y^r-ZNPJBf?riRPr@oqY zUm_2?U|<>t)Q_E!z2#T$NDnVV{P)A+;_j8$b8m9%{Mr${p6@78(gRZ8G*eRpuN7Q{PfHETmrYF@R4P`68 z*?FyBJ!~E00-R`M05w$3+oEz}+ENsI^Mcwc0V8dR!oTWu@sBT2MUA@5f9%*n{U)k~P&KQZB66)G-HDAgaVMos$M;nM9IizRv*jr9k zL}u=w=c!Vc1c-x8J9%K_vDxI~V1tb&Lse_buc$ZJW989O+Pv9Waa@IEy!oa_UudK( z9T49*(gL}ycf@>WtmxhX)ySzI&o+nrD2|?9O&BhzD;a`)8$xX1w6jInzQLAiI*M(r zqw!w%Tu(~l>k|_<;|`r>Z|ZA&;iF}|bfrxUxSG=zHKiSrqE^29Y34h{(JNurS)@0N z;=1?`oIrJ(T;i1ob-PN9Pm|&^(~N1xAdImQ0+2_0-Q+WD7-!W_!UR^GWPv%4!jas; zSO=0l9_;V#!K$MG0Od3O9$1_!-WzC-cOnqck~6dhNg%-iEorWRfnq$=@y-P8Krg&; zpuPz%&=rStkUXQprRMu|R)!HzFD3kCxo#MX~O;njwBoYaM z%0uMkK`aD_96Yu(Bp+|Iq$H~!`1|?#@ zZL4QHoWBl)W&Q{6-_XCuz71xfFc_2u3FoslJRJ?RaadJ>4MJ)6$6b4=dR#sx&{yM5HDhC!777NA074h;Qdn6VC zg2Ui2kUbOu2Prx#DmcpH+Q%gKuew{5PkgrgqjfC@y6cREj8s3N^&rm5*#iEha#c!N`HdP@LptA zCT?-cLBX(}yj#x*~TcEqy#*@bh)5}oj@_5CZM zes3rIACo1IN5Tc{vbN5e0=xLVg7d*;>`V zN30C_Uz#Xy1OBoNuU9b(^l-~a<=A!l5|L&VabduptSdNQx_Xq_k*-*eUZr1)4xQbr2gRN zTPA({N{jY?*zuidpnz6XLuJoI1bOS{qnCKe5u&$E3 z=tAt7<{evW-AFt4+`xtc`=SEA{hRP{=SwY{w$ZBtE~=b;m^8os4kq7RRTP5ZsvXeO zSobO-;k{;YSSooSKDvY5FAb529r}u_zS}5JS=^N45l~O*!#uTAld6BvShsjGcQLoA zk>PVDQHUB`UDv2NRK54HU?1kPa~b_kW8JrS#_gk3juwt&_#PlMmDLd%v`SAB=#T1XpBt2gooN_>4q{&TN>7cy?L^5L z@d9-J7sVCv;$zMtJQB+SX6Sv=%N3#I0$+1@PQOxCo~T(y+brp(dTWnpPC|RW%R)`? zwf=-X{SO)^`1dKkQR{LDa%V5Eertmp8t7uf2vBJ6mE z1U~A#EICqoWXEs`P((@S3{i2eGU~03>(D?q+i2RR^l_+~V~|X2*}s^RiX3rsBT%xKdI-l4|2+=mSMLpJlrYd*Y_673qWV7e~jH8$x4e zY*rM_Yg5if_B~n^m3&!3TAl}us<4+#guJeLUtHW&H%!jddR7s8)TBnDZ=Vj&rw|2m zDlQgvKH$lR>RLwGjOK@QuKs)181Ho886WE$z@u^Mue+j%j4&E=YD9}`$F6B-^?ccV z{oPNhZlVwL#O~-RoA)z8=UhZ}TF=7LJ22H0Un)IJ(mbWu!rcYpa!t2vAU$7u~HSKo!^IghEp8~zooVH7lYe|Of3dd|8|*AVtT}<++5YKZn2!&QmQBLa>VXnD#xBUTwbsLI zVa&R>NYHLdopm+&5q`$3NnWy4--0+Pk;E$z`6<(vZ2x-F~FmS23cy+_K=eo{G;j zKRuxa*K!_-w3tFt<5FdKW4iS{rc(=}Kb0w0y}OUpL!mpa>N<|*9=Aw;z(++W1{j0F zPI}1hr_qh=o$iy92=(OKqUmHPUdsol+D<9XR#sA3$rsqE@^kJHmF zmbw!juRpt$-;B30yKdPUNL3GB5^6D0&ngb)kIm(gZV-F&p7F336kywn-CaYuVOw=N zUjLD+Q(sSoo1P&~%B)SLw64|WvXdom_zWerFaMS7zRnXn1*Su*Q$I=!CGX|5~Oi$w<+W0Lm5`;ex{r@h7;m$ik<^L zsWuULZLs0&jN-WOh{fI=6m_jt(DCHn((Xov>|>6SMgc0F{ow++3!!RU3m=R&WqcWi zc#QR}bn#M=V~TuplLy_EI;*S~^t4^~(M<>N`^w9hRg8uk(MjBc#A(qoGPhM&AIPI+ z+;D6amXgxsP+)hE%5FZ67~H_d!dDtEMwkt8^$T!JQxe{<$Moh?VIsNn>is<$WbR_`bbM3kqIZLP;k0>Ps;c47%v-@Vg$df%VY5oK{c zt2E~HINgqHUK-q;DNsFl%h+J4KFW8a0g|*?u#qxXMY!~dekc&lBfVKie{Ngc_4vr> zl6tFqe9%<2W#6rNA(FZQ+VqP>&jg0)W4Ue%Zn|xRvQaaA+IwU)RV^ESWtX^%xJ$)# zo(u2dzo_DA;2yQ_#u`uCk)c*LxL4*Mq8dOzTD9MjZT1H+H^ z5ON;0oJFNgtZd-2Qdf#vm^t546$Z0MfS~=eF-yUSBd*#tL0a_XS(iaZ#p01sBqo@p zaX3@Rtlnza_S3-D`Q5%k{Thidq3$qwdSK^Nh{k2#?#7d6M+d&9br|b1lg6-uPo-rf z9vz?xaL#ZI%BU21pJ^ZSp4!2EBg53U-r(rS;ygahs)SB=vn1{9SWe|@5aHyTt9;{W zGwq~1foWgqDN;n6t1Sa%zV0sx{umq+eGL;{o8RGD=l1a;(E`9l0*BbVkB*4*Xmokv z{#Gj?VF(eu ziwIG_k$d0wy?1@zKkr)K``>*mvz~MI-oL%~@9bxVz!mLc>)?z4xcj&w00?gfTRc4P>G9|0o}BfR zDi`(Spb*e*`OT+zgL_m>{#Nj3;vCfduCbcDek{U}E}V-j9Qmvh|bPKH~_O&zV=%q)34OMa$Q3X$%>Q z+Jy1@^5w1RX**ZGA4v}Ry;%_GY3Vpr*oWwJzoT1&y!S;4)W{rX)Rt{EcOKSh-#DT? zmt3x7xV7oAjlFQ<@#XK+N7p>Pzu267NDy<8qQh{Df9FxGi7So#%7`~8r`1?VAuwii zWe~19nQ9i)v`WFBkAIgg3$K*Y6FDKQ- z5c3TM+?oQj@WH+85427-k7aM6@}vXDt=5*c1Ra>Heb_!bb!RxK4_1k# z@AgTinbM^$cUW__@3gk>d~to3s&t=C!w3I;1Nx_R<<)xwbM;qMMgm9;)A53uS}vqZ ziHSPjZgPoU*$kvC=Q?X6TEcH|&2sf0w_ZPH3#JySE=w~|z#Get8PnU8IZP&7#LMg) z!4&v}DbRNJ05O6&A^o4^C2D{Cuz10>?=kQ9=_+UV@w&BGFF~^Ap6l$~zb7one*9h6t}##G;SrW_DIu;JqAA

    Rg%L{ZkooGEsxn(rig; z04>(ts~~=tK2a59Sa8f#zA(+h7b6O)d|aDlfuu$EAjZ@bAm=B z&!-#24YG^*NO*LfMx3%v+db7wF&H0Le!W3{eej@hs&4Cf&JIN~@UWrwx#L-35b7}3 zFc8f6g(oqnxl!{DkSM@w_^@n^EmX(rp3KkEN{Ty zCo${f@+5fX3jCOQ974r;G9%6;77sHNNUByepotxJ;;N|cgX?jGPSBbre{Yl75;?fO zOq_(B+~ldU15pMae}5f^!A5IV)hQe*5?DS8xL%<_8)5mg;cZd^IT1bYghSC1U^A&> zvx8qZrI}aH#kjaqp`hp+y*vFv9y)i^(AoLBRw{76e?m$d`H%X4!zD-CK|QdYyIbb>D;g>RT!%3L6%=h-($w&P)@0<)&_! zteLsZ^e^>yr-rS|Bl0bsHHk=0uWU3BOEz;OcF>vZIUl1^>HWnSR9?adjU2^#C%;RZ zuWz=j1sLl{GxZR?Dp0zMG_kfUP8jVBwWQ=@G9cyh%rw9j30zP3+EO5;m(Hx|M#@jJ zsQNjnoajxZ)^wzXxtT&RL?9<6|J>(k{Ca3HDgU&A0TB7)vx(phzNC5c6?*A&qx;nr z*~2?b9c{5q@89cA%5On~>zy&!qQ2Tn3=M^yS-YWf|YO86pU)Fj3rZb$ZX5R>1{M|v2n&%+zj9c6Hi?{nI(lF`dt52P;E|4#xyv4{HEHrlrCv??*$u!TUx4}E zaque?yvsi)biUj??q@zxz~bFE=EL@Dk2{lQ2-_N(s1_QaaS^$!xA0i-*=r<(8>}NM zKRnbag-x;hMBWtec5}RbsE|yi9e%6to9G7yIqeEri#@&&Q}i=WiX8ln+Cb(p)R+4n z-w{&zHirw?nS=G2Eg|-B+HIwntLd^%%)S9`%XiAqu*-o^&pEVB{d7VJjqyl(THGw(cW7cf+iZ!ztSiFnjSA^5sudWPL zo}}Y(OQDG%ZgM)3484=yPwDQCgOPMFuSD8Bn3^S(bE;`ICsVYIgO1!2&Vi_us3uiL z<_FfSB#C!xii|<{T?9{moF@9_3q+)HD#16NSy#7F@h^6BJi9)Dc^GHVBw64$%~R2& zA6waAW+D5zYnPXxuButGse82}I0>7RhI!#;8yEgc@6%Ayeh2D?@G>xh$3QBwGZ^ST z7(WeIAjWT_fBiGQI*jD?aa}SPtXOE50&cE+TWHEk6eO0PIq>+71f#C&gzstwI-U$@ zGx2EB-^l9lElgG^N|YQTrDDnG(3EuU+qg!4ihaOTaL37&aCuD)Gz5~j)Wu)KUbw0&l z58w^gugZGGg*cF_=KKN<)rq_a!G}C&+qATNSqv?34kW5@pV6XfRG)Y%$kPKx-IS=( z;^N@ly#0-Uf5LSL-}|JU+bzmq^wp<@7QV-8TuS*YKT{?6K7yG8NVVw4NOG@!Cj!fb zfI`b24|h7@5hw+)Y#7mU9DyreD;pA)G|aA8c^0RtN)g#p31#YE6+lakzpVV|Z?EBr zDlZ7*fQ~d+TQQo*CQ*6Lg;YwVT8~Un1NDg2xzvsKpKxR_H4__ zZ&<2rLw^b~s~49BsfoT;5YqX+fSTL#x!tOR$%F6kbd!CL$goGvL7|d{^;nPY(*maK zE+d=v_75XECAv4S^PZY&m`}>EvGa+tcO*DHIJp`$?fIBm`?Ha7k%FSwo5dRjQ)5iD z<%;q7rys^w0|$;|pH?rVzp`nx;TqJE3A+W9&9okwdue`~&FBW6mX~?bD^l`vYPu>9 zOF0_}sZP)CZ9HtRQ-dvpAA~5k zW8Hiv)q5(}2bvU=ethLPt@sZ9( z4Y>^KE3NQ)ZXY01VU8?**_5sbrd!<7Tgo3mF&b6N0`6kwA;6*vtCrQkB^oUjq`i9d z(+-Xn#@w;3u)5Kl$knqKwM&Ad4|FAZW#VIUMyOZ43qaX~8^^QUfi# z_?D)#8DONM{QUiNFYb1+Mdzd23`2y?;+!=kQsNEhy#|KDSJZy^Ba>dM;CsiC(zTK< z0iV=vJ{!^fqNnRDppAJ&{PEG8>SNn*UdEuI`lcz}btMz&j_Gh(6~`BM0=Zau-)!-} zF(z_l{K6~>O3rN{2G)NbeQZj}Vv>(O=oBNR@9oJ%c4W@i&c4+_%%R@n0k|rJeg3%qH9VJclHDUH$Iy+$5cgKfsb=Ms?oN*H={K>5YOr?B2jA5+6bi z)buAoFiqC+ntUN0U<(qXT|>1WMX3;#l?&~%f2azGwNv1D0&JnW2MtS~(1gjZ58nMO z3$cD)h0bRbN0?Cby$kM9e;(;&^Ti2_>N;b;Uh}ERt;26eaeDimFC3s&sv@`9{5k0>iQrWa+VTD3$Pa=i$+XEcIf6 z*eOe|4#(;TjaEvgazdsG1U z7xE2xl_GQms@AR1XW`tG>M^lz=gnMqVdd-d3&llYMF6tE;JOBBz6P~N7aHV(HgeM2 zU5$Q;jb6b+#iHX^;|L3FnbzP+eal9j^8y59P-@+9gzY-!X>#bwQA1SXJ1@8NrGV|h z;S5mP)!j!Ol@FwDFHkP5X=jhMEfQ? zgN9|XyNCb_|K4@C+wUBcL2%0f%$J2?qmAMK?elgWMRU_-a6go@Jeo_5Ix91Qys(Tq z&yb^2<;71rwsZC_&=U=IW8%1*6#0q~n@4RI^Io;KZs>MRa<1TXM(p_w{Ln^)A}DsQ zt7aCAe>(X7*~H%Di}!szYw-yTvIOne_njX1^nV8TvI35?dm}g10$(VVlQm@wODzS5 zm}k25Zl5Oh3^PU|Y}_Ji30cgta- z`2Y-aK?*_PE;a}uZ=@^k76cDZ?vA%B6y}6*2iPF&98eJ8PGc(&-~fjJjU_aNHC>ev z_6};kXoSA6mI2Jy2_^#v-jOGl^9JJpkO+4uz#Hj|!hpRYz~8uF-23G;2nhJC;_d_i znrP|(lwHsWfVhyjkg%Ytw}YoBP@WthhlbmN^;GWu34t3yfcEb0u3!+z%gam1OH9ZG zZ3hyOk&yuji-JT&1#udJ7$1~7)LRgR;kbnO149LYfuS8--5p#|fJ;oMjf;mn1PH{* z0so2*>8h#uZ+H~uPZn@|fV`ouAQ2&95E2Rcs|Chg)e{HuXF&f?3ycBovIwMyz_@sz zVF*=E1j?P`uMlw9zwKQ;(9XZpfx|!uX9NY6(Lwz#Cg&H?HA+X_ea z-!$DFZ2v>n-(tIz{7&buf#A&ljr%w4f93vL8K5P@Q82_M6b@X- z0f!?hE@5i}m$VTS78j8b6h}zH1)*?+s31&I1|}^cCMqn9u>A{!HrfGKl~CuuMs*1V z$3aQJMWJE{X)!@tF)0Z_aY<3AAXG%gMi4G84TB29VKSmn#BV4#41CuGjfCQs(*X&! zLx5aScE1Iego71z)FD7oA>seb=r}{&ZE*$=-~$JghxdO31`bGszB}}iO%X|4v|`fY zBBCO=n1%mhZG=E$aFuw8DIzQ+_J`zhS-`ktaKu6{>l6p@8y1%fSQ(9gy1SqaTwI(X zz{`*TmzKZF8zA?`qNq7wa2h_B75`_=>m%I$82#}HI6M3n0RX?t77T^`;RFNqM8JPL z!rA>Hg4sh+b_m?}{bxb_Yu@4iwOBGDl5lBTgrJBx9Ew{k8@Qk}94aOVx52S1CJdE< zLB;=$j&ZSd_kyAkigvh6aoOMs=yx^%-rrR6{axG39&yQ&u&5ZW90Wx~4MZfsqLN?< zQ9)rTFpg8up9zC5zv_QwEC>3(IFb9U@Rv4#v-@KX*Isbl3iR)G^(SYSH2x2tKiA@a z=m7`)kCXq3-+$=(hpzvMf&WVRpX&ODuK$XG|4R9v>iYji7x{kmx-=Gi(5JabshpYA*>&0dk=3FD_dvp8!yF3m0?!@2q&Jl0!kbc-UE9iqU8 z4v(ULbp(>^#&YA~g;3xTFyc|y;Q?In73K*p2Sh@6yFuypp;eM3O-Irh9a9N&vI)@{ zW>*#FD`ZWyITi+UgYIN>XgV{kIW`gG>uku{egs@c=tpSZJBeqg@Ayz>|^EMqX5#z&ylPbLz%fSfV z90)ee2#Y;&$~r-5xzJX#N*u-XretagKcA!#iS24-aIa{IGHt>{A_6+7dmw|64Y6Q4k z^+8?Kgi;7Bg@w35SZ07sMu$hl+QgL^%{i}Tt+6ggulW${q6t5{yFTgr$AnUiqe?NPLi za+;{#+=t3$bm)$j31%~2^lr~S{|31TeCE&~G=Rm-jxL?Qa%f05@uVKVR%|eC(nDUm zGrmnGFf&p#qgOcmHr-_hv=LLTO}}0EA>iRWIaa)_3=tfcxUb%aCbF4R^2!cr+&Nn3 zch!D7^*Ed0uxv|LX?__sm`HOn=tJO@rg$QZmqgm04k)@_M@sZ<%U`cKw!C+UzRvu$ zYDX1S1LjbX$Y-!)d8@;9Etk1>zbdvA{q*&G z3P=6wD)98@+37toLvk#pAK;o~i1tv*@6TeJ>^-=bx*=OZxBDSuk`NiIpVt%}?Y(F1 zS8FMg;<;Db|0@`)G@rs;GphQ^bC?y!$q92WuluMOw;ac5Diy%>nhebf*-Y*Rmuu01nm;dG z_E5sr@MGetM=CnEti(N|W|>ecNL%*c9xasv-E6PwD}_=sv-6G6iF$ZtNXejE+eyoN z)vw~mGz4GZ$vb&6bCiyF7Sl7FG%RYeR@WxPY(uRCX zwwQc9;hvYKT-kfg8#Af&O3spxV`EE3)3q1+cnx0jehvEua>n(a5@OwmHUHHUFv{(~ zby_p>9TC{@u+Bx)*V6o(H^mHF{*Q1(n`Lh!{~-Sd{fAOaFkg9}(<>bZ{*ZdJQUk(@ z(?Y&`D|&QfGs>ZB+{5lax1)0ckao>-gO~??@{d@?Q35Zj_6Ak<&kKL~Sw5+*@6-I! z&3d*Kqxj_mvfN3=Yqez{pjFa1C;t77tQLr?=O?$B#n&@I6f+^~eygQnNK@#SUXuMg zM;uo}8GWtVN~lg1=g-AV_#?MHVumznnmj_CA+5%gxfz=rSCyn}3NagmZWcl3VvUYcxmEm1|JdqaYSb1$@!52=={ zkD;t(hg-HEafBQrL90WgqHz@2%-0B%iiLp>qtv}!HgHMl_P8F=w+Z=exyVD^ABKsk ze(r|byuHUa=UxN|pCM*ui(XeV+2)Xx2rYfI?8yKwSZWX8=eYBw`m$Nli(CGJMUXNz zyqh*j9T6}K!AiSgrL)Lq&PldC#%`Jl^&D@1SC8Ao_P$-$3%o&KsJwK3c;9cuU{Zv% zVVtO0$SnP^X)EyKr$>T=vEEM{=c%6d{-Pc$U*1A~ zPN`|C_kC*QHYqC}JzNqegi%1$3jCn;;*;EPJp@StvZjw&OWc{*gA5QcZWjErqO+lzyEv2Ct0x zn;rW71YR0k6XM=dGj})HGJKRvpsXyBn~Bj!se&`+wYsoOnye=tvdKe~L6)mO1DX0; z$lRG}?s%S_OzHeI4|yrsDBfuosgsOzsz-O^2*w6e)p)3B#i7Fjl@O$FRoeG)7 kpF5Sy!T;t_a5-a?x?3B4s`UuB0mQ>oSJhG}Rk9BKKfs2~hyVZp diff --git a/docs/_build/html/_static/minus.png b/docs/_build/html/_static/minus.png deleted file mode 100644 index d96755fdaf8bb2214971e0db9c1fd3077d7c419d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 90 zcmeAS@N?(olHy`uVBq!ia0vp^+#t*WBp7;*Yy1LIik>cxAr*|t7R?Mi>2?kWtu=nj kDsEF_5m^0CR;1wuP-*O&G^0G}KYk!hp00i_>zopr08q^qX#fBK diff --git a/docs/_build/html/_static/plus.png b/docs/_build/html/_static/plus.png deleted file mode 100644 index 7107cec93a979b9a5f64843235a16651d563ce2d..0000000000000000000000000000000000000000 GIT binary patch literal 0 HcmV?d00001 literal 90 zcmeAS@N?(olHy`uVBq!ia0vp^+#t*WBp7;*Yy1LIik>cxAr*|t7R?Mi>2?kWtu>-2 m3q%Vub%g%s<8sJhVPMczOq}xhg9DJoz~JfX=d#Wzp$Pyb1r*Kz diff --git a/docs/_build/html/_static/pygments.css b/docs/_build/html/_static/pygments.css deleted file mode 100644 index c2e07c71e..000000000 --- a/docs/_build/html/_static/pygments.css +++ /dev/null @@ -1,258 +0,0 @@ -.highlight pre { line-height: 125%; } -.highlight td.linenos .normal { color: inherit; background-color: transparent; padding-left: 5px; padding-right: 5px; } -.highlight span.linenos { color: inherit; background-color: transparent; padding-left: 5px; padding-right: 5px; } -.highlight td.linenos .special { color: #000000; background-color: #ffffc0; padding-left: 5px; padding-right: 5px; } -.highlight span.linenos.special { color: #000000; background-color: #ffffc0; padding-left: 5px; padding-right: 5px; } -.highlight .hll { background-color: #ffffcc } -.highlight { background: #f8f8f8; } -.highlight .c { color: #8f5902; font-style: italic } /* Comment */ -.highlight .err { color: #a40000; border: 1px solid #ef2929 } /* Error */ -.highlight .g { color: #000000 } /* Generic */ -.highlight .k { color: #204a87; font-weight: bold } /* Keyword */ -.highlight .l { color: #000000 } /* Literal */ -.highlight .n { color: #000000 } /* Name */ -.highlight .o { color: #ce5c00; font-weight: bold } /* Operator */ -.highlight .x { color: #000000 } /* Other */ -.highlight .p { color: #000000; font-weight: bold } /* Punctuation */ -.highlight .ch { color: #8f5902; font-style: italic } /* Comment.Hashbang */ -.highlight .cm { color: #8f5902; font-style: italic } /* Comment.Multiline */ -.highlight .cp { color: #8f5902; font-style: italic } /* Comment.Preproc */ -.highlight .cpf { color: #8f5902; font-style: italic } /* Comment.PreprocFile */ -.highlight .c1 { color: #8f5902; font-style: italic } /* Comment.Single */ -.highlight .cs { color: #8f5902; font-style: italic } /* Comment.Special */ -.highlight .gd { color: #a40000 } /* Generic.Deleted */ -.highlight .ge { color: #000000; font-style: italic } /* Generic.Emph */ -.highlight .ges { color: #000000; font-weight: bold; font-style: italic } /* Generic.EmphStrong */ -.highlight .gr { color: #ef2929 } /* Generic.Error */ -.highlight .gh { color: #000080; font-weight: bold } /* Generic.Heading */ -.highlight .gi { color: #00A000 } /* Generic.Inserted */ -.highlight .go { color: #000000; font-style: italic } /* Generic.Output */ -.highlight .gp { color: #8f5902 } /* Generic.Prompt */ -.highlight .gs { color: #000000; font-weight: bold } /* Generic.Strong */ -.highlight .gu { color: #800080; font-weight: bold } /* Generic.Subheading */ -.highlight .gt { color: #a40000; font-weight: bold } /* Generic.Traceback */ -.highlight .kc { color: #204a87; font-weight: bold } /* Keyword.Constant */ -.highlight .kd { color: #204a87; font-weight: bold } /* Keyword.Declaration */ -.highlight .kn { color: #204a87; font-weight: bold } /* Keyword.Namespace */ -.highlight .kp { color: #204a87; font-weight: bold } /* Keyword.Pseudo */ -.highlight .kr { color: #204a87; font-weight: bold } /* Keyword.Reserved */ -.highlight .kt { color: #204a87; font-weight: bold } /* Keyword.Type */ -.highlight .ld { color: #000000 } /* Literal.Date */ -.highlight .m { color: #0000cf; font-weight: bold } /* Literal.Number */ -.highlight .s { color: #4e9a06 } /* Literal.String */ -.highlight .na { color: #c4a000 } /* Name.Attribute */ -.highlight .nb { color: #204a87 } /* Name.Builtin */ -.highlight .nc { color: #000000 } /* Name.Class */ -.highlight .no { color: #000000 } /* Name.Constant */ -.highlight .nd { color: #5c35cc; font-weight: bold } /* Name.Decorator */ -.highlight .ni { color: #ce5c00 } /* Name.Entity */ -.highlight .ne { color: #cc0000; font-weight: bold } /* Name.Exception */ -.highlight .nf { color: #000000 } /* Name.Function */ -.highlight .nl { color: #f57900 } /* Name.Label */ -.highlight .nn { color: #000000 } /* Name.Namespace */ -.highlight .nx { color: #000000 } /* Name.Other */ -.highlight .py { color: #000000 } /* Name.Property */ -.highlight .nt { color: #204a87; font-weight: bold } /* Name.Tag */ -.highlight .nv { color: #000000 } /* Name.Variable */ -.highlight .ow { color: #204a87; font-weight: bold } /* Operator.Word */ -.highlight .pm { color: #000000; font-weight: bold } /* Punctuation.Marker */ -.highlight .w { color: #f8f8f8 } /* Text.Whitespace */ -.highlight .mb { color: #0000cf; font-weight: bold } /* Literal.Number.Bin */ -.highlight .mf { color: #0000cf; font-weight: bold } /* Literal.Number.Float */ -.highlight .mh { color: #0000cf; font-weight: bold } /* Literal.Number.Hex */ -.highlight .mi { color: #0000cf; font-weight: bold } /* Literal.Number.Integer */ -.highlight .mo { color: #0000cf; font-weight: bold } /* Literal.Number.Oct */ -.highlight .sa { color: #4e9a06 } /* Literal.String.Affix */ -.highlight .sb { color: #4e9a06 } /* Literal.String.Backtick */ -.highlight .sc { color: #4e9a06 } /* Literal.String.Char */ -.highlight .dl { color: #4e9a06 } /* Literal.String.Delimiter */ -.highlight .sd { color: #8f5902; font-style: italic } /* Literal.String.Doc */ -.highlight .s2 { color: #4e9a06 } /* Literal.String.Double */ -.highlight .se { color: #4e9a06 } /* Literal.String.Escape */ -.highlight .sh { color: #4e9a06 } /* Literal.String.Heredoc */ -.highlight .si { color: #4e9a06 } /* Literal.String.Interpol */ -.highlight .sx { color: #4e9a06 } /* Literal.String.Other */ -.highlight .sr { color: #4e9a06 } /* Literal.String.Regex */ -.highlight .s1 { color: #4e9a06 } /* Literal.String.Single */ -.highlight .ss { color: #4e9a06 } /* Literal.String.Symbol */ -.highlight .bp { color: #3465a4 } /* Name.Builtin.Pseudo */ -.highlight .fm { color: #000000 } /* Name.Function.Magic */ -.highlight .vc { color: #000000 } /* Name.Variable.Class */ -.highlight .vg { color: #000000 } /* Name.Variable.Global */ -.highlight .vi { color: #000000 } /* Name.Variable.Instance */ -.highlight .vm { color: #000000 } /* Name.Variable.Magic */ -.highlight .il { color: #0000cf; font-weight: bold } /* Literal.Number.Integer.Long */ -@media not print { -body[data-theme="dark"] .highlight pre { line-height: 125%; } -body[data-theme="dark"] .highlight td.linenos .normal { color: #aaaaaa; background-color: transparent; padding-left: 5px; padding-right: 5px; } -body[data-theme="dark"] .highlight span.linenos { color: #aaaaaa; background-color: transparent; padding-left: 5px; padding-right: 5px; } -body[data-theme="dark"] .highlight td.linenos .special { color: #000000; background-color: #ffffc0; padding-left: 5px; padding-right: 5px; } -body[data-theme="dark"] .highlight span.linenos.special { color: #000000; background-color: #ffffc0; padding-left: 5px; padding-right: 5px; } -body[data-theme="dark"] .highlight .hll { background-color: #404040 } -body[data-theme="dark"] .highlight { background: #202020; color: #d0d0d0 } -body[data-theme="dark"] .highlight .c { color: #ababab; font-style: italic } /* Comment */ -body[data-theme="dark"] .highlight .err { color: #a61717; background-color: #e3d2d2 } /* Error */ -body[data-theme="dark"] .highlight .esc { color: #d0d0d0 } /* Escape */ -body[data-theme="dark"] .highlight .g { color: #d0d0d0 } /* Generic */ -body[data-theme="dark"] .highlight .k { color: #6ebf26; font-weight: bold } /* Keyword */ -body[data-theme="dark"] .highlight .l { color: #d0d0d0 } /* Literal */ -body[data-theme="dark"] .highlight .n { color: #d0d0d0 } /* Name */ -body[data-theme="dark"] .highlight .o { color: #d0d0d0 } /* Operator */ -body[data-theme="dark"] .highlight .x { color: #d0d0d0 } /* Other */ -body[data-theme="dark"] .highlight .p { color: #d0d0d0 } /* Punctuation */ -body[data-theme="dark"] .highlight .ch { color: #ababab; font-style: italic } /* Comment.Hashbang */ -body[data-theme="dark"] .highlight .cm { color: #ababab; font-style: italic } /* Comment.Multiline */ -body[data-theme="dark"] .highlight .cp { color: #ff3a3a; font-weight: bold } /* Comment.Preproc */ -body[data-theme="dark"] .highlight .cpf { color: #ababab; font-style: italic } /* Comment.PreprocFile */ -body[data-theme="dark"] .highlight .c1 { color: #ababab; font-style: italic } /* Comment.Single */ -body[data-theme="dark"] .highlight .cs { color: #e50808; font-weight: bold; background-color: #520000 } /* Comment.Special */ -body[data-theme="dark"] .highlight .gd { color: #d22323 } /* Generic.Deleted */ -body[data-theme="dark"] .highlight .ge { color: #d0d0d0; font-style: italic } /* Generic.Emph */ -body[data-theme="dark"] .highlight .ges { color: #d0d0d0; font-weight: bold; font-style: italic } /* Generic.EmphStrong */ -body[data-theme="dark"] .highlight .gr { color: #d22323 } /* Generic.Error */ -body[data-theme="dark"] .highlight .gh { color: #ffffff; font-weight: bold } /* Generic.Heading */ -body[data-theme="dark"] .highlight .gi { color: #589819 } /* Generic.Inserted */ -body[data-theme="dark"] .highlight .go { color: #cccccc } /* Generic.Output */ -body[data-theme="dark"] .highlight .gp { color: #aaaaaa } /* Generic.Prompt */ -body[data-theme="dark"] .highlight .gs { color: #d0d0d0; font-weight: bold } /* Generic.Strong */ -body[data-theme="dark"] .highlight .gu { color: #ffffff; text-decoration: underline } /* Generic.Subheading */ -body[data-theme="dark"] .highlight .gt { color: #d22323 } /* Generic.Traceback */ -body[data-theme="dark"] .highlight .kc { color: #6ebf26; font-weight: bold } /* Keyword.Constant */ -body[data-theme="dark"] .highlight .kd { color: #6ebf26; font-weight: bold } /* Keyword.Declaration */ -body[data-theme="dark"] .highlight .kn { color: #6ebf26; font-weight: bold } /* Keyword.Namespace */ -body[data-theme="dark"] .highlight .kp { color: #6ebf26 } /* Keyword.Pseudo */ -body[data-theme="dark"] .highlight .kr { color: #6ebf26; font-weight: bold } /* Keyword.Reserved */ -body[data-theme="dark"] .highlight .kt { color: #6ebf26; font-weight: bold } /* Keyword.Type */ -body[data-theme="dark"] .highlight .ld { color: #d0d0d0 } /* Literal.Date */ -body[data-theme="dark"] .highlight .m { color: #51b2fd } /* Literal.Number */ -body[data-theme="dark"] .highlight .s { color: #ed9d13 } /* Literal.String */ -body[data-theme="dark"] .highlight .na { color: #bbbbbb } /* Name.Attribute */ -body[data-theme="dark"] .highlight .nb { color: #2fbccd } /* Name.Builtin */ -body[data-theme="dark"] .highlight .nc { color: #71adff; text-decoration: underline } /* Name.Class */ -body[data-theme="dark"] .highlight .no { color: #40ffff } /* Name.Constant */ -body[data-theme="dark"] .highlight .nd { color: #ffa500 } /* Name.Decorator */ -body[data-theme="dark"] .highlight .ni { color: #d0d0d0 } /* Name.Entity */ -body[data-theme="dark"] .highlight .ne { color: #bbbbbb } /* Name.Exception */ -body[data-theme="dark"] .highlight .nf { color: #71adff } /* Name.Function */ -body[data-theme="dark"] .highlight .nl { color: #d0d0d0 } /* Name.Label */ -body[data-theme="dark"] .highlight .nn { color: #71adff; text-decoration: underline } /* Name.Namespace */ -body[data-theme="dark"] .highlight .nx { color: #d0d0d0 } /* Name.Other */ -body[data-theme="dark"] .highlight .py { color: #d0d0d0 } /* Name.Property */ -body[data-theme="dark"] .highlight .nt { color: #6ebf26; font-weight: bold } /* Name.Tag */ -body[data-theme="dark"] .highlight .nv { color: #40ffff } /* Name.Variable */ -body[data-theme="dark"] .highlight .ow { color: #6ebf26; font-weight: bold } /* Operator.Word */ -body[data-theme="dark"] .highlight .pm { color: #d0d0d0 } /* Punctuation.Marker */ -body[data-theme="dark"] .highlight .w { color: #666666 } /* Text.Whitespace */ -body[data-theme="dark"] .highlight .mb { color: #51b2fd } /* Literal.Number.Bin */ -body[data-theme="dark"] .highlight .mf { color: #51b2fd } /* Literal.Number.Float */ -body[data-theme="dark"] .highlight .mh { color: #51b2fd } /* Literal.Number.Hex */ -body[data-theme="dark"] .highlight .mi { color: #51b2fd } /* Literal.Number.Integer */ -body[data-theme="dark"] .highlight .mo { color: #51b2fd } /* Literal.Number.Oct */ -body[data-theme="dark"] .highlight .sa { color: #ed9d13 } /* Literal.String.Affix */ -body[data-theme="dark"] .highlight .sb { color: #ed9d13 } /* Literal.String.Backtick */ -body[data-theme="dark"] .highlight .sc { color: #ed9d13 } /* Literal.String.Char */ -body[data-theme="dark"] .highlight .dl { color: #ed9d13 } /* Literal.String.Delimiter */ -body[data-theme="dark"] .highlight .sd { color: #ed9d13 } /* Literal.String.Doc */ -body[data-theme="dark"] .highlight .s2 { color: #ed9d13 } /* Literal.String.Double */ -body[data-theme="dark"] .highlight .se { color: #ed9d13 } /* Literal.String.Escape */ -body[data-theme="dark"] .highlight .sh { color: #ed9d13 } /* Literal.String.Heredoc */ -body[data-theme="dark"] .highlight .si { color: #ed9d13 } /* Literal.String.Interpol */ -body[data-theme="dark"] .highlight .sx { color: #ffa500 } /* Literal.String.Other */ -body[data-theme="dark"] .highlight .sr { color: #ed9d13 } /* Literal.String.Regex */ -body[data-theme="dark"] .highlight .s1 { color: #ed9d13 } /* Literal.String.Single */ -body[data-theme="dark"] .highlight .ss { color: #ed9d13 } /* Literal.String.Symbol */ -body[data-theme="dark"] .highlight .bp { color: #2fbccd } /* Name.Builtin.Pseudo */ -body[data-theme="dark"] .highlight .fm { color: #71adff } /* Name.Function.Magic */ -body[data-theme="dark"] .highlight .vc { color: #40ffff } /* Name.Variable.Class */ -body[data-theme="dark"] .highlight .vg { color: #40ffff } /* Name.Variable.Global */ -body[data-theme="dark"] .highlight .vi { color: #40ffff } /* Name.Variable.Instance */ -body[data-theme="dark"] .highlight .vm { color: #40ffff } /* Name.Variable.Magic */ -body[data-theme="dark"] .highlight .il { color: #51b2fd } /* Literal.Number.Integer.Long */ -@media (prefers-color-scheme: dark) { -body:not([data-theme="light"]) .highlight pre { line-height: 125%; } -body:not([data-theme="light"]) .highlight td.linenos .normal { color: #aaaaaa; background-color: transparent; padding-left: 5px; padding-right: 5px; } -body:not([data-theme="light"]) .highlight span.linenos { color: #aaaaaa; background-color: transparent; padding-left: 5px; padding-right: 5px; } -body:not([data-theme="light"]) .highlight td.linenos .special { color: #000000; background-color: #ffffc0; padding-left: 5px; padding-right: 5px; } -body:not([data-theme="light"]) .highlight span.linenos.special { color: #000000; background-color: #ffffc0; padding-left: 5px; padding-right: 5px; } -body:not([data-theme="light"]) .highlight .hll { background-color: #404040 } -body:not([data-theme="light"]) .highlight { background: #202020; color: #d0d0d0 } -body:not([data-theme="light"]) .highlight .c { color: #ababab; font-style: italic } /* Comment */ -body:not([data-theme="light"]) .highlight .err { color: #a61717; background-color: #e3d2d2 } /* Error */ -body:not([data-theme="light"]) .highlight .esc { color: #d0d0d0 } /* Escape */ -body:not([data-theme="light"]) .highlight .g { color: #d0d0d0 } /* Generic */ -body:not([data-theme="light"]) .highlight .k { color: #6ebf26; font-weight: bold } /* Keyword */ -body:not([data-theme="light"]) .highlight .l { color: #d0d0d0 } /* Literal */ -body:not([data-theme="light"]) .highlight .n { color: #d0d0d0 } /* Name */ -body:not([data-theme="light"]) .highlight .o { color: #d0d0d0 } /* Operator */ -body:not([data-theme="light"]) .highlight .x { color: #d0d0d0 } /* Other */ -body:not([data-theme="light"]) .highlight .p { color: #d0d0d0 } /* Punctuation */ -body:not([data-theme="light"]) .highlight .ch { color: #ababab; font-style: italic } /* Comment.Hashbang */ -body:not([data-theme="light"]) .highlight .cm { color: #ababab; font-style: italic } /* Comment.Multiline */ -body:not([data-theme="light"]) .highlight .cp { color: #ff3a3a; font-weight: bold } /* Comment.Preproc */ -body:not([data-theme="light"]) .highlight .cpf { color: #ababab; font-style: italic } /* Comment.PreprocFile */ -body:not([data-theme="light"]) .highlight .c1 { color: #ababab; font-style: italic } /* Comment.Single */ -body:not([data-theme="light"]) .highlight .cs { color: #e50808; font-weight: bold; background-color: #520000 } /* Comment.Special */ -body:not([data-theme="light"]) .highlight .gd { color: #d22323 } /* Generic.Deleted */ -body:not([data-theme="light"]) .highlight .ge { color: #d0d0d0; font-style: italic } /* Generic.Emph */ -body:not([data-theme="light"]) .highlight .ges { color: #d0d0d0; font-weight: bold; font-style: italic } /* Generic.EmphStrong */ -body:not([data-theme="light"]) .highlight .gr { color: #d22323 } /* Generic.Error */ -body:not([data-theme="light"]) .highlight .gh { color: #ffffff; font-weight: bold } /* Generic.Heading */ -body:not([data-theme="light"]) .highlight .gi { color: #589819 } /* Generic.Inserted */ -body:not([data-theme="light"]) .highlight .go { color: #cccccc } /* Generic.Output */ -body:not([data-theme="light"]) .highlight .gp { color: #aaaaaa } /* Generic.Prompt */ -body:not([data-theme="light"]) .highlight .gs { color: #d0d0d0; font-weight: bold } /* Generic.Strong */ -body:not([data-theme="light"]) .highlight .gu { color: #ffffff; text-decoration: underline } /* Generic.Subheading */ -body:not([data-theme="light"]) .highlight .gt { color: #d22323 } /* Generic.Traceback */ -body:not([data-theme="light"]) .highlight .kc { color: #6ebf26; font-weight: bold } /* Keyword.Constant */ -body:not([data-theme="light"]) .highlight .kd { color: #6ebf26; font-weight: bold } /* Keyword.Declaration */ -body:not([data-theme="light"]) .highlight .kn { color: #6ebf26; font-weight: bold } /* Keyword.Namespace */ -body:not([data-theme="light"]) .highlight .kp { color: #6ebf26 } /* Keyword.Pseudo */ -body:not([data-theme="light"]) .highlight .kr { color: #6ebf26; font-weight: bold } /* Keyword.Reserved */ -body:not([data-theme="light"]) .highlight .kt { color: #6ebf26; font-weight: bold } /* Keyword.Type */ -body:not([data-theme="light"]) .highlight .ld { color: #d0d0d0 } /* Literal.Date */ -body:not([data-theme="light"]) .highlight .m { color: #51b2fd } /* Literal.Number */ -body:not([data-theme="light"]) .highlight .s { color: #ed9d13 } /* Literal.String */ -body:not([data-theme="light"]) .highlight .na { color: #bbbbbb } /* Name.Attribute */ -body:not([data-theme="light"]) .highlight .nb { color: #2fbccd } /* Name.Builtin */ -body:not([data-theme="light"]) .highlight .nc { color: #71adff; text-decoration: underline } /* Name.Class */ -body:not([data-theme="light"]) .highlight .no { color: #40ffff } /* Name.Constant */ -body:not([data-theme="light"]) .highlight .nd { color: #ffa500 } /* Name.Decorator */ -body:not([data-theme="light"]) .highlight .ni { color: #d0d0d0 } /* Name.Entity */ -body:not([data-theme="light"]) .highlight .ne { color: #bbbbbb } /* Name.Exception */ -body:not([data-theme="light"]) .highlight .nf { color: #71adff } /* Name.Function */ -body:not([data-theme="light"]) .highlight .nl { color: #d0d0d0 } /* Name.Label */ -body:not([data-theme="light"]) .highlight .nn { color: #71adff; text-decoration: underline } /* Name.Namespace */ -body:not([data-theme="light"]) .highlight .nx { color: #d0d0d0 } /* Name.Other */ -body:not([data-theme="light"]) .highlight .py { color: #d0d0d0 } /* Name.Property */ -body:not([data-theme="light"]) .highlight .nt { color: #6ebf26; font-weight: bold } /* Name.Tag */ -body:not([data-theme="light"]) .highlight .nv { color: #40ffff } /* Name.Variable */ -body:not([data-theme="light"]) .highlight .ow { color: #6ebf26; font-weight: bold } /* Operator.Word */ -body:not([data-theme="light"]) .highlight .pm { color: #d0d0d0 } /* Punctuation.Marker */ -body:not([data-theme="light"]) .highlight .w { color: #666666 } /* Text.Whitespace */ -body:not([data-theme="light"]) .highlight .mb { color: #51b2fd } /* Literal.Number.Bin */ -body:not([data-theme="light"]) .highlight .mf { color: #51b2fd } /* Literal.Number.Float */ -body:not([data-theme="light"]) .highlight .mh { color: #51b2fd } /* Literal.Number.Hex */ -body:not([data-theme="light"]) .highlight .mi { color: #51b2fd } /* Literal.Number.Integer */ -body:not([data-theme="light"]) .highlight .mo { color: #51b2fd } /* Literal.Number.Oct */ -body:not([data-theme="light"]) .highlight .sa { color: #ed9d13 } /* Literal.String.Affix */ -body:not([data-theme="light"]) .highlight .sb { color: #ed9d13 } /* Literal.String.Backtick */ -body:not([data-theme="light"]) .highlight .sc { color: #ed9d13 } /* Literal.String.Char */ -body:not([data-theme="light"]) .highlight .dl { color: #ed9d13 } /* Literal.String.Delimiter */ -body:not([data-theme="light"]) .highlight .sd { color: #ed9d13 } /* Literal.String.Doc */ -body:not([data-theme="light"]) .highlight .s2 { color: #ed9d13 } /* Literal.String.Double */ -body:not([data-theme="light"]) .highlight .se { color: #ed9d13 } /* Literal.String.Escape */ -body:not([data-theme="light"]) .highlight .sh { color: #ed9d13 } /* Literal.String.Heredoc */ -body:not([data-theme="light"]) .highlight .si { color: #ed9d13 } /* Literal.String.Interpol */ -body:not([data-theme="light"]) .highlight .sx { color: #ffa500 } /* Literal.String.Other */ -body:not([data-theme="light"]) .highlight .sr { color: #ed9d13 } /* Literal.String.Regex */ -body:not([data-theme="light"]) .highlight .s1 { color: #ed9d13 } /* Literal.String.Single */ -body:not([data-theme="light"]) .highlight .ss { color: #ed9d13 } /* Literal.String.Symbol */ -body:not([data-theme="light"]) .highlight .bp { color: #2fbccd } /* Name.Builtin.Pseudo */ -body:not([data-theme="light"]) .highlight .fm { color: #71adff } /* Name.Function.Magic */ -body:not([data-theme="light"]) .highlight .vc { color: #40ffff } /* Name.Variable.Class */ -body:not([data-theme="light"]) .highlight .vg { color: #40ffff } /* Name.Variable.Global */ -body:not([data-theme="light"]) .highlight .vi { color: #40ffff } /* Name.Variable.Instance */ -body:not([data-theme="light"]) .highlight .vm { color: #40ffff } /* Name.Variable.Magic */ -body:not([data-theme="light"]) .highlight .il { color: #51b2fd } /* Literal.Number.Integer.Long */ -} -} \ No newline at end of file diff --git a/docs/_build/html/_static/scripts/furo-extensions.js b/docs/_build/html/_static/scripts/furo-extensions.js deleted file mode 100644 index e69de29bb..000000000 diff --git a/docs/_build/html/_static/scripts/furo.js b/docs/_build/html/_static/scripts/furo.js deleted file mode 100644 index 32e7c05be..000000000 --- a/docs/_build/html/_static/scripts/furo.js +++ /dev/null @@ -1,3 +0,0 @@ -/*! For license information please see furo.js.LICENSE.txt */ -(()=>{var t={212:function(t,e,n){var o,r;r=void 0!==n.g?n.g:"undefined"!=typeof window?window:this,o=function(){return function(t){"use strict";var e={navClass:"active",contentClass:"active",nested:!1,nestedClass:"active",offset:0,reflow:!1,events:!0},n=function(t,e,n){if(n.settings.events){var o=new CustomEvent(t,{bubbles:!0,cancelable:!0,detail:n});e.dispatchEvent(o)}},o=function(t){var e=0;if(t.offsetParent)for(;t;)e+=t.offsetTop,t=t.offsetParent;return e>=0?e:0},r=function(t){t&&t.sort((function(t,e){return o(t.content)=Math.max(document.body.scrollHeight,document.documentElement.scrollHeight,document.body.offsetHeight,document.documentElement.offsetHeight,document.body.clientHeight,document.documentElement.clientHeight)},l=function(t,e){var n=t[t.length-1];if(function(t,e){return!(!s()||!c(t.content,e,!0))}(n,e))return n;for(var o=t.length-1;o>=0;o--)if(c(t[o].content,e))return t[o]},a=function(t,e){if(e.nested&&t.parentNode){var n=t.parentNode.closest("li");n&&(n.classList.remove(e.nestedClass),a(n,e))}},i=function(t,e){if(t){var o=t.nav.closest("li");o&&(o.classList.remove(e.navClass),t.content.classList.remove(e.contentClass),a(o,e),n("gumshoeDeactivate",o,{link:t.nav,content:t.content,settings:e}))}},u=function(t,e){if(e.nested){var n=t.parentNode.closest("li");n&&(n.classList.add(e.nestedClass),u(n,e))}};return function(o,c){var s,a,d,f,m,v={setup:function(){s=document.querySelectorAll(o),a=[],Array.prototype.forEach.call(s,(function(t){var e=document.getElementById(decodeURIComponent(t.hash.substr(1)));e&&a.push({nav:t,content:e})})),r(a)},detect:function(){var t=l(a,m);t?d&&t.content===d.content||(i(d,m),function(t,e){if(t){var o=t.nav.closest("li");o&&(o.classList.add(e.navClass),t.content.classList.add(e.contentClass),u(o,e),n("gumshoeActivate",o,{link:t.nav,content:t.content,settings:e}))}}(t,m),d=t):d&&(i(d,m),d=null)}},h=function(e){f&&t.cancelAnimationFrame(f),f=t.requestAnimationFrame(v.detect)},g=function(e){f&&t.cancelAnimationFrame(f),f=t.requestAnimationFrame((function(){r(a),v.detect()}))};return v.destroy=function(){d&&i(d,m),t.removeEventListener("scroll",h,!1),m.reflow&&t.removeEventListener("resize",g,!1),a=null,s=null,d=null,f=null,m=null},m=function(){var t={};return Array.prototype.forEach.call(arguments,(function(e){for(var n in e){if(!e.hasOwnProperty(n))return;t[n]=e[n]}})),t}(e,c||{}),v.setup(),v.detect(),t.addEventListener("scroll",h,!1),m.reflow&&t.addEventListener("resize",g,!1),v}}(r)}.apply(e,[]),void 0===o||(t.exports=o)}},e={};function n(o){var r=e[o];if(void 0!==r)return r.exports;var c=e[o]={exports:{}};return t[o].call(c.exports,c,c.exports,n),c.exports}n.n=t=>{var e=t&&t.__esModule?()=>t.default:()=>t;return n.d(e,{a:e}),e},n.d=(t,e)=>{for(var o in e)n.o(e,o)&&!n.o(t,o)&&Object.defineProperty(t,o,{enumerable:!0,get:e[o]})},n.g=function(){if("object"==typeof globalThis)return globalThis;try{return this||new Function("return this")()}catch(t){if("object"==typeof window)return window}}(),n.o=(t,e)=>Object.prototype.hasOwnProperty.call(t,e),(()=>{"use strict";var t=n(212),e=n.n(t),o=null,r=null,c=window.pageYOffset||document.documentElement.scrollTop;const s=64;function l(){const t=localStorage.getItem("theme")||"auto";var e;"light"!==(e=window.matchMedia("(prefers-color-scheme: dark)").matches?"auto"===t?"light":"light"==t?"dark":"auto":"auto"===t?"dark":"dark"==t?"light":"auto")&&"dark"!==e&&"auto"!==e&&(console.error(`Got invalid theme mode: ${e}. Resetting to auto.`),e="auto"),document.body.dataset.theme=e,localStorage.setItem("theme",e),console.log(`Changed to ${e} mode.`)}function a(){!function(){const t=document.getElementsByClassName("theme-toggle");Array.from(t).forEach((t=>{t.addEventListener("click",l)}))}(),function(){let t=0,e=!1;window.addEventListener("scroll",(function(n){t=window.scrollY,e||(window.requestAnimationFrame((function(){var n;n=t,0==Math.floor(r.getBoundingClientRect().top)?r.classList.add("scrolled"):r.classList.remove("scrolled"),function(t){tc&&document.documentElement.classList.remove("show-back-to-top"),c=t}(n),function(t){null!==o&&(0==t?o.scrollTo(0,0):Math.ceil(t)>=Math.floor(document.documentElement.scrollHeight-window.innerHeight)?o.scrollTo(0,o.scrollHeight):document.querySelector(".scroll-current"))}(n),e=!1})),e=!0)})),window.scroll()}(),null!==o&&new(e())(".toc-tree a",{reflow:!0,recursive:!0,navClass:"scroll-current",offset:()=>{let t=parseFloat(getComputedStyle(document.documentElement).fontSize);return r.getBoundingClientRect().height+.5*t+1}})}document.addEventListener("DOMContentLoaded",(function(){document.body.parentNode.classList.remove("no-js"),r=document.querySelector("header"),o=document.querySelector(".toc-scroll"),a()}))})()})(); -//# sourceMappingURL=furo.js.map \ No newline at end of file diff --git a/docs/_build/html/_static/scripts/furo.js.LICENSE.txt b/docs/_build/html/_static/scripts/furo.js.LICENSE.txt deleted file mode 100644 index 1632189c7..000000000 --- a/docs/_build/html/_static/scripts/furo.js.LICENSE.txt +++ /dev/null @@ -1,7 +0,0 @@ -/*! - * gumshoejs v5.1.2 (patched by @pradyunsg) - * A simple, framework-agnostic scrollspy script. - * (c) 2019 Chris Ferdinandi - * MIT License - * http://github.com/cferdinandi/gumshoe - */ diff --git a/docs/_build/html/_static/scripts/furo.js.map b/docs/_build/html/_static/scripts/furo.js.map deleted file mode 100644 index 7b7ddb113..000000000 --- a/docs/_build/html/_static/scripts/furo.js.map +++ /dev/null @@ -1 +0,0 @@ -{"version":3,"file":"scripts/furo.js","mappings":";iCAAA,MAQWA,SAWS,IAAX,EAAAC,EACH,EAAAA,EACkB,oBAAXC,OACPA,OACAC,KAbS,EAAF,WACP,OAaJ,SAAUD,GACR,aAMA,IAAIE,EAAW,CAEbC,SAAU,SACVC,aAAc,SAGdC,QAAQ,EACRC,YAAa,SAGbC,OAAQ,EACRC,QAAQ,EAGRC,QAAQ,GA6BNC,EAAY,SAAUC,EAAMC,EAAMC,GAEpC,GAAKA,EAAOC,SAASL,OAArB,CAGA,IAAIM,EAAQ,IAAIC,YAAYL,EAAM,CAChCM,SAAS,EACTC,YAAY,EACZL,OAAQA,IAIVD,EAAKO,cAAcJ,EAVgB,CAWrC,EAOIK,EAAe,SAAUR,GAC3B,IAAIS,EAAW,EACf,GAAIT,EAAKU,aACP,KAAOV,GACLS,GAAYT,EAAKW,UACjBX,EAAOA,EAAKU,aAGhB,OAAOD,GAAY,EAAIA,EAAW,CACpC,EAMIG,EAAe,SAAUC,GACvBA,GACFA,EAASC,MAAK,SAAUC,EAAOC,GAG7B,OAFcR,EAAaO,EAAME,SACnBT,EAAaQ,EAAMC,UACF,EACxB,CACT,GAEJ,EAwCIC,EAAW,SAAUlB,EAAME,EAAUiB,GACvC,IAAIC,EAASpB,EAAKqB,wBACd1B,EAnCU,SAAUO,GAExB,MAA+B,mBAApBA,EAASP,OACX2B,WAAWpB,EAASP,UAItB2B,WAAWpB,EAASP,OAC7B,CA2Be4B,CAAUrB,GACvB,OAAIiB,EAEAK,SAASJ,EAAOD,OAAQ,KACvB/B,EAAOqC,aAAeC,SAASC,gBAAgBC,cAG7CJ,SAASJ,EAAOS,IAAK,KAAOlC,CACrC,EAMImC,EAAa,WACf,OACEC,KAAKC,KAAK5C,EAAOqC,YAAcrC,EAAO6C,cAnCjCF,KAAKG,IACVR,SAASS,KAAKC,aACdV,SAASC,gBAAgBS,aACzBV,SAASS,KAAKE,aACdX,SAASC,gBAAgBU,aACzBX,SAASS,KAAKP,aACdF,SAASC,gBAAgBC,aAkC7B,EAmBIU,EAAY,SAAUzB,EAAUX,GAClC,IAAIqC,EAAO1B,EAASA,EAAS2B,OAAS,GACtC,GAbgB,SAAUC,EAAMvC,GAChC,SAAI4B,MAAgBZ,EAASuB,EAAKxB,QAASf,GAAU,GAEvD,CAUMwC,CAAYH,EAAMrC,GAAW,OAAOqC,EACxC,IAAK,IAAII,EAAI9B,EAAS2B,OAAS,EAAGG,GAAK,EAAGA,IACxC,GAAIzB,EAASL,EAAS8B,GAAG1B,QAASf,GAAW,OAAOW,EAAS8B,EAEjE,EAOIC,EAAmB,SAAUC,EAAK3C,GAEpC,GAAKA,EAAST,QAAWoD,EAAIC,WAA7B,CAGA,IAAIC,EAAKF,EAAIC,WAAWE,QAAQ,MAC3BD,IAGLA,EAAGE,UAAUC,OAAOhD,EAASR,aAG7BkD,EAAiBG,EAAI7C,GAV0B,CAWjD,EAOIiD,EAAa,SAAUC,EAAOlD,GAEhC,GAAKkD,EAAL,CAGA,IAAIL,EAAKK,EAAMP,IAAIG,QAAQ,MACtBD,IAGLA,EAAGE,UAAUC,OAAOhD,EAASX,UAC7B6D,EAAMnC,QAAQgC,UAAUC,OAAOhD,EAASV,cAGxCoD,EAAiBG,EAAI7C,GAGrBJ,EAAU,oBAAqBiD,EAAI,CACjCM,KAAMD,EAAMP,IACZ5B,QAASmC,EAAMnC,QACff,SAAUA,IAjBM,CAmBpB,EAOIoD,EAAiB,SAAUT,EAAK3C,GAElC,GAAKA,EAAST,OAAd,CAGA,IAAIsD,EAAKF,EAAIC,WAAWE,QAAQ,MAC3BD,IAGLA,EAAGE,UAAUM,IAAIrD,EAASR,aAG1B4D,EAAeP,EAAI7C,GAVS,CAW9B,EA6LA,OA1JkB,SAAUsD,EAAUC,GAKpC,IACIC,EAAU7C,EAAU8C,EAASC,EAAS1D,EADtC2D,EAAa,CAUjBA,MAAmB,WAEjBH,EAAWhC,SAASoC,iBAAiBN,GAGrC3C,EAAW,GAGXkD,MAAMC,UAAUC,QAAQC,KAAKR,GAAU,SAAUjB,GAE/C,IAAIxB,EAAUS,SAASyC,eACrBC,mBAAmB3B,EAAK4B,KAAKC,OAAO,KAEjCrD,GAGLJ,EAAS0D,KAAK,CACZ1B,IAAKJ,EACLxB,QAASA,GAEb,IAGAL,EAAaC,EACf,EAKAgD,OAAoB,WAElB,IAAIW,EAASlC,EAAUzB,EAAUX,GAG5BsE,EASDb,GAAWa,EAAOvD,UAAY0C,EAAQ1C,UAG1CkC,EAAWQ,EAASzD,GAzFT,SAAUkD,EAAOlD,GAE9B,GAAKkD,EAAL,CAGA,IAAIL,EAAKK,EAAMP,IAAIG,QAAQ,MACtBD,IAGLA,EAAGE,UAAUM,IAAIrD,EAASX,UAC1B6D,EAAMnC,QAAQgC,UAAUM,IAAIrD,EAASV,cAGrC8D,EAAeP,EAAI7C,GAGnBJ,EAAU,kBAAmBiD,EAAI,CAC/BM,KAAMD,EAAMP,IACZ5B,QAASmC,EAAMnC,QACff,SAAUA,IAjBM,CAmBpB,CAqEIuE,CAASD,EAAQtE,GAGjByD,EAAUa,GAfJb,IACFR,EAAWQ,EAASzD,GACpByD,EAAU,KAchB,GAMIe,EAAgB,SAAUvE,GAExByD,GACFxE,EAAOuF,qBAAqBf,GAI9BA,EAAUxE,EAAOwF,sBAAsBf,EAAWgB,OACpD,EAMIC,EAAgB,SAAU3E,GAExByD,GACFxE,EAAOuF,qBAAqBf,GAI9BA,EAAUxE,EAAOwF,uBAAsB,WACrChE,EAAaC,GACbgD,EAAWgB,QACb,GACF,EAkDA,OA7CAhB,EAAWkB,QAAU,WAEfpB,GACFR,EAAWQ,EAASzD,GAItBd,EAAO4F,oBAAoB,SAAUN,GAAe,GAChDxE,EAASN,QACXR,EAAO4F,oBAAoB,SAAUF,GAAe,GAItDjE,EAAW,KACX6C,EAAW,KACXC,EAAU,KACVC,EAAU,KACV1D,EAAW,IACb,EAOEA,EA3XS,WACX,IAAI+E,EAAS,CAAC,EAOd,OANAlB,MAAMC,UAAUC,QAAQC,KAAKgB,WAAW,SAAUC,GAChD,IAAK,IAAIC,KAAOD,EAAK,CACnB,IAAKA,EAAIE,eAAeD,GAAM,OAC9BH,EAAOG,GAAOD,EAAIC,EACpB,CACF,IACOH,CACT,CAkXeK,CAAOhG,EAAUmE,GAAW,CAAC,GAGxCI,EAAW0B,QAGX1B,EAAWgB,SAGXzF,EAAOoG,iBAAiB,SAAUd,GAAe,GAC7CxE,EAASN,QACXR,EAAOoG,iBAAiB,SAAUV,GAAe,GAS9CjB,CACT,CAOF,CArcW4B,CAAQvG,EAChB,UAFM,SAEN,uBCXDwG,EAA2B,CAAC,EAGhC,SAASC,EAAoBC,GAE5B,IAAIC,EAAeH,EAAyBE,GAC5C,QAAqBE,IAAjBD,EACH,OAAOA,EAAaE,QAGrB,IAAIC,EAASN,EAAyBE,GAAY,CAGjDG,QAAS,CAAC,GAOX,OAHAE,EAAoBL,GAAU1B,KAAK8B,EAAOD,QAASC,EAAQA,EAAOD,QAASJ,GAGpEK,EAAOD,OACf,CCrBAJ,EAAoBO,EAAKF,IACxB,IAAIG,EAASH,GAAUA,EAAOI,WAC7B,IAAOJ,EAAiB,QACxB,IAAM,EAEP,OADAL,EAAoBU,EAAEF,EAAQ,CAAEG,EAAGH,IAC5BA,CAAM,ECLdR,EAAoBU,EAAI,CAACN,EAASQ,KACjC,IAAI,IAAInB,KAAOmB,EACXZ,EAAoBa,EAAED,EAAYnB,KAASO,EAAoBa,EAAET,EAASX,IAC5EqB,OAAOC,eAAeX,EAASX,EAAK,CAAEuB,YAAY,EAAMC,IAAKL,EAAWnB,IAE1E,ECNDO,EAAoBxG,EAAI,WACvB,GAA0B,iBAAf0H,WAAyB,OAAOA,WAC3C,IACC,OAAOxH,MAAQ,IAAIyH,SAAS,cAAb,EAChB,CAAE,MAAOC,GACR,GAAsB,iBAAX3H,OAAqB,OAAOA,MACxC,CACA,CAPuB,GCAxBuG,EAAoBa,EAAI,CAACrB,EAAK6B,IAAUP,OAAOzC,UAAUqB,eAAenB,KAAKiB,EAAK6B,4CCK9EC,EAAY,KACZC,EAAS,KACTC,EAAgB/H,OAAO6C,aAAeP,SAASC,gBAAgByF,UACnE,MAAMC,EAAmB,GA2EzB,SAASC,IACP,MAAMC,EAAeC,aAAaC,QAAQ,UAAY,OAZxD,IAAkBC,EACH,WADGA,EAaItI,OAAOuI,WAAW,gCAAgCC,QAI/C,SAAjBL,EACO,QACgB,SAAhBA,EACA,OAEA,OAIU,SAAjBA,EACO,OACgB,QAAhBA,EACA,QAEA,SA9BoB,SAATG,GAA4B,SAATA,IACzCG,QAAQC,MAAM,2BAA2BJ,yBACzCA,EAAO,QAGThG,SAASS,KAAK4F,QAAQC,MAAQN,EAC9BF,aAAaS,QAAQ,QAASP,GAC9BG,QAAQK,IAAI,cAAcR,UA0B5B,CAkDA,SAASnC,KART,WAEE,MAAM4C,EAAUzG,SAAS0G,uBAAuB,gBAChDrE,MAAMsE,KAAKF,GAASlE,SAASqE,IAC3BA,EAAI9C,iBAAiB,QAAS8B,EAAe,GAEjD,CAGEiB,GA9CF,WAEE,IAAIC,EAA6B,EAC7BC,GAAU,EAEdrJ,OAAOoG,iBAAiB,UAAU,SAAUuB,GAC1CyB,EAA6BpJ,OAAOsJ,QAE/BD,IACHrJ,OAAOwF,uBAAsB,WAzDnC,IAAuB+D,IA0DDH,EA9GkC,GAAlDzG,KAAK6G,MAAM1B,EAAO7F,wBAAwBQ,KAC5CqF,EAAOjE,UAAUM,IAAI,YAErB2D,EAAOjE,UAAUC,OAAO,YAI5B,SAAmCyF,GAC7BA,EAAYtB,EACd3F,SAASC,gBAAgBsB,UAAUC,OAAO,oBAEtCyF,EAAYxB,EACdzF,SAASC,gBAAgBsB,UAAUM,IAAI,oBAC9BoF,EAAYxB,GACrBzF,SAASC,gBAAgBsB,UAAUC,OAAO,oBAG9CiE,EAAgBwB,CAClB,CAoCEE,CAA0BF,GAlC5B,SAA6BA,GACT,OAAd1B,IAKa,GAAb0B,EACF1B,EAAU6B,SAAS,EAAG,GAGtB/G,KAAKC,KAAK2G,IACV5G,KAAK6G,MAAMlH,SAASC,gBAAgBS,aAAehD,OAAOqC,aAE1DwF,EAAU6B,SAAS,EAAG7B,EAAU7E,cAGhBV,SAASqH,cAAc,mBAc3C,CAKEC,CAAoBL,GAwDdF,GAAU,CACZ,IAEAA,GAAU,EAEd,IACArJ,OAAO6J,QACT,CA6BEC,GA1BkB,OAAdjC,GAKJ,IAAI,IAAJ,CAAY,cAAe,CACzBrH,QAAQ,EACRuJ,WAAW,EACX5J,SAAU,iBACVI,OAAQ,KACN,IAAIyJ,EAAM9H,WAAW+H,iBAAiB3H,SAASC,iBAAiB2H,UAChE,OAAOpC,EAAO7F,wBAAwBkI,OAAS,GAAMH,EAAM,CAAC,GAiBlE,CAcA1H,SAAS8D,iBAAiB,oBAT1B,WACE9D,SAASS,KAAKW,WAAWG,UAAUC,OAAO,SAE1CgE,EAASxF,SAASqH,cAAc,UAChC9B,EAAYvF,SAASqH,cAAc,eAEnCxD,GACF","sources":["webpack:///./src/furo/assets/scripts/gumshoe-patched.js","webpack:///webpack/bootstrap","webpack:///webpack/runtime/compat get default export","webpack:///webpack/runtime/define property getters","webpack:///webpack/runtime/global","webpack:///webpack/runtime/hasOwnProperty shorthand","webpack:///./src/furo/assets/scripts/furo.js"],"sourcesContent":["/*!\n * gumshoejs v5.1.2 (patched by @pradyunsg)\n * A simple, framework-agnostic scrollspy script.\n * (c) 2019 Chris Ferdinandi\n * MIT License\n * http://github.com/cferdinandi/gumshoe\n */\n\n(function (root, factory) {\n if (typeof define === \"function\" && define.amd) {\n define([], function () {\n return factory(root);\n });\n } else if (typeof exports === \"object\") {\n module.exports = factory(root);\n } else {\n root.Gumshoe = factory(root);\n }\n})(\n typeof global !== \"undefined\"\n ? global\n : typeof window !== \"undefined\"\n ? window\n : this,\n function (window) {\n \"use strict\";\n\n //\n // Defaults\n //\n\n var defaults = {\n // Active classes\n navClass: \"active\",\n contentClass: \"active\",\n\n // Nested navigation\n nested: false,\n nestedClass: \"active\",\n\n // Offset & reflow\n offset: 0,\n reflow: false,\n\n // Event support\n events: true,\n };\n\n //\n // Methods\n //\n\n /**\n * Merge two or more objects together.\n * @param {Object} objects The objects to merge together\n * @returns {Object} Merged values of defaults and options\n */\n var extend = function () {\n var merged = {};\n Array.prototype.forEach.call(arguments, function (obj) {\n for (var key in obj) {\n if (!obj.hasOwnProperty(key)) return;\n merged[key] = obj[key];\n }\n });\n return merged;\n };\n\n /**\n * Emit a custom event\n * @param {String} type The event type\n * @param {Node} elem The element to attach the event to\n * @param {Object} detail Any details to pass along with the event\n */\n var emitEvent = function (type, elem, detail) {\n // Make sure events are enabled\n if (!detail.settings.events) return;\n\n // Create a new event\n var event = new CustomEvent(type, {\n bubbles: true,\n cancelable: true,\n detail: detail,\n });\n\n // Dispatch the event\n elem.dispatchEvent(event);\n };\n\n /**\n * Get an element's distance from the top of the Document.\n * @param {Node} elem The element\n * @return {Number} Distance from the top in pixels\n */\n var getOffsetTop = function (elem) {\n var location = 0;\n if (elem.offsetParent) {\n while (elem) {\n location += elem.offsetTop;\n elem = elem.offsetParent;\n }\n }\n return location >= 0 ? location : 0;\n };\n\n /**\n * Sort content from first to last in the DOM\n * @param {Array} contents The content areas\n */\n var sortContents = function (contents) {\n if (contents) {\n contents.sort(function (item1, item2) {\n var offset1 = getOffsetTop(item1.content);\n var offset2 = getOffsetTop(item2.content);\n if (offset1 < offset2) return -1;\n return 1;\n });\n }\n };\n\n /**\n * Get the offset to use for calculating position\n * @param {Object} settings The settings for this instantiation\n * @return {Float} The number of pixels to offset the calculations\n */\n var getOffset = function (settings) {\n // if the offset is a function run it\n if (typeof settings.offset === \"function\") {\n return parseFloat(settings.offset());\n }\n\n // Otherwise, return it as-is\n return parseFloat(settings.offset);\n };\n\n /**\n * Get the document element's height\n * @private\n * @returns {Number}\n */\n var getDocumentHeight = function () {\n return Math.max(\n document.body.scrollHeight,\n document.documentElement.scrollHeight,\n document.body.offsetHeight,\n document.documentElement.offsetHeight,\n document.body.clientHeight,\n document.documentElement.clientHeight,\n );\n };\n\n /**\n * Determine if an element is in view\n * @param {Node} elem The element\n * @param {Object} settings The settings for this instantiation\n * @param {Boolean} bottom If true, check if element is above bottom of viewport instead\n * @return {Boolean} Returns true if element is in the viewport\n */\n var isInView = function (elem, settings, bottom) {\n var bounds = elem.getBoundingClientRect();\n var offset = getOffset(settings);\n if (bottom) {\n return (\n parseInt(bounds.bottom, 10) <\n (window.innerHeight || document.documentElement.clientHeight)\n );\n }\n return parseInt(bounds.top, 10) <= offset;\n };\n\n /**\n * Check if at the bottom of the viewport\n * @return {Boolean} If true, page is at the bottom of the viewport\n */\n var isAtBottom = function () {\n if (\n Math.ceil(window.innerHeight + window.pageYOffset) >=\n getDocumentHeight()\n )\n return true;\n return false;\n };\n\n /**\n * Check if the last item should be used (even if not at the top of the page)\n * @param {Object} item The last item\n * @param {Object} settings The settings for this instantiation\n * @return {Boolean} If true, use the last item\n */\n var useLastItem = function (item, settings) {\n if (isAtBottom() && isInView(item.content, settings, true)) return true;\n return false;\n };\n\n /**\n * Get the active content\n * @param {Array} contents The content areas\n * @param {Object} settings The settings for this instantiation\n * @return {Object} The content area and matching navigation link\n */\n var getActive = function (contents, settings) {\n var last = contents[contents.length - 1];\n if (useLastItem(last, settings)) return last;\n for (var i = contents.length - 1; i >= 0; i--) {\n if (isInView(contents[i].content, settings)) return contents[i];\n }\n };\n\n /**\n * Deactivate parent navs in a nested navigation\n * @param {Node} nav The starting navigation element\n * @param {Object} settings The settings for this instantiation\n */\n var deactivateNested = function (nav, settings) {\n // If nesting isn't activated, bail\n if (!settings.nested || !nav.parentNode) return;\n\n // Get the parent navigation\n var li = nav.parentNode.closest(\"li\");\n if (!li) return;\n\n // Remove the active class\n li.classList.remove(settings.nestedClass);\n\n // Apply recursively to any parent navigation elements\n deactivateNested(li, settings);\n };\n\n /**\n * Deactivate a nav and content area\n * @param {Object} items The nav item and content to deactivate\n * @param {Object} settings The settings for this instantiation\n */\n var deactivate = function (items, settings) {\n // Make sure there are items to deactivate\n if (!items) return;\n\n // Get the parent list item\n var li = items.nav.closest(\"li\");\n if (!li) return;\n\n // Remove the active class from the nav and content\n li.classList.remove(settings.navClass);\n items.content.classList.remove(settings.contentClass);\n\n // Deactivate any parent navs in a nested navigation\n deactivateNested(li, settings);\n\n // Emit a custom event\n emitEvent(\"gumshoeDeactivate\", li, {\n link: items.nav,\n content: items.content,\n settings: settings,\n });\n };\n\n /**\n * Activate parent navs in a nested navigation\n * @param {Node} nav The starting navigation element\n * @param {Object} settings The settings for this instantiation\n */\n var activateNested = function (nav, settings) {\n // If nesting isn't activated, bail\n if (!settings.nested) return;\n\n // Get the parent navigation\n var li = nav.parentNode.closest(\"li\");\n if (!li) return;\n\n // Add the active class\n li.classList.add(settings.nestedClass);\n\n // Apply recursively to any parent navigation elements\n activateNested(li, settings);\n };\n\n /**\n * Activate a nav and content area\n * @param {Object} items The nav item and content to activate\n * @param {Object} settings The settings for this instantiation\n */\n var activate = function (items, settings) {\n // Make sure there are items to activate\n if (!items) return;\n\n // Get the parent list item\n var li = items.nav.closest(\"li\");\n if (!li) return;\n\n // Add the active class to the nav and content\n li.classList.add(settings.navClass);\n items.content.classList.add(settings.contentClass);\n\n // Activate any parent navs in a nested navigation\n activateNested(li, settings);\n\n // Emit a custom event\n emitEvent(\"gumshoeActivate\", li, {\n link: items.nav,\n content: items.content,\n settings: settings,\n });\n };\n\n /**\n * Create the Constructor object\n * @param {String} selector The selector to use for navigation items\n * @param {Object} options User options and settings\n */\n var Constructor = function (selector, options) {\n //\n // Variables\n //\n\n var publicAPIs = {};\n var navItems, contents, current, timeout, settings;\n\n //\n // Methods\n //\n\n /**\n * Set variables from DOM elements\n */\n publicAPIs.setup = function () {\n // Get all nav items\n navItems = document.querySelectorAll(selector);\n\n // Create contents array\n contents = [];\n\n // Loop through each item, get it's matching content, and push to the array\n Array.prototype.forEach.call(navItems, function (item) {\n // Get the content for the nav item\n var content = document.getElementById(\n decodeURIComponent(item.hash.substr(1)),\n );\n if (!content) return;\n\n // Push to the contents array\n contents.push({\n nav: item,\n content: content,\n });\n });\n\n // Sort contents by the order they appear in the DOM\n sortContents(contents);\n };\n\n /**\n * Detect which content is currently active\n */\n publicAPIs.detect = function () {\n // Get the active content\n var active = getActive(contents, settings);\n\n // if there's no active content, deactivate and bail\n if (!active) {\n if (current) {\n deactivate(current, settings);\n current = null;\n }\n return;\n }\n\n // If the active content is the one currently active, do nothing\n if (current && active.content === current.content) return;\n\n // Deactivate the current content and activate the new content\n deactivate(current, settings);\n activate(active, settings);\n\n // Update the currently active content\n current = active;\n };\n\n /**\n * Detect the active content on scroll\n * Debounced for performance\n */\n var scrollHandler = function (event) {\n // If there's a timer, cancel it\n if (timeout) {\n window.cancelAnimationFrame(timeout);\n }\n\n // Setup debounce callback\n timeout = window.requestAnimationFrame(publicAPIs.detect);\n };\n\n /**\n * Update content sorting on resize\n * Debounced for performance\n */\n var resizeHandler = function (event) {\n // If there's a timer, cancel it\n if (timeout) {\n window.cancelAnimationFrame(timeout);\n }\n\n // Setup debounce callback\n timeout = window.requestAnimationFrame(function () {\n sortContents(contents);\n publicAPIs.detect();\n });\n };\n\n /**\n * Destroy the current instantiation\n */\n publicAPIs.destroy = function () {\n // Undo DOM changes\n if (current) {\n deactivate(current, settings);\n }\n\n // Remove event listeners\n window.removeEventListener(\"scroll\", scrollHandler, false);\n if (settings.reflow) {\n window.removeEventListener(\"resize\", resizeHandler, false);\n }\n\n // Reset variables\n contents = null;\n navItems = null;\n current = null;\n timeout = null;\n settings = null;\n };\n\n /**\n * Initialize the current instantiation\n */\n var init = function () {\n // Merge user options into defaults\n settings = extend(defaults, options || {});\n\n // Setup variables based on the current DOM\n publicAPIs.setup();\n\n // Find the currently active content\n publicAPIs.detect();\n\n // Setup event listeners\n window.addEventListener(\"scroll\", scrollHandler, false);\n if (settings.reflow) {\n window.addEventListener(\"resize\", resizeHandler, false);\n }\n };\n\n //\n // Initialize and return the public APIs\n //\n\n init();\n return publicAPIs;\n };\n\n //\n // Return the Constructor\n //\n\n return Constructor;\n },\n);\n","// The module cache\nvar __webpack_module_cache__ = {};\n\n// The require function\nfunction __webpack_require__(moduleId) {\n\t// Check if module is in cache\n\tvar cachedModule = __webpack_module_cache__[moduleId];\n\tif (cachedModule !== undefined) {\n\t\treturn cachedModule.exports;\n\t}\n\t// Create a new module (and put it into the cache)\n\tvar module = __webpack_module_cache__[moduleId] = {\n\t\t// no module.id needed\n\t\t// no module.loaded needed\n\t\texports: {}\n\t};\n\n\t// Execute the module function\n\t__webpack_modules__[moduleId].call(module.exports, module, module.exports, __webpack_require__);\n\n\t// Return the exports of the module\n\treturn module.exports;\n}\n\n","// getDefaultExport function for compatibility with non-harmony modules\n__webpack_require__.n = (module) => {\n\tvar getter = module && module.__esModule ?\n\t\t() => (module['default']) :\n\t\t() => (module);\n\t__webpack_require__.d(getter, { a: getter });\n\treturn getter;\n};","// define getter functions for harmony exports\n__webpack_require__.d = (exports, definition) => {\n\tfor(var key in definition) {\n\t\tif(__webpack_require__.o(definition, key) && !__webpack_require__.o(exports, key)) {\n\t\t\tObject.defineProperty(exports, key, { enumerable: true, get: definition[key] });\n\t\t}\n\t}\n};","__webpack_require__.g = (function() {\n\tif (typeof globalThis === 'object') return globalThis;\n\ttry {\n\t\treturn this || new Function('return this')();\n\t} catch (e) {\n\t\tif (typeof window === 'object') return window;\n\t}\n})();","__webpack_require__.o = (obj, prop) => (Object.prototype.hasOwnProperty.call(obj, prop))","import Gumshoe from \"./gumshoe-patched.js\";\n\n////////////////////////////////////////////////////////////////////////////////\n// Scroll Handling\n////////////////////////////////////////////////////////////////////////////////\nvar tocScroll = null;\nvar header = null;\nvar lastScrollTop = window.pageYOffset || document.documentElement.scrollTop;\nconst GO_TO_TOP_OFFSET = 64;\n\nfunction scrollHandlerForHeader() {\n if (Math.floor(header.getBoundingClientRect().top) == 0) {\n header.classList.add(\"scrolled\");\n } else {\n header.classList.remove(\"scrolled\");\n }\n}\n\nfunction scrollHandlerForBackToTop(positionY) {\n if (positionY < GO_TO_TOP_OFFSET) {\n document.documentElement.classList.remove(\"show-back-to-top\");\n } else {\n if (positionY < lastScrollTop) {\n document.documentElement.classList.add(\"show-back-to-top\");\n } else if (positionY > lastScrollTop) {\n document.documentElement.classList.remove(\"show-back-to-top\");\n }\n }\n lastScrollTop = positionY;\n}\n\nfunction scrollHandlerForTOC(positionY) {\n if (tocScroll === null) {\n return;\n }\n\n // top of page.\n if (positionY == 0) {\n tocScroll.scrollTo(0, 0);\n } else if (\n // bottom of page.\n Math.ceil(positionY) >=\n Math.floor(document.documentElement.scrollHeight - window.innerHeight)\n ) {\n tocScroll.scrollTo(0, tocScroll.scrollHeight);\n } else {\n // somewhere in the middle.\n const current = document.querySelector(\".scroll-current\");\n if (current == null) {\n return;\n }\n\n // https://github.com/pypa/pip/issues/9159 This breaks scroll behaviours.\n // // scroll the currently \"active\" heading in toc, into view.\n // const rect = current.getBoundingClientRect();\n // if (0 > rect.top) {\n // current.scrollIntoView(true); // the argument is \"alignTop\"\n // } else if (rect.bottom > window.innerHeight) {\n // current.scrollIntoView(false);\n // }\n }\n}\n\nfunction scrollHandler(positionY) {\n scrollHandlerForHeader();\n scrollHandlerForBackToTop(positionY);\n scrollHandlerForTOC(positionY);\n}\n\n////////////////////////////////////////////////////////////////////////////////\n// Theme Toggle\n////////////////////////////////////////////////////////////////////////////////\nfunction setTheme(mode) {\n if (mode !== \"light\" && mode !== \"dark\" && mode !== \"auto\") {\n console.error(`Got invalid theme mode: ${mode}. Resetting to auto.`);\n mode = \"auto\";\n }\n\n document.body.dataset.theme = mode;\n localStorage.setItem(\"theme\", mode);\n console.log(`Changed to ${mode} mode.`);\n}\n\nfunction cycleThemeOnce() {\n const currentTheme = localStorage.getItem(\"theme\") || \"auto\";\n const prefersDark = window.matchMedia(\"(prefers-color-scheme: dark)\").matches;\n\n if (prefersDark) {\n // Auto (dark) -> Light -> Dark\n if (currentTheme === \"auto\") {\n setTheme(\"light\");\n } else if (currentTheme == \"light\") {\n setTheme(\"dark\");\n } else {\n setTheme(\"auto\");\n }\n } else {\n // Auto (light) -> Dark -> Light\n if (currentTheme === \"auto\") {\n setTheme(\"dark\");\n } else if (currentTheme == \"dark\") {\n setTheme(\"light\");\n } else {\n setTheme(\"auto\");\n }\n }\n}\n\n////////////////////////////////////////////////////////////////////////////////\n// Setup\n////////////////////////////////////////////////////////////////////////////////\nfunction setupScrollHandler() {\n // Taken from https://developer.mozilla.org/en-US/docs/Web/API/Document/scroll_event\n let last_known_scroll_position = 0;\n let ticking = false;\n\n window.addEventListener(\"scroll\", function (e) {\n last_known_scroll_position = window.scrollY;\n\n if (!ticking) {\n window.requestAnimationFrame(function () {\n scrollHandler(last_known_scroll_position);\n ticking = false;\n });\n\n ticking = true;\n }\n });\n window.scroll();\n}\n\nfunction setupScrollSpy() {\n if (tocScroll === null) {\n return;\n }\n\n // Scrollspy -- highlight table on contents, based on scroll\n new Gumshoe(\".toc-tree a\", {\n reflow: true,\n recursive: true,\n navClass: \"scroll-current\",\n offset: () => {\n let rem = parseFloat(getComputedStyle(document.documentElement).fontSize);\n return header.getBoundingClientRect().height + 0.5 * rem + 1;\n },\n });\n}\n\nfunction setupTheme() {\n // Attach event handlers for toggling themes\n const buttons = document.getElementsByClassName(\"theme-toggle\");\n Array.from(buttons).forEach((btn) => {\n btn.addEventListener(\"click\", cycleThemeOnce);\n });\n}\n\nfunction setup() {\n setupTheme();\n setupScrollHandler();\n setupScrollSpy();\n}\n\n////////////////////////////////////////////////////////////////////////////////\n// Main entrypoint\n////////////////////////////////////////////////////////////////////////////////\nfunction main() {\n document.body.parentNode.classList.remove(\"no-js\");\n\n header = document.querySelector(\"header\");\n tocScroll = document.querySelector(\".toc-scroll\");\n\n setup();\n}\n\ndocument.addEventListener(\"DOMContentLoaded\", main);\n"],"names":["root","g","window","this","defaults","navClass","contentClass","nested","nestedClass","offset","reflow","events","emitEvent","type","elem","detail","settings","event","CustomEvent","bubbles","cancelable","dispatchEvent","getOffsetTop","location","offsetParent","offsetTop","sortContents","contents","sort","item1","item2","content","isInView","bottom","bounds","getBoundingClientRect","parseFloat","getOffset","parseInt","innerHeight","document","documentElement","clientHeight","top","isAtBottom","Math","ceil","pageYOffset","max","body","scrollHeight","offsetHeight","getActive","last","length","item","useLastItem","i","deactivateNested","nav","parentNode","li","closest","classList","remove","deactivate","items","link","activateNested","add","selector","options","navItems","current","timeout","publicAPIs","querySelectorAll","Array","prototype","forEach","call","getElementById","decodeURIComponent","hash","substr","push","active","activate","scrollHandler","cancelAnimationFrame","requestAnimationFrame","detect","resizeHandler","destroy","removeEventListener","merged","arguments","obj","key","hasOwnProperty","extend","setup","addEventListener","factory","__webpack_module_cache__","__webpack_require__","moduleId","cachedModule","undefined","exports","module","__webpack_modules__","n","getter","__esModule","d","a","definition","o","Object","defineProperty","enumerable","get","globalThis","Function","e","prop","tocScroll","header","lastScrollTop","scrollTop","GO_TO_TOP_OFFSET","cycleThemeOnce","currentTheme","localStorage","getItem","mode","matchMedia","matches","console","error","dataset","theme","setItem","log","buttons","getElementsByClassName","from","btn","setupTheme","last_known_scroll_position","ticking","scrollY","positionY","floor","scrollHandlerForBackToTop","scrollTo","querySelector","scrollHandlerForTOC","scroll","setupScrollHandler","recursive","rem","getComputedStyle","fontSize","height"],"sourceRoot":""} \ No newline at end of file diff --git a/docs/_build/html/_static/searchtools.js b/docs/_build/html/_static/searchtools.js deleted file mode 100644 index 7918c3fab..000000000 --- a/docs/_build/html/_static/searchtools.js +++ /dev/null @@ -1,574 +0,0 @@ -/* - * searchtools.js - * ~~~~~~~~~~~~~~~~ - * - * Sphinx JavaScript utilities for the full-text search. - * - * :copyright: Copyright 2007-2023 by the Sphinx team, see AUTHORS. - * :license: BSD, see LICENSE for details. - * - */ -"use strict"; - -/** - * Simple result scoring code. - */ -if (typeof Scorer === "undefined") { - var Scorer = { - // Implement the following function to further tweak the score for each result - // The function takes a result array [docname, title, anchor, descr, score, filename] - // and returns the new score. - /* - score: result => { - const [docname, title, anchor, descr, score, filename] = result - return score - }, - */ - - // query matches the full name of an object - objNameMatch: 11, - // or matches in the last dotted part of the object name - objPartialMatch: 6, - // Additive scores depending on the priority of the object - objPrio: { - 0: 15, // used to be importantResults - 1: 5, // used to be objectResults - 2: -5, // used to be unimportantResults - }, - // Used when the priority is not in the mapping. - objPrioDefault: 0, - - // query found in title - title: 15, - partialTitle: 7, - // query found in terms - term: 5, - partialTerm: 2, - }; -} - -const _removeChildren = (element) => { - while (element && element.lastChild) element.removeChild(element.lastChild); -}; - -/** - * See https://developer.mozilla.org/en-US/docs/Web/JavaScript/Guide/Regular_Expressions#escaping - */ -const _escapeRegExp = (string) => - string.replace(/[.*+\-?^${}()|[\]\\]/g, "\\$&"); // $& means the whole matched string - -const _displayItem = (item, searchTerms, highlightTerms) => { - const docBuilder = DOCUMENTATION_OPTIONS.BUILDER; - const docFileSuffix = DOCUMENTATION_OPTIONS.FILE_SUFFIX; - const docLinkSuffix = DOCUMENTATION_OPTIONS.LINK_SUFFIX; - const showSearchSummary = DOCUMENTATION_OPTIONS.SHOW_SEARCH_SUMMARY; - const contentRoot = document.documentElement.dataset.content_root; - - const [docName, title, anchor, descr, score, _filename] = item; - - let listItem = document.createElement("li"); - let requestUrl; - let linkUrl; - if (docBuilder === "dirhtml") { - // dirhtml builder - let dirname = docName + "/"; - if (dirname.match(/\/index\/$/)) - dirname = dirname.substring(0, dirname.length - 6); - else if (dirname === "index/") dirname = ""; - requestUrl = contentRoot + dirname; - linkUrl = requestUrl; - } else { - // normal html builders - requestUrl = contentRoot + docName + docFileSuffix; - linkUrl = docName + docLinkSuffix; - } - let linkEl = listItem.appendChild(document.createElement("a")); - linkEl.href = linkUrl + anchor; - linkEl.dataset.score = score; - linkEl.innerHTML = title; - if (descr) { - listItem.appendChild(document.createElement("span")).innerHTML = - " (" + descr + ")"; - // highlight search terms in the description - if (SPHINX_HIGHLIGHT_ENABLED) // set in sphinx_highlight.js - highlightTerms.forEach((term) => _highlightText(listItem, term, "highlighted")); - } - else if (showSearchSummary) - fetch(requestUrl) - .then((responseData) => responseData.text()) - .then((data) => { - if (data) - listItem.appendChild( - Search.makeSearchSummary(data, searchTerms) - ); - // highlight search terms in the summary - if (SPHINX_HIGHLIGHT_ENABLED) // set in sphinx_highlight.js - highlightTerms.forEach((term) => _highlightText(listItem, term, "highlighted")); - }); - Search.output.appendChild(listItem); -}; -const _finishSearch = (resultCount) => { - Search.stopPulse(); - Search.title.innerText = _("Search Results"); - if (!resultCount) - Search.status.innerText = Documentation.gettext( - "Your search did not match any documents. Please make sure that all words are spelled correctly and that you've selected enough categories." - ); - else - Search.status.innerText = _( - `Search finished, found ${resultCount} page(s) matching the search query.` - ); -}; -const _displayNextItem = ( - results, - resultCount, - searchTerms, - highlightTerms, -) => { - // results left, load the summary and display it - // this is intended to be dynamic (don't sub resultsCount) - if (results.length) { - _displayItem(results.pop(), searchTerms, highlightTerms); - setTimeout( - () => _displayNextItem(results, resultCount, searchTerms, highlightTerms), - 5 - ); - } - // search finished, update title and status message - else _finishSearch(resultCount); -}; - -/** - * Default splitQuery function. Can be overridden in ``sphinx.search`` with a - * custom function per language. - * - * The regular expression works by splitting the string on consecutive characters - * that are not Unicode letters, numbers, underscores, or emoji characters. - * This is the same as ``\W+`` in Python, preserving the surrogate pair area. - */ -if (typeof splitQuery === "undefined") { - var splitQuery = (query) => query - .split(/[^\p{Letter}\p{Number}_\p{Emoji_Presentation}]+/gu) - .filter(term => term) // remove remaining empty strings -} - -/** - * Search Module - */ -const Search = { - _index: null, - _queued_query: null, - _pulse_status: -1, - - htmlToText: (htmlString) => { - const htmlElement = new DOMParser().parseFromString(htmlString, 'text/html'); - htmlElement.querySelectorAll(".headerlink").forEach((el) => { el.remove() }); - const docContent = htmlElement.querySelector('[role="main"]'); - if (docContent !== undefined) return docContent.textContent; - console.warn( - "Content block not found. Sphinx search tries to obtain it via '[role=main]'. Could you check your theme or template." - ); - return ""; - }, - - init: () => { - const query = new URLSearchParams(window.location.search).get("q"); - document - .querySelectorAll('input[name="q"]') - .forEach((el) => (el.value = query)); - if (query) Search.performSearch(query); - }, - - loadIndex: (url) => - (document.body.appendChild(document.createElement("script")).src = url), - - setIndex: (index) => { - Search._index = index; - if (Search._queued_query !== null) { - const query = Search._queued_query; - Search._queued_query = null; - Search.query(query); - } - }, - - hasIndex: () => Search._index !== null, - - deferQuery: (query) => (Search._queued_query = query), - - stopPulse: () => (Search._pulse_status = -1), - - startPulse: () => { - if (Search._pulse_status >= 0) return; - - const pulse = () => { - Search._pulse_status = (Search._pulse_status + 1) % 4; - Search.dots.innerText = ".".repeat(Search._pulse_status); - if (Search._pulse_status >= 0) window.setTimeout(pulse, 500); - }; - pulse(); - }, - - /** - * perform a search for something (or wait until index is loaded) - */ - performSearch: (query) => { - // create the required interface elements - const searchText = document.createElement("h2"); - searchText.textContent = _("Searching"); - const searchSummary = document.createElement("p"); - searchSummary.classList.add("search-summary"); - searchSummary.innerText = ""; - const searchList = document.createElement("ul"); - searchList.classList.add("search"); - - const out = document.getElementById("search-results"); - Search.title = out.appendChild(searchText); - Search.dots = Search.title.appendChild(document.createElement("span")); - Search.status = out.appendChild(searchSummary); - Search.output = out.appendChild(searchList); - - const searchProgress = document.getElementById("search-progress"); - // Some themes don't use the search progress node - if (searchProgress) { - searchProgress.innerText = _("Preparing search..."); - } - Search.startPulse(); - - // index already loaded, the browser was quick! - if (Search.hasIndex()) Search.query(query); - else Search.deferQuery(query); - }, - - /** - * execute search (requires search index to be loaded) - */ - query: (query) => { - const filenames = Search._index.filenames; - const docNames = Search._index.docnames; - const titles = Search._index.titles; - const allTitles = Search._index.alltitles; - const indexEntries = Search._index.indexentries; - - // stem the search terms and add them to the correct list - const stemmer = new Stemmer(); - const searchTerms = new Set(); - const excludedTerms = new Set(); - const highlightTerms = new Set(); - const objectTerms = new Set(splitQuery(query.toLowerCase().trim())); - splitQuery(query.trim()).forEach((queryTerm) => { - const queryTermLower = queryTerm.toLowerCase(); - - // maybe skip this "word" - // stopwords array is from language_data.js - if ( - stopwords.indexOf(queryTermLower) !== -1 || - queryTerm.match(/^\d+$/) - ) - return; - - // stem the word - let word = stemmer.stemWord(queryTermLower); - // select the correct list - if (word[0] === "-") excludedTerms.add(word.substr(1)); - else { - searchTerms.add(word); - highlightTerms.add(queryTermLower); - } - }); - - if (SPHINX_HIGHLIGHT_ENABLED) { // set in sphinx_highlight.js - localStorage.setItem("sphinx_highlight_terms", [...highlightTerms].join(" ")) - } - - // console.debug("SEARCH: searching for:"); - // console.info("required: ", [...searchTerms]); - // console.info("excluded: ", [...excludedTerms]); - - // array of [docname, title, anchor, descr, score, filename] - let results = []; - _removeChildren(document.getElementById("search-progress")); - - const queryLower = query.toLowerCase(); - for (const [title, foundTitles] of Object.entries(allTitles)) { - if (title.toLowerCase().includes(queryLower) && (queryLower.length >= title.length/2)) { - for (const [file, id] of foundTitles) { - let score = Math.round(100 * queryLower.length / title.length) - results.push([ - docNames[file], - titles[file] !== title ? `${titles[file]} > ${title}` : title, - id !== null ? "#" + id : "", - null, - score, - filenames[file], - ]); - } - } - } - - // search for explicit entries in index directives - for (const [entry, foundEntries] of Object.entries(indexEntries)) { - if (entry.includes(queryLower) && (queryLower.length >= entry.length/2)) { - for (const [file, id] of foundEntries) { - let score = Math.round(100 * queryLower.length / entry.length) - results.push([ - docNames[file], - titles[file], - id ? "#" + id : "", - null, - score, - filenames[file], - ]); - } - } - } - - // lookup as object - objectTerms.forEach((term) => - results.push(...Search.performObjectSearch(term, objectTerms)) - ); - - // lookup as search terms in fulltext - results.push(...Search.performTermsSearch(searchTerms, excludedTerms)); - - // let the scorer override scores with a custom scoring function - if (Scorer.score) results.forEach((item) => (item[4] = Scorer.score(item))); - - // now sort the results by score (in opposite order of appearance, since the - // display function below uses pop() to retrieve items) and then - // alphabetically - results.sort((a, b) => { - const leftScore = a[4]; - const rightScore = b[4]; - if (leftScore === rightScore) { - // same score: sort alphabetically - const leftTitle = a[1].toLowerCase(); - const rightTitle = b[1].toLowerCase(); - if (leftTitle === rightTitle) return 0; - return leftTitle > rightTitle ? -1 : 1; // inverted is intentional - } - return leftScore > rightScore ? 1 : -1; - }); - - // remove duplicate search results - // note the reversing of results, so that in the case of duplicates, the highest-scoring entry is kept - let seen = new Set(); - results = results.reverse().reduce((acc, result) => { - let resultStr = result.slice(0, 4).concat([result[5]]).map(v => String(v)).join(','); - if (!seen.has(resultStr)) { - acc.push(result); - seen.add(resultStr); - } - return acc; - }, []); - - results = results.reverse(); - - // for debugging - //Search.lastresults = results.slice(); // a copy - // console.info("search results:", Search.lastresults); - - // print the results - _displayNextItem(results, results.length, searchTerms, highlightTerms); - }, - - /** - * search for object names - */ - performObjectSearch: (object, objectTerms) => { - const filenames = Search._index.filenames; - const docNames = Search._index.docnames; - const objects = Search._index.objects; - const objNames = Search._index.objnames; - const titles = Search._index.titles; - - const results = []; - - const objectSearchCallback = (prefix, match) => { - const name = match[4] - const fullname = (prefix ? prefix + "." : "") + name; - const fullnameLower = fullname.toLowerCase(); - if (fullnameLower.indexOf(object) < 0) return; - - let score = 0; - const parts = fullnameLower.split("."); - - // check for different match types: exact matches of full name or - // "last name" (i.e. last dotted part) - if (fullnameLower === object || parts.slice(-1)[0] === object) - score += Scorer.objNameMatch; - else if (parts.slice(-1)[0].indexOf(object) > -1) - score += Scorer.objPartialMatch; // matches in last name - - const objName = objNames[match[1]][2]; - const title = titles[match[0]]; - - // If more than one term searched for, we require other words to be - // found in the name/title/description - const otherTerms = new Set(objectTerms); - otherTerms.delete(object); - if (otherTerms.size > 0) { - const haystack = `${prefix} ${name} ${objName} ${title}`.toLowerCase(); - if ( - [...otherTerms].some((otherTerm) => haystack.indexOf(otherTerm) < 0) - ) - return; - } - - let anchor = match[3]; - if (anchor === "") anchor = fullname; - else if (anchor === "-") anchor = objNames[match[1]][1] + "-" + fullname; - - const descr = objName + _(", in ") + title; - - // add custom score for some objects according to scorer - if (Scorer.objPrio.hasOwnProperty(match[2])) - score += Scorer.objPrio[match[2]]; - else score += Scorer.objPrioDefault; - - results.push([ - docNames[match[0]], - fullname, - "#" + anchor, - descr, - score, - filenames[match[0]], - ]); - }; - Object.keys(objects).forEach((prefix) => - objects[prefix].forEach((array) => - objectSearchCallback(prefix, array) - ) - ); - return results; - }, - - /** - * search for full-text terms in the index - */ - performTermsSearch: (searchTerms, excludedTerms) => { - // prepare search - const terms = Search._index.terms; - const titleTerms = Search._index.titleterms; - const filenames = Search._index.filenames; - const docNames = Search._index.docnames; - const titles = Search._index.titles; - - const scoreMap = new Map(); - const fileMap = new Map(); - - // perform the search on the required terms - searchTerms.forEach((word) => { - const files = []; - const arr = [ - { files: terms[word], score: Scorer.term }, - { files: titleTerms[word], score: Scorer.title }, - ]; - // add support for partial matches - if (word.length > 2) { - const escapedWord = _escapeRegExp(word); - Object.keys(terms).forEach((term) => { - if (term.match(escapedWord) && !terms[word]) - arr.push({ files: terms[term], score: Scorer.partialTerm }); - }); - Object.keys(titleTerms).forEach((term) => { - if (term.match(escapedWord) && !titleTerms[word]) - arr.push({ files: titleTerms[word], score: Scorer.partialTitle }); - }); - } - - // no match but word was a required one - if (arr.every((record) => record.files === undefined)) return; - - // found search word in contents - arr.forEach((record) => { - if (record.files === undefined) return; - - let recordFiles = record.files; - if (recordFiles.length === undefined) recordFiles = [recordFiles]; - files.push(...recordFiles); - - // set score for the word in each file - recordFiles.forEach((file) => { - if (!scoreMap.has(file)) scoreMap.set(file, {}); - scoreMap.get(file)[word] = record.score; - }); - }); - - // create the mapping - files.forEach((file) => { - if (fileMap.has(file) && fileMap.get(file).indexOf(word) === -1) - fileMap.get(file).push(word); - else fileMap.set(file, [word]); - }); - }); - - // now check if the files don't contain excluded terms - const results = []; - for (const [file, wordList] of fileMap) { - // check if all requirements are matched - - // as search terms with length < 3 are discarded - const filteredTermCount = [...searchTerms].filter( - (term) => term.length > 2 - ).length; - if ( - wordList.length !== searchTerms.size && - wordList.length !== filteredTermCount - ) - continue; - - // ensure that none of the excluded terms is in the search result - if ( - [...excludedTerms].some( - (term) => - terms[term] === file || - titleTerms[term] === file || - (terms[term] || []).includes(file) || - (titleTerms[term] || []).includes(file) - ) - ) - break; - - // select one (max) score for the file. - const score = Math.max(...wordList.map((w) => scoreMap.get(file)[w])); - // add result to the result list - results.push([ - docNames[file], - titles[file], - "", - null, - score, - filenames[file], - ]); - } - return results; - }, - - /** - * helper function to return a node containing the - * search summary for a given text. keywords is a list - * of stemmed words. - */ - makeSearchSummary: (htmlText, keywords) => { - const text = Search.htmlToText(htmlText); - if (text === "") return null; - - const textLower = text.toLowerCase(); - const actualStartPosition = [...keywords] - .map((k) => textLower.indexOf(k.toLowerCase())) - .filter((i) => i > -1) - .slice(-1)[0]; - const startWithContext = Math.max(actualStartPosition - 120, 0); - - const top = startWithContext === 0 ? "" : "..."; - const tail = startWithContext + 240 < text.length ? "..." : ""; - - let summary = document.createElement("p"); - summary.classList.add("context"); - summary.textContent = top + text.substr(startWithContext, 240).trim() + tail; - - return summary; - }, -}; - -_ready(Search.init); diff --git a/docs/_build/html/_static/skeleton.css b/docs/_build/html/_static/skeleton.css deleted file mode 100644 index 467c878c6..000000000 --- a/docs/_build/html/_static/skeleton.css +++ /dev/null @@ -1,296 +0,0 @@ -/* Some sane resets. */ -html { - height: 100%; -} - -body { - margin: 0; - min-height: 100%; -} - -/* All the flexbox magic! */ -body, -.sb-announcement, -.sb-content, -.sb-main, -.sb-container, -.sb-container__inner, -.sb-article-container, -.sb-footer-content, -.sb-header, -.sb-header-secondary, -.sb-footer { - display: flex; -} - -/* These order things vertically */ -body, -.sb-main, -.sb-article-container { - flex-direction: column; -} - -/* Put elements in the center */ -.sb-header, -.sb-header-secondary, -.sb-container, -.sb-content, -.sb-footer, -.sb-footer-content { - justify-content: center; -} -/* Put elements at the ends */ -.sb-article-container { - justify-content: space-between; -} - -/* These elements grow. */ -.sb-main, -.sb-content, -.sb-container, -article { - flex-grow: 1; -} - -/* Because padding making this wider is not fun */ -article { - box-sizing: border-box; -} - -/* The announcements element should never be wider than the page. */ -.sb-announcement { - max-width: 100%; -} - -.sb-sidebar-primary, -.sb-sidebar-secondary { - flex-shrink: 0; - width: 17rem; -} - -.sb-announcement__inner { - justify-content: center; - - box-sizing: border-box; - height: 3rem; - - overflow-x: auto; - white-space: nowrap; -} - -/* Sidebars, with checkbox-based toggle */ -.sb-sidebar-primary, -.sb-sidebar-secondary { - position: fixed; - height: 100%; - top: 0; -} - -.sb-sidebar-primary { - left: -17rem; - transition: left 250ms ease-in-out; -} -.sb-sidebar-secondary { - right: -17rem; - transition: right 250ms ease-in-out; -} - -.sb-sidebar-toggle { - display: none; -} -.sb-sidebar-overlay { - position: fixed; - top: 0; - width: 0; - height: 0; - - transition: width 0ms ease 250ms, height 0ms ease 250ms, opacity 250ms ease; - - opacity: 0; - background-color: rgba(0, 0, 0, 0.54); -} - -#sb-sidebar-toggle--primary:checked - ~ .sb-sidebar-overlay[for="sb-sidebar-toggle--primary"], -#sb-sidebar-toggle--secondary:checked - ~ .sb-sidebar-overlay[for="sb-sidebar-toggle--secondary"] { - width: 100%; - height: 100%; - opacity: 1; - transition: width 0ms ease, height 0ms ease, opacity 250ms ease; -} - -#sb-sidebar-toggle--primary:checked ~ .sb-container .sb-sidebar-primary { - left: 0; -} -#sb-sidebar-toggle--secondary:checked ~ .sb-container .sb-sidebar-secondary { - right: 0; -} - -/* Full-width mode */ -.drop-secondary-sidebar-for-full-width-content - .hide-when-secondary-sidebar-shown { - display: none !important; -} -.drop-secondary-sidebar-for-full-width-content .sb-sidebar-secondary { - display: none !important; -} - -/* Mobile views */ -.sb-page-width { - width: 100%; -} - -.sb-article-container, -.sb-footer-content__inner, -.drop-secondary-sidebar-for-full-width-content .sb-article, -.drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 100vw; -} - -.sb-article, -.match-content-width { - padding: 0 1rem; - box-sizing: border-box; -} - -@media (min-width: 32rem) { - .sb-article, - .match-content-width { - padding: 0 2rem; - } -} - -/* Tablet views */ -@media (min-width: 42rem) { - .sb-article-container { - width: auto; - } - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 42rem; - } - .sb-article, - .match-content-width { - width: 42rem; - } -} -@media (min-width: 46rem) { - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 46rem; - } - .sb-article, - .match-content-width { - width: 46rem; - } -} -@media (min-width: 50rem) { - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 50rem; - } - .sb-article, - .match-content-width { - width: 50rem; - } -} - -/* Tablet views */ -@media (min-width: 59rem) { - .sb-sidebar-secondary { - position: static; - } - .hide-when-secondary-sidebar-shown { - display: none !important; - } - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 59rem; - } - .sb-article, - .match-content-width { - width: 42rem; - } -} -@media (min-width: 63rem) { - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 63rem; - } - .sb-article, - .match-content-width { - width: 46rem; - } -} -@media (min-width: 67rem) { - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 67rem; - } - .sb-article, - .match-content-width { - width: 50rem; - } -} - -/* Desktop views */ -@media (min-width: 76rem) { - .sb-sidebar-primary { - position: static; - } - .hide-when-primary-sidebar-shown { - display: none !important; - } - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 59rem; - } - .sb-article, - .match-content-width { - width: 42rem; - } -} - -/* Full desktop views */ -@media (min-width: 80rem) { - .sb-article, - .match-content-width { - width: 46rem; - } - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 63rem; - } -} - -@media (min-width: 84rem) { - .sb-article, - .match-content-width { - width: 50rem; - } - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 67rem; - } -} - -@media (min-width: 88rem) { - .sb-footer-content__inner, - .drop-secondary-sidebar-for-full-width-content .sb-article, - .drop-secondary-sidebar-for-full-width-content .match-content-width { - width: 67rem; - } - .sb-page-width { - width: 88rem; - } -} diff --git a/docs/_build/html/_static/sphinx_highlight.js b/docs/_build/html/_static/sphinx_highlight.js deleted file mode 100644 index 8a96c69a1..000000000 --- a/docs/_build/html/_static/sphinx_highlight.js +++ /dev/null @@ -1,154 +0,0 @@ -/* Highlighting utilities for Sphinx HTML documentation. */ -"use strict"; - -const SPHINX_HIGHLIGHT_ENABLED = true - -/** - * highlight a given string on a node by wrapping it in - * span elements with the given class name. - */ -const _highlight = (node, addItems, text, className) => { - if (node.nodeType === Node.TEXT_NODE) { - const val = node.nodeValue; - const parent = node.parentNode; - const pos = val.toLowerCase().indexOf(text); - if ( - pos >= 0 && - !parent.classList.contains(className) && - !parent.classList.contains("nohighlight") - ) { - let span; - - const closestNode = parent.closest("body, svg, foreignObject"); - const isInSVG = closestNode && closestNode.matches("svg"); - if (isInSVG) { - span = document.createElementNS("http://www.w3.org/2000/svg", "tspan"); - } else { - span = document.createElement("span"); - span.classList.add(className); - } - - span.appendChild(document.createTextNode(val.substr(pos, text.length))); - const rest = document.createTextNode(val.substr(pos + text.length)); - parent.insertBefore( - span, - parent.insertBefore( - rest, - node.nextSibling - ) - ); - node.nodeValue = val.substr(0, pos); - /* There may be more occurrences of search term in this node. So call this - * function recursively on the remaining fragment. - */ - _highlight(rest, addItems, text, className); - - if (isInSVG) { - const rect = document.createElementNS( - "http://www.w3.org/2000/svg", - "rect" - ); - const bbox = parent.getBBox(); - rect.x.baseVal.value = bbox.x; - rect.y.baseVal.value = bbox.y; - rect.width.baseVal.value = bbox.width; - rect.height.baseVal.value = bbox.height; - rect.setAttribute("class", className); - addItems.push({ parent: parent, target: rect }); - } - } - } else if (node.matches && !node.matches("button, select, textarea")) { - node.childNodes.forEach((el) => _highlight(el, addItems, text, className)); - } -}; -const _highlightText = (thisNode, text, className) => { - let addItems = []; - _highlight(thisNode, addItems, text, className); - addItems.forEach((obj) => - obj.parent.insertAdjacentElement("beforebegin", obj.target) - ); -}; - -/** - * Small JavaScript module for the documentation. - */ -const SphinxHighlight = { - - /** - * highlight the search words provided in localstorage in the text - */ - highlightSearchWords: () => { - if (!SPHINX_HIGHLIGHT_ENABLED) return; // bail if no highlight - - // get and clear terms from localstorage - const url = new URL(window.location); - const highlight = - localStorage.getItem("sphinx_highlight_terms") - || url.searchParams.get("highlight") - || ""; - localStorage.removeItem("sphinx_highlight_terms") - url.searchParams.delete("highlight"); - window.history.replaceState({}, "", url); - - // get individual terms from highlight string - const terms = highlight.toLowerCase().split(/\s+/).filter(x => x); - if (terms.length === 0) return; // nothing to do - - // There should never be more than one element matching "div.body" - const divBody = document.querySelectorAll("div.body"); - const body = divBody.length ? divBody[0] : document.querySelector("body"); - window.setTimeout(() => { - terms.forEach((term) => _highlightText(body, term, "highlighted")); - }, 10); - - const searchBox = document.getElementById("searchbox"); - if (searchBox === null) return; - searchBox.appendChild( - document - .createRange() - .createContextualFragment( - '

    " - ) - ); - }, - - /** - * helper function to hide the search marks again - */ - hideSearchWords: () => { - document - .querySelectorAll("#searchbox .highlight-link") - .forEach((el) => el.remove()); - document - .querySelectorAll("span.highlighted") - .forEach((el) => el.classList.remove("highlighted")); - localStorage.removeItem("sphinx_highlight_terms") - }, - - initEscapeListener: () => { - // only install a listener if it is really needed - if (!DOCUMENTATION_OPTIONS.ENABLE_SEARCH_SHORTCUTS) return; - - document.addEventListener("keydown", (event) => { - // bail for input elements - if (BLACKLISTED_KEY_CONTROL_ELEMENTS.has(document.activeElement.tagName)) return; - // bail with special keys - if (event.shiftKey || event.altKey || event.ctrlKey || event.metaKey) return; - if (DOCUMENTATION_OPTIONS.ENABLE_SEARCH_SHORTCUTS && (event.key === "Escape")) { - SphinxHighlight.hideSearchWords(); - event.preventDefault(); - } - }); - }, -}; - -_ready(() => { - /* Do not call highlightSearchWords() when we are on the search page. - * It will highlight words from the *previous* search query. - */ - if (typeof Search === "undefined") SphinxHighlight.highlightSearchWords(); - SphinxHighlight.initEscapeListener(); -}); diff --git a/docs/_build/html/_static/styles/furo-extensions.css b/docs/_build/html/_static/styles/furo-extensions.css deleted file mode 100644 index bc447f228..000000000 --- a/docs/_build/html/_static/styles/furo-extensions.css +++ /dev/null @@ -1,2 +0,0 @@ -#furo-sidebar-ad-placement{padding:var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal)}#furo-sidebar-ad-placement .ethical-sidebar{background:var(--color-background-secondary);border:none;box-shadow:none}#furo-sidebar-ad-placement .ethical-sidebar:hover{background:var(--color-background-hover)}#furo-sidebar-ad-placement .ethical-sidebar a{color:var(--color-foreground-primary)}#furo-sidebar-ad-placement .ethical-callout a{color:var(--color-foreground-secondary)!important}#furo-readthedocs-versions{background:transparent;display:block;position:static;width:100%}#furo-readthedocs-versions .rst-versions{background:#1a1c1e}#furo-readthedocs-versions .rst-current-version{background:var(--color-sidebar-item-background);cursor:unset}#furo-readthedocs-versions .rst-current-version:hover{background:var(--color-sidebar-item-background)}#furo-readthedocs-versions .rst-current-version .fa-book{color:var(--color-foreground-primary)}#furo-readthedocs-versions>.rst-other-versions{padding:0}#furo-readthedocs-versions>.rst-other-versions small{opacity:1}#furo-readthedocs-versions .injected .rst-versions{position:unset}#furo-readthedocs-versions:focus-within,#furo-readthedocs-versions:hover{box-shadow:0 0 0 1px var(--color-sidebar-background-border)}#furo-readthedocs-versions:focus-within .rst-current-version,#furo-readthedocs-versions:hover .rst-current-version{background:#1a1c1e;font-size:inherit;height:auto;line-height:inherit;padding:12px;text-align:right}#furo-readthedocs-versions:focus-within .rst-current-version .fa-book,#furo-readthedocs-versions:hover .rst-current-version .fa-book{color:#fff;float:left}#furo-readthedocs-versions:focus-within .fa-caret-down,#furo-readthedocs-versions:hover .fa-caret-down{display:none}#furo-readthedocs-versions:focus-within .injected,#furo-readthedocs-versions:focus-within .rst-current-version,#furo-readthedocs-versions:focus-within .rst-other-versions,#furo-readthedocs-versions:hover .injected,#furo-readthedocs-versions:hover .rst-current-version,#furo-readthedocs-versions:hover .rst-other-versions{display:block}#furo-readthedocs-versions:focus-within>.rst-current-version,#furo-readthedocs-versions:hover>.rst-current-version{display:none}.highlight:hover button.copybtn{color:var(--color-code-foreground)}.highlight button.copybtn{align-items:center;background-color:var(--color-code-background);border:none;color:var(--color-background-item);cursor:pointer;height:1.25em;opacity:1;right:.5rem;top:.625rem;transition:color .3s,opacity .3s;width:1.25em}.highlight button.copybtn:hover{background-color:var(--color-code-background);color:var(--color-brand-content)}.highlight button.copybtn:after{background-color:transparent;color:var(--color-code-foreground);display:none}.highlight button.copybtn.success{color:#22863a;transition:color 0ms}.highlight button.copybtn.success:after{display:block}.highlight button.copybtn svg{padding:0}body{--sd-color-primary:var(--color-brand-primary);--sd-color-primary-highlight:var(--color-brand-content);--sd-color-primary-text:var(--color-background-primary);--sd-color-shadow:rgba(0,0,0,.05);--sd-color-card-border:var(--color-card-border);--sd-color-card-border-hover:var(--color-brand-content);--sd-color-card-background:var(--color-card-background);--sd-color-card-text:var(--color-foreground-primary);--sd-color-card-header:var(--color-card-marginals-background);--sd-color-card-footer:var(--color-card-marginals-background);--sd-color-tabs-label-active:var(--color-brand-content);--sd-color-tabs-label-hover:var(--color-foreground-muted);--sd-color-tabs-label-inactive:var(--color-foreground-muted);--sd-color-tabs-underline-active:var(--color-brand-content);--sd-color-tabs-underline-hover:var(--color-foreground-border);--sd-color-tabs-underline-inactive:var(--color-background-border);--sd-color-tabs-overline:var(--color-background-border);--sd-color-tabs-underline:var(--color-background-border)}.sd-tab-content{box-shadow:0 -2px var(--sd-color-tabs-overline),0 1px var(--sd-color-tabs-underline)}.sd-card{box-shadow:0 .1rem .25rem var(--sd-color-shadow),0 0 .0625rem rgba(0,0,0,.1)}.sd-shadow-sm{box-shadow:0 .1rem .25rem var(--sd-color-shadow),0 0 .0625rem rgba(0,0,0,.1)!important}.sd-shadow-md{box-shadow:0 .3rem .75rem var(--sd-color-shadow),0 0 .0625rem rgba(0,0,0,.1)!important}.sd-shadow-lg{box-shadow:0 .6rem 1.5rem var(--sd-color-shadow),0 0 .0625rem rgba(0,0,0,.1)!important}.sd-card-hover:hover{transform:none}.sd-cards-carousel{gap:.25rem;padding:.25rem}body{--tabs--label-text:var(--color-foreground-muted);--tabs--label-text--hover:var(--color-foreground-muted);--tabs--label-text--active:var(--color-brand-content);--tabs--label-text--active--hover:var(--color-brand-content);--tabs--label-background:transparent;--tabs--label-background--hover:transparent;--tabs--label-background--active:transparent;--tabs--label-background--active--hover:transparent;--tabs--padding-x:0.25em;--tabs--margin-x:1em;--tabs--border:var(--color-background-border);--tabs--label-border:transparent;--tabs--label-border--hover:var(--color-foreground-muted);--tabs--label-border--active:var(--color-brand-content);--tabs--label-border--active--hover:var(--color-brand-content)}[role=main] .container{max-width:none;padding-left:0;padding-right:0}.shadow.docutils{border:none;box-shadow:0 .2rem .5rem rgba(0,0,0,.05),0 0 .0625rem rgba(0,0,0,.1)!important}.sphinx-bs .card{background-color:var(--color-background-secondary);color:var(--color-foreground)} -/*# sourceMappingURL=furo-extensions.css.map*/ \ No newline at end of file diff --git a/docs/_build/html/_static/styles/furo-extensions.css.map b/docs/_build/html/_static/styles/furo-extensions.css.map deleted file mode 100644 index 9ba5637f9..000000000 --- a/docs/_build/html/_static/styles/furo-extensions.css.map +++ /dev/null @@ -1 +0,0 @@ -{"version":3,"file":"styles/furo-extensions.css","mappings":"AAGA,2BACE,oFACA,4CAKE,6CAHA,YACA,eAEA,CACA,kDACE,yCAEF,8CACE,sCAEJ,8CACE,kDAEJ,2BAGE,uBACA,cAHA,gBACA,UAEA,CAGA,yCACE,mBAEF,gDAEE,gDADA,YACA,CACA,sDACE,gDACF,yDACE,sCAEJ,+CACE,UACA,qDACE,UAGF,mDACE,eAEJ,yEAEE,4DAEA,mHASE,mBAPA,kBAEA,YADA,oBAGA,aADA,gBAIA,CAEA,qIAEE,WADA,UACA,CAEJ,uGACE,aAEF,iUAGE,cAEF,mHACE,aC1EJ,gCACE,mCAEF,0BAKE,mBAUA,8CACA,YAFA,mCAKA,eAZA,cALA,UASA,YADA,YAYA,iCAdA,YAcA,CAEA,gCAEE,8CADA,gCACA,CAEF,gCAGE,6BADA,mCADA,YAEA,CAEF,kCAEE,cADA,oBACA,CACA,wCACE,cAEJ,8BACE,UC5CN,KAEE,6CAA8C,CAC9C,uDAAwD,CACxD,uDAAwD,CAGxD,iCAAsC,CAGtC,+CAAgD,CAChD,uDAAwD,CACxD,uDAAwD,CACxD,oDAAqD,CACrD,6DAA8D,CAC9D,6DAA8D,CAG9D,uDAAwD,CACxD,yDAA0D,CAC1D,4DAA6D,CAC7D,2DAA4D,CAC5D,8DAA+D,CAC/D,iEAAkE,CAClE,uDAAwD,CACxD,wDAAyD,CAG3D,gBACE,qFAGF,SACE,6EAEF,cACE,uFAEF,cACE,uFAEF,cACE,uFAGF,qBACE,eAEF,mBACE,WACA,eChDF,KACE,gDAAiD,CACjD,uDAAwD,CACxD,qDAAsD,CACtD,4DAA6D,CAC7D,oCAAqC,CACrC,2CAA4C,CAC5C,4CAA6C,CAC7C,mDAAoD,CACpD,wBAAyB,CACzB,oBAAqB,CACrB,6CAA8C,CAC9C,gCAAiC,CACjC,yDAA0D,CAC1D,uDAAwD,CACxD,8DAA+D,CCbjE,uBACE,eACA,eACA,gBAGF,iBACE,YACA,+EAGF,iBACE,mDACA","sources":["webpack:///./src/furo/assets/styles/extensions/_readthedocs.sass","webpack:///./src/furo/assets/styles/extensions/_copybutton.sass","webpack:///./src/furo/assets/styles/extensions/_sphinx-design.sass","webpack:///./src/furo/assets/styles/extensions/_sphinx-inline-tabs.sass","webpack:///./src/furo/assets/styles/extensions/_sphinx-panels.sass"],"sourcesContent":["// This file contains the styles used for tweaking how ReadTheDoc's embedded\n// contents would show up inside the theme.\n\n#furo-sidebar-ad-placement\n padding: var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal)\n .ethical-sidebar\n // Remove the border and box-shadow.\n border: none\n box-shadow: none\n // Manage the background colors.\n background: var(--color-background-secondary)\n &:hover\n background: var(--color-background-hover)\n // Ensure the text is legible.\n a\n color: var(--color-foreground-primary)\n\n .ethical-callout a\n color: var(--color-foreground-secondary) !important\n\n#furo-readthedocs-versions\n position: static\n width: 100%\n background: transparent\n display: block\n\n // Make the background color fit with the theme's aesthetic.\n .rst-versions\n background: rgb(26, 28, 30)\n\n .rst-current-version\n cursor: unset\n background: var(--color-sidebar-item-background)\n &:hover\n background: var(--color-sidebar-item-background)\n .fa-book\n color: var(--color-foreground-primary)\n\n > .rst-other-versions\n padding: 0\n small\n opacity: 1\n\n .injected\n .rst-versions\n position: unset\n\n &:hover,\n &:focus-within\n box-shadow: 0 0 0 1px var(--color-sidebar-background-border)\n\n .rst-current-version\n // Undo the tweaks done in RTD's CSS\n font-size: inherit\n line-height: inherit\n height: auto\n text-align: right\n padding: 12px\n\n // Match the rest of the body\n background: #1a1c1e\n\n .fa-book\n float: left\n color: white\n\n .fa-caret-down\n display: none\n\n .rst-current-version,\n .rst-other-versions,\n .injected\n display: block\n\n > .rst-current-version\n display: none\n",".highlight\n &:hover button.copybtn\n color: var(--color-code-foreground)\n\n button.copybtn\n // Make it visible\n opacity: 1\n\n // Align things correctly\n align-items: center\n\n height: 1.25em\n width: 1.25em\n\n top: 0.625rem // $code-spacing-vertical\n right: 0.5rem\n\n // Make it look better\n color: var(--color-background-item)\n background-color: var(--color-code-background)\n border: none\n\n // Change to cursor to make it obvious that you can click on it\n cursor: pointer\n\n // Transition smoothly, for aesthetics\n transition: color 300ms, opacity 300ms\n\n &:hover\n color: var(--color-brand-content)\n background-color: var(--color-code-background)\n\n &::after\n display: none\n color: var(--color-code-foreground)\n background-color: transparent\n\n &.success\n transition: color 0ms\n color: #22863a\n &::after\n display: block\n\n svg\n padding: 0\n","body\n // Colors\n --sd-color-primary: var(--color-brand-primary)\n --sd-color-primary-highlight: var(--color-brand-content)\n --sd-color-primary-text: var(--color-background-primary)\n\n // Shadows\n --sd-color-shadow: rgba(0, 0, 0, 0.05)\n\n // Cards\n --sd-color-card-border: var(--color-card-border)\n --sd-color-card-border-hover: var(--color-brand-content)\n --sd-color-card-background: var(--color-card-background)\n --sd-color-card-text: var(--color-foreground-primary)\n --sd-color-card-header: var(--color-card-marginals-background)\n --sd-color-card-footer: var(--color-card-marginals-background)\n\n // Tabs\n --sd-color-tabs-label-active: var(--color-brand-content)\n --sd-color-tabs-label-hover: var(--color-foreground-muted)\n --sd-color-tabs-label-inactive: var(--color-foreground-muted)\n --sd-color-tabs-underline-active: var(--color-brand-content)\n --sd-color-tabs-underline-hover: var(--color-foreground-border)\n --sd-color-tabs-underline-inactive: var(--color-background-border)\n --sd-color-tabs-overline: var(--color-background-border)\n --sd-color-tabs-underline: var(--color-background-border)\n\n// Tabs\n.sd-tab-content\n box-shadow: 0 -2px var(--sd-color-tabs-overline), 0 1px var(--sd-color-tabs-underline)\n\n// Shadows\n.sd-card // Have a shadow by default\n box-shadow: 0 0.1rem 0.25rem var(--sd-color-shadow), 0 0 0.0625rem rgba(0, 0, 0, 0.1)\n\n.sd-shadow-sm\n box-shadow: 0 0.1rem 0.25rem var(--sd-color-shadow), 0 0 0.0625rem rgba(0, 0, 0, 0.1) !important\n\n.sd-shadow-md\n box-shadow: 0 0.3rem 0.75rem var(--sd-color-shadow), 0 0 0.0625rem rgba(0, 0, 0, 0.1) !important\n\n.sd-shadow-lg\n box-shadow: 0 0.6rem 1.5rem var(--sd-color-shadow), 0 0 0.0625rem rgba(0, 0, 0, 0.1) !important\n\n// Cards\n.sd-card-hover:hover // Don't change scale on hover\n transform: none\n\n.sd-cards-carousel // Have a bit of gap in the carousel by default\n gap: 0.25rem\n padding: 0.25rem\n","// This file contains styles to tweak sphinx-inline-tabs to work well with Furo.\n\nbody\n --tabs--label-text: var(--color-foreground-muted)\n --tabs--label-text--hover: var(--color-foreground-muted)\n --tabs--label-text--active: var(--color-brand-content)\n --tabs--label-text--active--hover: var(--color-brand-content)\n --tabs--label-background: transparent\n --tabs--label-background--hover: transparent\n --tabs--label-background--active: transparent\n --tabs--label-background--active--hover: transparent\n --tabs--padding-x: 0.25em\n --tabs--margin-x: 1em\n --tabs--border: var(--color-background-border)\n --tabs--label-border: transparent\n --tabs--label-border--hover: var(--color-foreground-muted)\n --tabs--label-border--active: var(--color-brand-content)\n --tabs--label-border--active--hover: var(--color-brand-content)\n","// This file contains styles to tweak sphinx-panels to work well with Furo.\n\n// sphinx-panels includes Bootstrap 4, which uses .container which can conflict\n// with docutils' `.. container::` directive.\n[role=\"main\"] .container\n max-width: initial\n padding-left: initial\n padding-right: initial\n\n// Make the panels look nicer!\n.shadow.docutils\n border: none\n box-shadow: 0 0.2rem 0.5rem rgba(0, 0, 0, 0.05), 0 0 0.0625rem rgba(0, 0, 0, 0.1) !important\n\n// Make panel colors respond to dark mode\n.sphinx-bs .card\n background-color: var(--color-background-secondary)\n color: var(--color-foreground)\n"],"names":[],"sourceRoot":""} \ No newline at end of file diff --git a/docs/_build/html/_static/styles/furo.css b/docs/_build/html/_static/styles/furo.css deleted file mode 100644 index 3d29a218f..000000000 --- a/docs/_build/html/_static/styles/furo.css +++ /dev/null @@ -1,2 +0,0 @@ -/*! normalize.css v8.0.1 | MIT License | github.com/necolas/normalize.css */html{-webkit-text-size-adjust:100%;line-height:1.15}body{margin:0}main{display:block}h1{font-size:2em;margin:.67em 0}hr{box-sizing:content-box;height:0;overflow:visible}pre{font-family:monospace,monospace;font-size:1em}a{background-color:transparent}abbr[title]{border-bottom:none;text-decoration:underline;text-decoration:underline dotted}b,strong{font-weight:bolder}code,kbd,samp{font-family:monospace,monospace;font-size:1em}sub,sup{font-size:75%;line-height:0;position:relative;vertical-align:baseline}sub{bottom:-.25em}sup{top:-.5em}img{border-style:none}button,input,optgroup,select,textarea{font-family:inherit;font-size:100%;line-height:1.15;margin:0}button,input{overflow:visible}button,select{text-transform:none}[type=button],[type=reset],[type=submit],button{-webkit-appearance:button}[type=button]::-moz-focus-inner,[type=reset]::-moz-focus-inner,[type=submit]::-moz-focus-inner,button::-moz-focus-inner{border-style:none;padding:0}[type=button]:-moz-focusring,[type=reset]:-moz-focusring,[type=submit]:-moz-focusring,button:-moz-focusring{outline:1px dotted ButtonText}fieldset{padding:.35em .75em .625em}legend{box-sizing:border-box;color:inherit;display:table;max-width:100%;padding:0;white-space:normal}progress{vertical-align:baseline}textarea{overflow:auto}[type=checkbox],[type=radio]{box-sizing:border-box;padding:0}[type=number]::-webkit-inner-spin-button,[type=number]::-webkit-outer-spin-button{height:auto}[type=search]{-webkit-appearance:textfield;outline-offset:-2px}[type=search]::-webkit-search-decoration{-webkit-appearance:none}::-webkit-file-upload-button{-webkit-appearance:button;font:inherit}details{display:block}summary{display:list-item}[hidden],template{display:none}@media print{.content-icon-container,.headerlink,.mobile-header,.related-pages{display:none!important}.highlight{border:.1pt solid var(--color-foreground-border)}a,blockquote,dl,ol,pre,table,ul{page-break-inside:avoid}caption,figure,h1,h2,h3,h4,h5,h6,img{page-break-after:avoid;page-break-inside:avoid}dl,ol,ul{page-break-before:avoid}}.visually-hidden{clip:rect(0,0,0,0)!important;border:0!important;height:1px!important;margin:-1px!important;overflow:hidden!important;padding:0!important;position:absolute!important;white-space:nowrap!important;width:1px!important}:-moz-focusring{outline:auto}body{--font-stack:-apple-system,BlinkMacSystemFont,Segoe UI,Helvetica,Arial,sans-serif,Apple Color Emoji,Segoe UI Emoji;--font-stack--monospace:"SFMono-Regular",Menlo,Consolas,Monaco,Liberation Mono,Lucida Console,monospace;--font-size--normal:100%;--font-size--small:87.5%;--font-size--small--2:81.25%;--font-size--small--3:75%;--font-size--small--4:62.5%;--sidebar-caption-font-size:var(--font-size--small--2);--sidebar-item-font-size:var(--font-size--small);--sidebar-search-input-font-size:var(--font-size--small);--toc-font-size:var(--font-size--small--3);--toc-font-size--mobile:var(--font-size--normal);--toc-title-font-size:var(--font-size--small--4);--admonition-font-size:0.8125rem;--admonition-title-font-size:0.8125rem;--code-font-size:var(--font-size--small--2);--api-font-size:var(--font-size--small);--header-height:calc(var(--sidebar-item-line-height) + var(--sidebar-item-spacing-vertical)*4);--header-padding:0.5rem;--sidebar-tree-space-above:1.5rem;--sidebar-caption-space-above:1rem;--sidebar-item-line-height:1rem;--sidebar-item-spacing-vertical:0.5rem;--sidebar-item-spacing-horizontal:1rem;--sidebar-item-height:calc(var(--sidebar-item-line-height) + var(--sidebar-item-spacing-vertical)*2);--sidebar-expander-width:var(--sidebar-item-height);--sidebar-search-space-above:0.5rem;--sidebar-search-input-spacing-vertical:0.5rem;--sidebar-search-input-spacing-horizontal:0.5rem;--sidebar-search-input-height:1rem;--sidebar-search-icon-size:var(--sidebar-search-input-height);--toc-title-padding:0.25rem 0;--toc-spacing-vertical:1.5rem;--toc-spacing-horizontal:1.5rem;--toc-item-spacing-vertical:0.4rem;--toc-item-spacing-horizontal:1rem;--icon-search:url('data:image/svg+xml;charset=utf-8,');--icon-pencil:url('data:image/svg+xml;charset=utf-8,');--icon-abstract:url('data:image/svg+xml;charset=utf-8,');--icon-info:url('data:image/svg+xml;charset=utf-8,');--icon-flame:url('data:image/svg+xml;charset=utf-8,');--icon-question:url('data:image/svg+xml;charset=utf-8,');--icon-warning:url('data:image/svg+xml;charset=utf-8,');--icon-failure:url('data:image/svg+xml;charset=utf-8,');--icon-spark:url('data:image/svg+xml;charset=utf-8,');--color-admonition-title--caution:#ff9100;--color-admonition-title-background--caution:rgba(255,145,0,.2);--color-admonition-title--warning:#ff9100;--color-admonition-title-background--warning:rgba(255,145,0,.2);--color-admonition-title--danger:#ff5252;--color-admonition-title-background--danger:rgba(255,82,82,.2);--color-admonition-title--attention:#ff5252;--color-admonition-title-background--attention:rgba(255,82,82,.2);--color-admonition-title--error:#ff5252;--color-admonition-title-background--error:rgba(255,82,82,.2);--color-admonition-title--hint:#00c852;--color-admonition-title-background--hint:rgba(0,200,82,.2);--color-admonition-title--tip:#00c852;--color-admonition-title-background--tip:rgba(0,200,82,.2);--color-admonition-title--important:#00bfa5;--color-admonition-title-background--important:rgba(0,191,165,.2);--color-admonition-title--note:#00b0ff;--color-admonition-title-background--note:rgba(0,176,255,.2);--color-admonition-title--seealso:#448aff;--color-admonition-title-background--seealso:rgba(68,138,255,.2);--color-admonition-title--admonition-todo:grey;--color-admonition-title-background--admonition-todo:hsla(0,0%,50%,.2);--color-admonition-title:#651fff;--color-admonition-title-background:rgba(101,31,255,.2);--icon-admonition-default:var(--icon-abstract);--color-topic-title:#14b8a6;--color-topic-title-background:rgba(20,184,166,.2);--icon-topic-default:var(--icon-pencil);--color-problematic:#b30000;--color-foreground-primary:#000;--color-foreground-secondary:#5a5c63;--color-foreground-muted:#646776;--color-foreground-border:#878787;--color-background-primary:#fff;--color-background-secondary:#f8f9fb;--color-background-hover:#efeff4;--color-background-hover--transparent:#efeff400;--color-background-border:#eeebee;--color-background-item:#ccc;--color-announcement-background:#000000dd;--color-announcement-text:#eeebee;--color-brand-primary:#2962ff;--color-brand-content:#2a5adf;--color-api-background:var(--color-background-hover--transparent);--color-api-background-hover:var(--color-background-hover);--color-api-overall:var(--color-foreground-secondary);--color-api-name:var(--color-problematic);--color-api-pre-name:var(--color-problematic);--color-api-paren:var(--color-foreground-secondary);--color-api-keyword:var(--color-foreground-primary);--color-highlight-on-target:#ffc;--color-inline-code-background:var(--color-background-secondary);--color-highlighted-background:#def;--color-highlighted-text:var(--color-foreground-primary);--color-guilabel-background:#ddeeff80;--color-guilabel-border:#bedaf580;--color-guilabel-text:var(--color-foreground-primary);--color-admonition-background:transparent;--color-table-header-background:var(--color-background-secondary);--color-table-border:var(--color-background-border);--color-card-border:var(--color-background-secondary);--color-card-background:transparent;--color-card-marginals-background:var(--color-background-secondary);--color-header-background:var(--color-background-primary);--color-header-border:var(--color-background-border);--color-header-text:var(--color-foreground-primary);--color-sidebar-background:var(--color-background-secondary);--color-sidebar-background-border:var(--color-background-border);--color-sidebar-brand-text:var(--color-foreground-primary);--color-sidebar-caption-text:var(--color-foreground-muted);--color-sidebar-link-text:var(--color-foreground-secondary);--color-sidebar-link-text--top-level:var(--color-brand-primary);--color-sidebar-item-background:var(--color-sidebar-background);--color-sidebar-item-background--current:var( --color-sidebar-item-background );--color-sidebar-item-background--hover:linear-gradient(90deg,var(--color-background-hover--transparent) 0%,var(--color-background-hover) var(--sidebar-item-spacing-horizontal),var(--color-background-hover) 100%);--color-sidebar-item-expander-background:transparent;--color-sidebar-item-expander-background--hover:var( --color-background-hover );--color-sidebar-search-text:var(--color-foreground-primary);--color-sidebar-search-background:var(--color-background-secondary);--color-sidebar-search-background--focus:var(--color-background-primary);--color-sidebar-search-border:var(--color-background-border);--color-sidebar-search-icon:var(--color-foreground-muted);--color-toc-background:var(--color-background-primary);--color-toc-title-text:var(--color-foreground-muted);--color-toc-item-text:var(--color-foreground-secondary);--color-toc-item-text--hover:var(--color-foreground-primary);--color-toc-item-text--active:var(--color-brand-primary);--color-content-foreground:var(--color-foreground-primary);--color-content-background:transparent;--color-link:var(--color-brand-content);--color-link--hover:var(--color-brand-content);--color-link-underline:var(--color-background-border);--color-link-underline--hover:var(--color-foreground-border)}.only-light{display:block!important}html body .only-dark{display:none!important}@media not print{body[data-theme=dark]{--color-problematic:#ee5151;--color-foreground-primary:#ffffffcc;--color-foreground-secondary:#9ca0a5;--color-foreground-muted:#81868d;--color-foreground-border:#666;--color-background-primary:#131416;--color-background-secondary:#1a1c1e;--color-background-hover:#1e2124;--color-background-hover--transparent:#1e212400;--color-background-border:#303335;--color-background-item:#444;--color-announcement-background:#000000dd;--color-announcement-text:#eeebee;--color-brand-primary:#2b8cee;--color-brand-content:#368ce2;--color-highlighted-background:#083563;--color-guilabel-background:#08356380;--color-guilabel-border:#13395f80;--color-api-keyword:var(--color-foreground-secondary);--color-highlight-on-target:#330;--color-admonition-background:#18181a;--color-card-border:var(--color-background-secondary);--color-card-background:#18181a;--color-card-marginals-background:var(--color-background-hover)}html body[data-theme=dark] .only-light{display:none!important}body[data-theme=dark] .only-dark{display:block!important}@media(prefers-color-scheme:dark){body:not([data-theme=light]){--color-problematic:#ee5151;--color-foreground-primary:#ffffffcc;--color-foreground-secondary:#9ca0a5;--color-foreground-muted:#81868d;--color-foreground-border:#666;--color-background-primary:#131416;--color-background-secondary:#1a1c1e;--color-background-hover:#1e2124;--color-background-hover--transparent:#1e212400;--color-background-border:#303335;--color-background-item:#444;--color-announcement-background:#000000dd;--color-announcement-text:#eeebee;--color-brand-primary:#2b8cee;--color-brand-content:#368ce2;--color-highlighted-background:#083563;--color-guilabel-background:#08356380;--color-guilabel-border:#13395f80;--color-api-keyword:var(--color-foreground-secondary);--color-highlight-on-target:#330;--color-admonition-background:#18181a;--color-card-border:var(--color-background-secondary);--color-card-background:#18181a;--color-card-marginals-background:var(--color-background-hover)}html body:not([data-theme=light]) .only-light{display:none!important}body:not([data-theme=light]) .only-dark{display:block!important}}}body[data-theme=auto] .theme-toggle svg.theme-icon-when-auto,body[data-theme=dark] .theme-toggle svg.theme-icon-when-dark,body[data-theme=light] .theme-toggle svg.theme-icon-when-light{display:block}body{font-family:var(--font-stack)}code,kbd,pre,samp{font-family:var(--font-stack--monospace)}body{-webkit-font-smoothing:antialiased;-moz-osx-font-smoothing:grayscale}article{line-height:1.5}h1,h2,h3,h4,h5,h6{border-radius:.5rem;font-weight:700;line-height:1.25;margin:.5rem -.5rem;padding-left:.5rem;padding-right:.5rem}h1+p,h2+p,h3+p,h4+p,h5+p,h6+p{margin-top:0}h1{font-size:2.5em;margin-bottom:1rem}h1,h2{margin-top:1.75rem}h2{font-size:2em}h3{font-size:1.5em}h4{font-size:1.25em}h5{font-size:1.125em}h6{font-size:1em}small{font-size:80%;opacity:75%}p{margin-bottom:.75rem;margin-top:.5rem}hr.docutils{background-color:var(--color-background-border);border:0;height:1px;margin:2rem 0;padding:0}.centered{text-align:center}a{color:var(--color-link);text-decoration:underline;text-decoration-color:var(--color-link-underline)}a:hover{color:var(--color-link--hover);text-decoration-color:var(--color-link-underline--hover)}a.muted-link{color:inherit}a.muted-link:hover{color:var(--color-link);text-decoration-color:var(--color-link-underline--hover)}html{overflow-x:hidden;overflow-y:scroll;scroll-behavior:smooth}.sidebar-scroll,.toc-scroll,article[role=main] *{scrollbar-color:var(--color-foreground-border) transparent;scrollbar-width:thin}.sidebar-scroll::-webkit-scrollbar,.toc-scroll::-webkit-scrollbar,article[role=main] ::-webkit-scrollbar{height:.25rem;width:.25rem}.sidebar-scroll::-webkit-scrollbar-thumb,.toc-scroll::-webkit-scrollbar-thumb,article[role=main] ::-webkit-scrollbar-thumb{background-color:var(--color-foreground-border);border-radius:.125rem}body,html{background:var(--color-background-primary);color:var(--color-foreground-primary);height:100%}article{background:var(--color-content-background);color:var(--color-content-foreground);overflow-wrap:break-word}.page{display:flex;min-height:100%}.mobile-header{background-color:var(--color-header-background);border-bottom:1px solid var(--color-header-border);color:var(--color-header-text);display:none;height:var(--header-height);width:100%;z-index:10}.mobile-header.scrolled{border-bottom:none;box-shadow:0 0 .2rem rgba(0,0,0,.1),0 .2rem .4rem rgba(0,0,0,.2)}.mobile-header .header-center a{color:var(--color-header-text);text-decoration:none}.main{display:flex;flex:1}.sidebar-drawer{background:var(--color-sidebar-background);border-right:1px solid var(--color-sidebar-background-border);box-sizing:border-box;display:flex;justify-content:flex-end;min-width:15em;width:calc(50% - 26em)}.sidebar-container,.toc-drawer{box-sizing:border-box;width:15em}.toc-drawer{background:var(--color-toc-background);padding-right:1rem}.sidebar-sticky,.toc-sticky{display:flex;flex-direction:column;height:min(100%,100vh);height:100vh;position:sticky;top:0}.sidebar-scroll,.toc-scroll{flex-grow:1;flex-shrink:1;overflow:auto;scroll-behavior:smooth}.content{display:flex;flex-direction:column;justify-content:space-between;padding:0 3em;width:46em}.icon{display:inline-block;height:1rem;width:1rem}.icon svg{height:100%;width:100%}.announcement{align-items:center;background-color:var(--color-announcement-background);color:var(--color-announcement-text);display:flex;height:var(--header-height);overflow-x:auto}.announcement+.page{min-height:calc(100% - var(--header-height))}.announcement-content{box-sizing:border-box;min-width:100%;padding:.5rem;text-align:center;white-space:nowrap}.announcement-content a{color:var(--color-announcement-text);text-decoration-color:var(--color-announcement-text)}.announcement-content a:hover{color:var(--color-announcement-text);text-decoration-color:var(--color-link--hover)}.no-js .theme-toggle-container{display:none}.theme-toggle-container{vertical-align:middle}.theme-toggle{background:transparent;border:none;cursor:pointer;padding:0}.theme-toggle svg{color:var(--color-foreground-primary);display:none;height:1rem;vertical-align:middle;width:1rem}.theme-toggle-header{float:left;padding:1rem .5rem}.nav-overlay-icon,.toc-overlay-icon{cursor:pointer;display:none}.nav-overlay-icon .icon,.toc-overlay-icon .icon{color:var(--color-foreground-secondary);height:1rem;width:1rem}.nav-overlay-icon,.toc-header-icon{align-items:center;justify-content:center}.toc-content-icon{height:1.5rem;width:1.5rem}.content-icon-container{display:flex;float:right;gap:.5rem;margin-bottom:1rem;margin-left:1rem;margin-top:1.5rem}.content-icon-container .edit-this-page svg{color:inherit;height:1rem;width:1rem}.sidebar-toggle{display:none;position:absolute}.sidebar-toggle[name=__toc]{left:20px}.sidebar-toggle:checked{left:40px}.overlay{background-color:rgba(0,0,0,.54);height:0;opacity:0;position:fixed;top:0;transition:width 0ms,height 0ms,opacity .25s ease-out;width:0}.sidebar-overlay{z-index:20}.toc-overlay{z-index:40}.sidebar-drawer{transition:left .25s ease-in-out;z-index:30}.toc-drawer{transition:right .25s ease-in-out;z-index:50}#__navigation:checked~.sidebar-overlay{height:100%;opacity:1;width:100%}#__navigation:checked~.page .sidebar-drawer{left:0;top:0}#__toc:checked~.toc-overlay{height:100%;opacity:1;width:100%}#__toc:checked~.page .toc-drawer{right:0;top:0}.back-to-top{background:var(--color-background-primary);border-radius:1rem;box-shadow:0 .2rem .5rem rgba(0,0,0,.05),0 0 1px 0 hsla(220,9%,46%,.502);display:none;font-size:.8125rem;left:0;margin-left:50%;padding:.5rem .75rem .5rem .5rem;position:fixed;text-decoration:none;top:1rem;transform:translateX(-50%);z-index:10}.back-to-top svg{fill:currentColor;display:inline-block;height:1rem;width:1rem}.back-to-top span{margin-left:.25rem}.show-back-to-top .back-to-top{align-items:center;display:flex}@media(min-width:97em){html{font-size:110%}}@media(max-width:82em){.toc-content-icon{display:flex}.toc-drawer{border-left:1px solid var(--color-background-muted);height:100vh;position:fixed;right:-15em;top:0}.toc-tree{border-left:none;font-size:var(--toc-font-size--mobile)}.sidebar-drawer{width:calc(50% - 18.5em)}}@media(max-width:67em){.nav-overlay-icon{display:flex}.sidebar-drawer{height:100vh;left:-15em;position:fixed;top:0;width:15em}.toc-header-icon{display:flex}.theme-toggle-content,.toc-content-icon{display:none}.theme-toggle-header{display:block}.mobile-header{align-items:center;display:flex;justify-content:space-between;position:sticky;top:0}.mobile-header .header-left,.mobile-header .header-right{display:flex;height:var(--header-height);padding:0 var(--header-padding)}.mobile-header .header-left label,.mobile-header .header-right label{height:100%;-webkit-user-select:none;-moz-user-select:none;user-select:none;width:100%}.nav-overlay-icon .icon,.theme-toggle svg{height:1.25rem;width:1.25rem}:target{scroll-margin-top:var(--header-height)}.back-to-top{top:calc(var(--header-height) + .5rem)}.page{flex-direction:column;justify-content:center}.content{margin-left:auto;margin-right:auto}}@media(max-width:52em){.content{overflow-x:auto;width:100%}}@media(max-width:46em){.content{padding:0 1em}article aside.sidebar{float:none;margin:1rem 0;width:100%}}.admonition,.topic{background:var(--color-admonition-background);border-radius:.2rem;box-shadow:0 .2rem .5rem rgba(0,0,0,.05),0 0 .0625rem rgba(0,0,0,.1);font-size:var(--admonition-font-size);margin:1rem auto;overflow:hidden;padding:0 .5rem .5rem;page-break-inside:avoid}.admonition>:nth-child(2),.topic>:nth-child(2){margin-top:0}.admonition>:last-child,.topic>:last-child{margin-bottom:0}.admonition p.admonition-title,p.topic-title{font-size:var(--admonition-title-font-size);font-weight:500;line-height:1.3;margin:0 -.5rem .5rem;padding:.4rem .5rem .4rem 2rem;position:relative}.admonition p.admonition-title:before,p.topic-title:before{content:"";height:1rem;left:.5rem;position:absolute;width:1rem}p.admonition-title{background-color:var(--color-admonition-title-background)}p.admonition-title:before{background-color:var(--color-admonition-title);-webkit-mask-image:var(--icon-admonition-default);mask-image:var(--icon-admonition-default);-webkit-mask-repeat:no-repeat;mask-repeat:no-repeat}p.topic-title{background-color:var(--color-topic-title-background)}p.topic-title:before{background-color:var(--color-topic-title);-webkit-mask-image:var(--icon-topic-default);mask-image:var(--icon-topic-default);-webkit-mask-repeat:no-repeat;mask-repeat:no-repeat}.admonition{border-left:.2rem solid var(--color-admonition-title)}.admonition.caution{border-left-color:var(--color-admonition-title--caution)}.admonition.caution>.admonition-title{background-color:var(--color-admonition-title-background--caution)}.admonition.caution>.admonition-title:before{background-color:var(--color-admonition-title--caution);-webkit-mask-image:var(--icon-spark);mask-image:var(--icon-spark)}.admonition.warning{border-left-color:var(--color-admonition-title--warning)}.admonition.warning>.admonition-title{background-color:var(--color-admonition-title-background--warning)}.admonition.warning>.admonition-title:before{background-color:var(--color-admonition-title--warning);-webkit-mask-image:var(--icon-warning);mask-image:var(--icon-warning)}.admonition.danger{border-left-color:var(--color-admonition-title--danger)}.admonition.danger>.admonition-title{background-color:var(--color-admonition-title-background--danger)}.admonition.danger>.admonition-title:before{background-color:var(--color-admonition-title--danger);-webkit-mask-image:var(--icon-spark);mask-image:var(--icon-spark)}.admonition.attention{border-left-color:var(--color-admonition-title--attention)}.admonition.attention>.admonition-title{background-color:var(--color-admonition-title-background--attention)}.admonition.attention>.admonition-title:before{background-color:var(--color-admonition-title--attention);-webkit-mask-image:var(--icon-warning);mask-image:var(--icon-warning)}.admonition.error{border-left-color:var(--color-admonition-title--error)}.admonition.error>.admonition-title{background-color:var(--color-admonition-title-background--error)}.admonition.error>.admonition-title:before{background-color:var(--color-admonition-title--error);-webkit-mask-image:var(--icon-failure);mask-image:var(--icon-failure)}.admonition.hint{border-left-color:var(--color-admonition-title--hint)}.admonition.hint>.admonition-title{background-color:var(--color-admonition-title-background--hint)}.admonition.hint>.admonition-title:before{background-color:var(--color-admonition-title--hint);-webkit-mask-image:var(--icon-question);mask-image:var(--icon-question)}.admonition.tip{border-left-color:var(--color-admonition-title--tip)}.admonition.tip>.admonition-title{background-color:var(--color-admonition-title-background--tip)}.admonition.tip>.admonition-title:before{background-color:var(--color-admonition-title--tip);-webkit-mask-image:var(--icon-info);mask-image:var(--icon-info)}.admonition.important{border-left-color:var(--color-admonition-title--important)}.admonition.important>.admonition-title{background-color:var(--color-admonition-title-background--important)}.admonition.important>.admonition-title:before{background-color:var(--color-admonition-title--important);-webkit-mask-image:var(--icon-flame);mask-image:var(--icon-flame)}.admonition.note{border-left-color:var(--color-admonition-title--note)}.admonition.note>.admonition-title{background-color:var(--color-admonition-title-background--note)}.admonition.note>.admonition-title:before{background-color:var(--color-admonition-title--note);-webkit-mask-image:var(--icon-pencil);mask-image:var(--icon-pencil)}.admonition.seealso{border-left-color:var(--color-admonition-title--seealso)}.admonition.seealso>.admonition-title{background-color:var(--color-admonition-title-background--seealso)}.admonition.seealso>.admonition-title:before{background-color:var(--color-admonition-title--seealso);-webkit-mask-image:var(--icon-info);mask-image:var(--icon-info)}.admonition.admonition-todo{border-left-color:var(--color-admonition-title--admonition-todo)}.admonition.admonition-todo>.admonition-title{background-color:var(--color-admonition-title-background--admonition-todo)}.admonition.admonition-todo>.admonition-title:before{background-color:var(--color-admonition-title--admonition-todo);-webkit-mask-image:var(--icon-pencil);mask-image:var(--icon-pencil)}.admonition-todo>.admonition-title{text-transform:uppercase}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) dd{margin-left:2rem}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) dd>:first-child{margin-top:.125rem}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) .field-list,dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) dd>:last-child{margin-bottom:.75rem}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) .field-list>dt{font-size:var(--font-size--small);text-transform:uppercase}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) .field-list dd:empty{margin-bottom:.5rem}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) .field-list dd>ul{margin-left:-1.2rem}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) .field-list dd>ul>li>p:nth-child(2){margin-top:0}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple) .field-list dd>ul>li>p+p:last-child:empty{margin-bottom:0;margin-top:0}dl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple)>dt{color:var(--color-api-overall)}.sig:not(.sig-inline){background:var(--color-api-background);border-radius:.25rem;font-family:var(--font-stack--monospace);font-size:var(--api-font-size);font-weight:700;margin-left:-.25rem;margin-right:-.25rem;padding:.25rem .5rem .25rem 3em;text-indent:-2.5em;transition:background .1s ease-out}.sig:not(.sig-inline):hover{background:var(--color-api-background-hover)}.sig:not(.sig-inline) a.reference .viewcode-link{font-weight:400;width:3.5rem}em.property{font-style:normal}em.property:first-child{color:var(--color-api-keyword)}.sig-name{color:var(--color-api-name)}.sig-prename{color:var(--color-api-pre-name);font-weight:400}.sig-paren{color:var(--color-api-paren)}.sig-param{font-style:normal}.versionmodified{font-style:italic}div.deprecated p,div.versionadded p,div.versionchanged p{margin-bottom:.125rem;margin-top:.125rem}.viewcode-back,.viewcode-link{float:right;text-align:right}.line-block{margin-bottom:.75rem;margin-top:.5rem}.line-block .line-block{margin-bottom:0;margin-top:0;padding-left:1rem}.code-block-caption,article p.caption,table>caption{font-size:var(--font-size--small);text-align:center}.toctree-wrapper.compound .caption,.toctree-wrapper.compound :not(.caption)>.caption-text{font-size:var(--font-size--small);margin-bottom:0;text-align:initial;text-transform:uppercase}.toctree-wrapper.compound>ul{margin-bottom:0;margin-top:0}.sig-inline,code.literal{background:var(--color-inline-code-background);border-radius:.2em;font-size:var(--font-size--small--2);padding:.1em .2em}pre.literal-block .sig-inline,pre.literal-block code.literal{font-size:inherit;padding:0}p .sig-inline,p code.literal{border:1px solid var(--color-background-border)}.sig-inline{font-family:var(--font-stack--monospace)}div[class*=" highlight-"],div[class^=highlight-]{display:flex;margin:1em 0}div[class*=" highlight-"] .table-wrapper,div[class^=highlight-] .table-wrapper,pre{margin:0;padding:0}pre{overflow:auto}article[role=main] .highlight pre{line-height:1.5}.highlight pre,pre.literal-block{font-size:var(--code-font-size);padding:.625rem .875rem}pre.literal-block{background-color:var(--color-code-background);border-radius:.2rem;color:var(--color-code-foreground);margin-bottom:1rem;margin-top:1rem}.highlight{border-radius:.2rem;width:100%}.highlight .gp,.highlight span.linenos{pointer-events:none;-webkit-user-select:none;-moz-user-select:none;user-select:none}.highlight .hll{display:block;margin-left:-.875rem;margin-right:-.875rem;padding-left:.875rem;padding-right:.875rem}.code-block-caption{background-color:var(--color-code-background);border-bottom:1px solid;border-radius:.25rem;border-bottom-left-radius:0;border-bottom-right-radius:0;border-color:var(--color-background-border);color:var(--color-code-foreground);display:flex;font-weight:300;padding:.625rem .875rem}.code-block-caption+div[class]{margin-top:0}.code-block-caption+div[class] pre{border-top-left-radius:0;border-top-right-radius:0}.highlighttable{display:block;width:100%}.highlighttable tbody{display:block}.highlighttable tr{display:flex}.highlighttable td.linenos{background-color:var(--color-code-background);border-bottom-left-radius:.2rem;border-top-left-radius:.2rem;color:var(--color-code-foreground);padding:.625rem 0 .625rem .875rem}.highlighttable .linenodiv{box-shadow:-.0625rem 0 var(--color-foreground-border) inset;font-size:var(--code-font-size);padding-right:.875rem}.highlighttable td.code{display:block;flex:1;overflow:hidden;padding:0}.highlighttable td.code .highlight{border-bottom-left-radius:0;border-top-left-radius:0}.highlight span.linenos{box-shadow:-.0625rem 0 var(--color-foreground-border) inset;display:inline-block;margin-right:.875rem;padding-left:0;padding-right:.875rem}.footnote-reference{font-size:var(--font-size--small--4);vertical-align:super}dl.footnote.brackets{color:var(--color-foreground-secondary);display:grid;font-size:var(--font-size--small);grid-template-columns:max-content auto}dl.footnote.brackets dt{margin:0}dl.footnote.brackets dt>.fn-backref{margin-left:.25rem}dl.footnote.brackets dt:after{content:":"}dl.footnote.brackets dt .brackets:before{content:"["}dl.footnote.brackets dt .brackets:after{content:"]"}dl.footnote.brackets dd{margin:0;padding:0 1rem}aside.footnote{color:var(--color-foreground-secondary);font-size:var(--font-size--small)}aside.footnote>span,div.citation>span{float:left;font-weight:500;padding-right:.25rem}aside.footnote>p,div.citation>p{margin-left:2rem}img{box-sizing:border-box;height:auto;max-width:100%}article .figure,article figure{border-radius:.2rem;margin:0}article .figure :last-child,article figure :last-child{margin-bottom:0}article .align-left{clear:left;float:left;margin:0 1rem 1rem}article .align-right{clear:right;float:right;margin:0 1rem 1rem}article .align-center,article .align-default{display:block;margin-left:auto;margin-right:auto;text-align:center}article table.align-default{display:table;text-align:initial}.domainindex-jumpbox,.genindex-jumpbox{border-bottom:1px solid var(--color-background-border);border-top:1px solid var(--color-background-border);padding:.25rem}.domainindex-section h2,.genindex-section h2{margin-bottom:.5rem;margin-top:.75rem}.domainindex-section ul,.genindex-section ul{margin-bottom:0;margin-top:0}ol,ul{margin-bottom:1rem;margin-top:1rem;padding-left:1.2rem}ol li>p:first-child,ul li>p:first-child{margin-bottom:.25rem;margin-top:.25rem}ol li>p:last-child,ul li>p:last-child{margin-top:.25rem}ol li>ol,ol li>ul,ul li>ol,ul li>ul{margin-bottom:.5rem;margin-top:.5rem}ol.arabic{list-style:decimal}ol.loweralpha{list-style:lower-alpha}ol.upperalpha{list-style:upper-alpha}ol.lowerroman{list-style:lower-roman}ol.upperroman{list-style:upper-roman}.simple li>ol,.simple li>ul,.toctree-wrapper li>ol,.toctree-wrapper li>ul{margin-bottom:0;margin-top:0}.field-list dt,.option-list dt,dl.footnote dt,dl.glossary dt,dl.simple dt,dl:not([class]) dt{font-weight:500;margin-top:.25rem}.field-list dt+dt,.option-list dt+dt,dl.footnote dt+dt,dl.glossary dt+dt,dl.simple dt+dt,dl:not([class]) dt+dt{margin-top:0}.field-list dt .classifier:before,.option-list dt .classifier:before,dl.footnote dt .classifier:before,dl.glossary dt .classifier:before,dl.simple dt .classifier:before,dl:not([class]) dt .classifier:before{content:":";margin-left:.2rem;margin-right:.2rem}.field-list dd ul,.field-list dd>p:first-child,.option-list dd ul,.option-list dd>p:first-child,dl.footnote dd ul,dl.footnote dd>p:first-child,dl.glossary dd ul,dl.glossary dd>p:first-child,dl.simple dd ul,dl.simple dd>p:first-child,dl:not([class]) dd ul,dl:not([class]) dd>p:first-child{margin-top:.125rem}.field-list dd ul,.option-list dd ul,dl.footnote dd ul,dl.glossary dd ul,dl.simple dd ul,dl:not([class]) dd ul{margin-bottom:.125rem}.math-wrapper{overflow-x:auto;width:100%}div.math{position:relative;text-align:center}div.math .headerlink,div.math:focus .headerlink{display:none}div.math:hover .headerlink{display:inline-block}div.math span.eqno{position:absolute;right:.5rem;top:50%;transform:translateY(-50%);z-index:1}abbr[title]{cursor:help}.problematic{color:var(--color-problematic)}kbd:not(.compound){background-color:var(--color-background-secondary);border:1px solid var(--color-foreground-border);border-radius:.2rem;box-shadow:0 .0625rem 0 rgba(0,0,0,.2),inset 0 0 0 .125rem var(--color-background-primary);color:var(--color-foreground-primary);display:inline-block;font-size:var(--font-size--small--3);margin:0 .2rem;padding:0 .2rem;vertical-align:text-bottom}blockquote{background:var(--color-background-secondary);border-left:4px solid var(--color-background-border);margin-left:0;margin-right:0;padding:.5rem 1rem}blockquote .attribution{font-weight:600;text-align:right}blockquote.highlights,blockquote.pull-quote{font-size:1.25em}blockquote.epigraph,blockquote.pull-quote{border-left-width:0;border-radius:.5rem}blockquote.highlights{background:transparent;border-left-width:0}p .reference img{vertical-align:middle}p.rubric{font-size:1.125em;font-weight:700;line-height:1.25}dd p.rubric{font-size:var(--font-size--small);font-weight:inherit;line-height:inherit;text-transform:uppercase}article .sidebar{background-color:var(--color-background-secondary);border:1px solid var(--color-background-border);border-radius:.2rem;clear:right;float:right;margin-left:1rem;margin-right:0;width:30%}article .sidebar>*{padding-left:1rem;padding-right:1rem}article .sidebar>ol,article .sidebar>ul{padding-left:2.2rem}article .sidebar .sidebar-title{border-bottom:1px solid var(--color-background-border);font-weight:500;margin:0;padding:.5rem 1rem}.table-wrapper{margin-bottom:.5rem;margin-top:1rem;overflow-x:auto;padding:.2rem .2rem .75rem;width:100%}table.docutils{border-collapse:collapse;border-radius:.2rem;border-spacing:0;box-shadow:0 .2rem .5rem rgba(0,0,0,.05),0 0 .0625rem rgba(0,0,0,.1)}table.docutils th{background:var(--color-table-header-background)}table.docutils td,table.docutils th{border-bottom:1px solid var(--color-table-border);border-left:1px solid var(--color-table-border);border-right:1px solid var(--color-table-border);padding:0 .25rem}table.docutils td p,table.docutils th p{margin:.25rem}table.docutils td:first-child,table.docutils th:first-child{border-left:none}table.docutils td:last-child,table.docutils th:last-child{border-right:none}table.docutils td.text-left,table.docutils th.text-left{text-align:left}table.docutils td.text-right,table.docutils th.text-right{text-align:right}table.docutils td.text-center,table.docutils th.text-center{text-align:center}:target{scroll-margin-top:.5rem}@media(max-width:67em){:target{scroll-margin-top:calc(.5rem + var(--header-height))}section>span:target{scroll-margin-top:calc(.8rem + var(--header-height))}}.headerlink{font-weight:100;-webkit-user-select:none;-moz-user-select:none;user-select:none}.code-block-caption>.headerlink,dl dt>.headerlink,figcaption p>.headerlink,h1>.headerlink,h2>.headerlink,h3>.headerlink,h4>.headerlink,h5>.headerlink,h6>.headerlink,p.caption>.headerlink,table>caption>.headerlink{margin-left:.5rem;visibility:hidden}.code-block-caption:hover>.headerlink,dl dt:hover>.headerlink,figcaption p:hover>.headerlink,h1:hover>.headerlink,h2:hover>.headerlink,h3:hover>.headerlink,h4:hover>.headerlink,h5:hover>.headerlink,h6:hover>.headerlink,p.caption:hover>.headerlink,table>caption:hover>.headerlink{visibility:visible}.code-block-caption>.toc-backref,dl dt>.toc-backref,figcaption p>.toc-backref,h1>.toc-backref,h2>.toc-backref,h3>.toc-backref,h4>.toc-backref,h5>.toc-backref,h6>.toc-backref,p.caption>.toc-backref,table>caption>.toc-backref{color:inherit;text-decoration-line:none}figure:hover>figcaption>p>.headerlink,table:hover>caption>.headerlink{visibility:visible}:target>h1:first-of-type,:target>h2:first-of-type,:target>h3:first-of-type,:target>h4:first-of-type,:target>h5:first-of-type,:target>h6:first-of-type,span:target~h1:first-of-type,span:target~h2:first-of-type,span:target~h3:first-of-type,span:target~h4:first-of-type,span:target~h5:first-of-type,span:target~h6:first-of-type{background-color:var(--color-highlight-on-target)}:target>h1:first-of-type code.literal,:target>h2:first-of-type code.literal,:target>h3:first-of-type code.literal,:target>h4:first-of-type code.literal,:target>h5:first-of-type code.literal,:target>h6:first-of-type code.literal,span:target~h1:first-of-type code.literal,span:target~h2:first-of-type code.literal,span:target~h3:first-of-type code.literal,span:target~h4:first-of-type code.literal,span:target~h5:first-of-type code.literal,span:target~h6:first-of-type code.literal{background-color:transparent}.literal-block-wrapper:target .code-block-caption,.this-will-duplicate-information-and-it-is-still-useful-here li :target,figure:target,table:target>caption{background-color:var(--color-highlight-on-target)}dt:target{background-color:var(--color-highlight-on-target)!important}.footnote-reference:target,.footnote>dt:target+dd{background-color:var(--color-highlight-on-target)}.guilabel{background-color:var(--color-guilabel-background);border:1px solid var(--color-guilabel-border);border-radius:.5em;color:var(--color-guilabel-text);font-size:.9em;padding:0 .3em}footer{display:flex;flex-direction:column;font-size:var(--font-size--small);margin-top:2rem}.bottom-of-page{align-items:center;border-top:1px solid var(--color-background-border);color:var(--color-foreground-secondary);display:flex;justify-content:space-between;line-height:1.5;margin-top:1rem;padding-bottom:1rem;padding-top:1rem}@media(max-width:46em){.bottom-of-page{flex-direction:column-reverse;gap:.25rem;text-align:center}}.bottom-of-page .left-details{font-size:var(--font-size--small)}.bottom-of-page .right-details{display:flex;flex-direction:column;gap:.25rem;text-align:right}.bottom-of-page .icons{display:flex;font-size:1rem;gap:.25rem;justify-content:flex-end}.bottom-of-page .icons a{text-decoration:none}.bottom-of-page .icons img,.bottom-of-page .icons svg{font-size:1.125rem;height:1em;width:1em}.related-pages a{align-items:center;display:flex;text-decoration:none}.related-pages a:hover .page-info .title{color:var(--color-link);text-decoration:underline;text-decoration-color:var(--color-link-underline)}.related-pages a svg.furo-related-icon,.related-pages a svg.furo-related-icon>use{color:var(--color-foreground-border);flex-shrink:0;height:.75rem;margin:0 .5rem;width:.75rem}.related-pages a.next-page{clear:right;float:right;max-width:50%;text-align:right}.related-pages a.prev-page{clear:left;float:left;max-width:50%}.related-pages a.prev-page svg{transform:rotate(180deg)}.page-info{display:flex;flex-direction:column;overflow-wrap:anywhere}.next-page .page-info{align-items:flex-end}.page-info .context{align-items:center;color:var(--color-foreground-muted);display:flex;font-size:var(--font-size--small);padding-bottom:.1rem;text-decoration:none}ul.search{list-style:none;padding-left:0}ul.search li{border-bottom:1px solid var(--color-background-border);padding:1rem 0}[role=main] .highlighted{background-color:var(--color-highlighted-background);color:var(--color-highlighted-text)}.sidebar-brand{display:flex;flex-direction:column;flex-shrink:0;padding:var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal);text-decoration:none}.sidebar-brand-text{color:var(--color-sidebar-brand-text);font-size:1.5rem;overflow-wrap:break-word}.sidebar-brand-text,.sidebar-logo-container{margin:var(--sidebar-item-spacing-vertical) 0}.sidebar-logo{display:block;margin:0 auto;max-width:100%}.sidebar-search-container{align-items:center;background:var(--color-sidebar-search-background);display:flex;margin-top:var(--sidebar-search-space-above);position:relative}.sidebar-search-container:focus-within,.sidebar-search-container:hover{background:var(--color-sidebar-search-background--focus)}.sidebar-search-container:before{background-color:var(--color-sidebar-search-icon);content:"";height:var(--sidebar-search-icon-size);left:var(--sidebar-item-spacing-horizontal);-webkit-mask-image:var(--icon-search);mask-image:var(--icon-search);position:absolute;width:var(--sidebar-search-icon-size)}.sidebar-search{background:transparent;border:none;border-bottom:1px solid var(--color-sidebar-search-border);border-top:1px solid var(--color-sidebar-search-border);box-sizing:border-box;color:var(--color-sidebar-search-foreground);padding:var(--sidebar-search-input-spacing-vertical) var(--sidebar-search-input-spacing-horizontal) var(--sidebar-search-input-spacing-vertical) calc(var(--sidebar-item-spacing-horizontal) + var(--sidebar-search-input-spacing-horizontal) + var(--sidebar-search-icon-size));width:100%;z-index:10}.sidebar-search:focus{outline:none}.sidebar-search::-moz-placeholder{font-size:var(--sidebar-search-input-font-size)}.sidebar-search::placeholder{font-size:var(--sidebar-search-input-font-size)}#searchbox .highlight-link{margin:0;padding:var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal) 0;text-align:center}#searchbox .highlight-link a{color:var(--color-sidebar-search-icon);font-size:var(--font-size--small--2)}.sidebar-tree{font-size:var(--sidebar-item-font-size);margin-bottom:var(--sidebar-item-spacing-vertical);margin-top:var(--sidebar-tree-space-above)}.sidebar-tree ul{display:flex;flex-direction:column;list-style:none;margin-bottom:0;margin-top:0;padding:0}.sidebar-tree li{margin:0;position:relative}.sidebar-tree li>ul{margin-left:var(--sidebar-item-spacing-horizontal)}.sidebar-tree .icon,.sidebar-tree .reference{color:var(--color-sidebar-link-text)}.sidebar-tree .reference{box-sizing:border-box;display:inline-block;height:100%;line-height:var(--sidebar-item-line-height);overflow-wrap:anywhere;padding:var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal);text-decoration:none;width:100%}.sidebar-tree .reference:hover{background:var(--color-sidebar-item-background--hover)}.sidebar-tree .reference.external:after{color:var(--color-sidebar-link-text);content:url("data:image/svg+xml;charset=utf-8,%3Csvg width='12' height='12' xmlns='http://www.w3.org/2000/svg' viewBox='0 0 24 24' stroke-width='1.5' stroke='%23607D8B' fill='none' stroke-linecap='round' stroke-linejoin='round'%3E%3Cpath d='M0 0h24v24H0z' stroke='none'/%3E%3Cpath d='M11 7H6a2 2 0 0 0-2 2v9a2 2 0 0 0 2 2h9a2 2 0 0 0 2-2v-5M10 14 20 4M15 4h5v5'/%3E%3C/svg%3E");margin:0 .25rem;vertical-align:middle}.sidebar-tree .current-page>.reference{font-weight:700}.sidebar-tree label{align-items:center;cursor:pointer;display:flex;height:var(--sidebar-item-height);justify-content:center;position:absolute;right:0;top:0;-webkit-user-select:none;-moz-user-select:none;user-select:none;width:var(--sidebar-expander-width)}.sidebar-tree .caption,.sidebar-tree :not(.caption)>.caption-text{color:var(--color-sidebar-caption-text);font-size:var(--sidebar-caption-font-size);font-weight:700;margin:var(--sidebar-caption-space-above) 0 0 0;padding:var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal);text-transform:uppercase}.sidebar-tree li.has-children>.reference{padding-right:var(--sidebar-expander-width)}.sidebar-tree .toctree-l1>.reference,.sidebar-tree .toctree-l1>label .icon{color:var(--color-sidebar-link-text--top-level)}.sidebar-tree label{background:var(--color-sidebar-item-expander-background)}.sidebar-tree label:hover{background:var(--color-sidebar-item-expander-background--hover)}.sidebar-tree .current>.reference{background:var(--color-sidebar-item-background--current)}.sidebar-tree .current>.reference:hover{background:var(--color-sidebar-item-background--hover)}.toctree-checkbox{display:none;position:absolute}.toctree-checkbox~ul{display:none}.toctree-checkbox~label .icon svg{transform:rotate(90deg)}.toctree-checkbox:checked~ul{display:block}.toctree-checkbox:checked~label .icon svg{transform:rotate(-90deg)}.toc-title-container{padding:var(--toc-title-padding);padding-top:var(--toc-spacing-vertical)}.toc-title{color:var(--color-toc-title-text);font-size:var(--toc-title-font-size);padding-left:var(--toc-spacing-horizontal);text-transform:uppercase}.no-toc{display:none}.toc-tree-container{padding-bottom:var(--toc-spacing-vertical)}.toc-tree{border-left:1px solid var(--color-background-border);font-size:var(--toc-font-size);line-height:1.3;padding-left:calc(var(--toc-spacing-horizontal) - var(--toc-item-spacing-horizontal))}.toc-tree>ul>li:first-child{padding-top:0}.toc-tree>ul>li:first-child>ul{padding-left:0}.toc-tree>ul>li:first-child>a{display:none}.toc-tree ul{list-style-type:none;margin-bottom:0;margin-top:0;padding-left:var(--toc-item-spacing-horizontal)}.toc-tree li{padding-top:var(--toc-item-spacing-vertical)}.toc-tree li.scroll-current>.reference{color:var(--color-toc-item-text--active);font-weight:700}.toc-tree .reference{color:var(--color-toc-item-text);overflow-wrap:anywhere;text-decoration:none}.toc-scroll{max-height:100vh;overflow-y:scroll}.contents:not(.this-will-duplicate-information-and-it-is-still-useful-here){background:rgba(255,0,0,.25);color:var(--color-problematic)}.contents:not(.this-will-duplicate-information-and-it-is-still-useful-here):before{content:"ERROR: Adding a table of contents in Furo-based documentation is unnecessary, and does not work well with existing styling.Add a 'this-will-duplicate-information-and-it-is-still-useful-here' class, if you want an escape hatch."}.text-align\:left>p{text-align:left}.text-align\:center>p{text-align:center}.text-align\:right>p{text-align:right} -/*# sourceMappingURL=furo.css.map*/ \ No newline at end of file diff --git a/docs/_build/html/_static/styles/furo.css.map b/docs/_build/html/_static/styles/furo.css.map deleted file mode 100644 index d1dfb109d..000000000 --- a/docs/_build/html/_static/styles/furo.css.map +++ /dev/null @@ -1 +0,0 @@ -{"version":3,"file":"styles/furo.css","mappings":"AAAA,2EAA2E,CAU3E,KAEE,6BAA8B,CAD9B,gBAEF,CASA,KACE,QACF,CAMA,KACE,aACF,CAOA,GACE,aAAc,CACd,cACF,CAUA,GACE,sBAAuB,CACvB,QAAS,CACT,gBACF,CAOA,IACE,+BAAiC,CACjC,aACF,CASA,EACE,4BACF,CAOA,YACE,kBAAmB,CACnB,yBAA0B,CAC1B,gCACF,CAMA,SAEE,kBACF,CAOA,cAGE,+BAAiC,CACjC,aACF,CAeA,QAEE,aAAc,CACd,aAAc,CACd,iBAAkB,CAClB,uBACF,CAEA,IACE,aACF,CAEA,IACE,SACF,CASA,IACE,iBACF,CAUA,sCAKE,mBAAoB,CACpB,cAAe,CACf,gBAAiB,CACjB,QACF,CAOA,aAEE,gBACF,CAOA,cAEE,mBACF,CAMA,gDAIE,yBACF,CAMA,wHAIE,iBAAkB,CAClB,SACF,CAMA,4GAIE,6BACF,CAMA,SACE,0BACF,CASA,OACE,qBAAsB,CACtB,aAAc,CACd,aAAc,CACd,cAAe,CACf,SAAU,CACV,kBACF,CAMA,SACE,uBACF,CAMA,SACE,aACF,CAOA,6BAEE,qBAAsB,CACtB,SACF,CAMA,kFAEE,WACF,CAOA,cACE,4BAA6B,CAC7B,mBACF,CAMA,yCACE,uBACF,CAOA,6BACE,yBAA0B,CAC1B,YACF,CASA,QACE,aACF,CAMA,QACE,iBACF,CAiBA,kBACE,YACF,CCvVA,aAcE,kEACE,uBAOF,WACE,iDAMF,gCACE,wBAEF,qCAEE,uBADA,uBACA,CAEF,SACE,wBAtBA,CCpBJ,iBAOE,6BAEA,mBANA,qBAEA,sBACA,0BAFA,oBAHA,4BAOA,6BANA,mBAOA,CAEF,gBACE,aCPF,KCGE,mHAEA,wGAGA,wBAAyB,CACzB,wBAAyB,CACzB,4BAA6B,CAC7B,yBAA0B,CAC1B,2BAA4B,CAG5B,sDAAuD,CACvD,gDAAiD,CACjD,wDAAyD,CAGzD,0CAA2C,CAC3C,gDAAiD,CACjD,gDAAiD,CAKjD,gCAAiC,CACjC,sCAAuC,CAGvC,2CAA4C,CAG5C,uCAAwC,CChCxC,+FAGA,uBAAwB,CAGxB,iCAAkC,CAClC,kCAAmC,CAEnC,+BAAgC,CAChC,sCAAuC,CACvC,sCAAuC,CACvC,qGAIA,mDAAoD,CAEpD,mCAAoC,CACpC,8CAA+C,CAC/C,gDAAiD,CACjD,kCAAmC,CACnC,6DAA8D,CAG9D,6BAA8B,CAC9B,6BAA8B,CAC9B,+BAAgC,CAChC,kCAAmC,CACnC,kCAAmC,CCPjC,ukBCYA,srCAZF,kaCVA,mLAOA,oTAWA,2UAaA,0CACA,gEACA,0CAGA,gEAUA,yCACA,+DAGA,4CACA,CACA,iEAGA,sGACA,uCACA,4DAGA,sCACA,2DAEA,4CACA,kEACA,oGACA,CAEA,0GACA,+CAGA,+MAOA,+EACA,wCAIA,4DACA,sEACA,kEACA,sEACA,gDAGA,+DACA,0CACA,gEACA,gGACA,CAGA,2DACA,qDAGA,0CACA,8CACA,oDACA,oDL7GF,iCAEA,iEAME,oCKyGA,yDAIA,sCACA,kCACA,sDAGA,0CACA,kEACA,oDAEA,sDAGA,oCACA,oEAIA,CAGA,yDAGA,qDACA,oDAGA,6DAIA,iEAGA,2DAEA,2DL9IE,4DAEA,gEAIF,gEKgGA,gFAIA,oNAOA,qDAEA,gFAIA,4DAIA,oEAMA,yEAIA,6DACA,0DAGA,uDAGA,qDAEA,wDLpII,6DAEA,yDACE,2DAMN,uCAIA,yCACE,8CAGF,sDMjDA,6DAKA,oCAIA,4CACA,kBAGF,sBAMA,2BAME,qCAGA,qCAEA,iCAEA,+BAEA,mCAEA,qCAIA,CACA,gCACA,gDAKA,kCAIA,6BAEA,0CAQA,kCAIF,8BAGE,8BACA,uCAGF,sCAKE,kCAEA,sDAGA,iCACE,CACA,2FAGA,gCACE,CACA,+DCzEJ,wCAEA,sBAEF,yDAEE,mCACA,wDAGA,2GAGA,wIACE,gDAMJ,kCAGE,6BACA,0CAGA,gEACA,8BACA,uCAKA,sCAIA,kCACA,sDACA,iCACA,sCAOA,sDAKE,gGAIE,+CAGN,sBAEE,yCAMA,0BAMA,yLAMA,aACA,MAEF,6BACE,2DAIF,wCAIE,kCAGA,SACA,kCAKA,mBAGA,CAJA,eACA,CAHF,gBAEE,CAWA,mBACA,mBACA,mDAGA,YACA,CACA,kBACA,CAEE,kBAKJ,OAPE,kBAQA,CADF,GACE,iCACA,wCAEA,wBACA,aACA,CAFA,WAEA,GACA,oBACA,CAFA,gBAEA,aACE,+CAIF,UAJE,kCAIF,WACA,iBACA,GAGA,uBACE,CAJF,yBAGA,CACE,iDACA,uCAEA,yDACE,cACA,wDAKN,yDAIE,uBAEF,kBACE,uBAEA,kDAIA,0DAGA,CAHA,oBAGA,0GAYA,aAEA,CAHA,YAGA,4HAKF,+CAGE,sBAEF,WAKE,0CAEA,CALA,qCAGA,CAJA,WAOA,SAIA,2CAJA,qCAIA,CACE,wBACA,OACA,YAEJ,gBACE,gBAIA,+CAKF,CAGE,kDAGA,CANF,8BAGE,CAGA,YAEA,CAdF,2BACE,CAHA,UAEF,CAYE,UAEA,CACA,0CACF,iEAOE,iCACA,8BAGA,wCAIA,wBAKE,0CAKF,CARE,6DAGA,CALF,qBAEE,CASA,YACA,yBAGA,CAEE,cAKN,CAPI,sBAOJ,gCAGE,qBAEA,WACA,aACA,sCAEA,mBACA,6BAGA,uEADA,qBACA,6BAIA,yBACA,qCAEE,UAEA,YACA,sBAEF,8BAGA,CAPE,aACA,WAMF,4BACE,sBACA,WAMJ,uBACE,cAYE,mBAXA,qDAKA,qCAGA,CAEA,YACA,CAHA,2BAEA,CACA,oCAEA,4CACA,uBAIA,oCAEJ,CAFI,cAIF,iBACE,CAHJ,kBAGI,yBAEA,oCAIA,qDAMF,mEAEA,CACE,8CAKA,gCAEA,qCAGA,oCAGE,sBACA,CAJF,WAEE,CAFF,eAEE,SAEA,mBACA,qCACE,aACA,CAFF,YADA,qBACA,WAEE,sBACA,kEAEN,2BAEE,iDAKA,uCAGF,CACE,0DAKA,kBACF,CAFE,sBAGA,mBACA,0BAEJ,yBAII,aADA,WACA,CAMF,UAFE,kBAEF,CAJF,gBACE,CAHE,iBAMF,6CC9ZF,yBACE,WACA,iBAEA,aAFA,iBAEA,6BAEA,kCACA,mBAKA,gCAGA,CARA,QAEA,CAGA,UALA,qBAEA,qDAGA,CALA,OAQA,4BACE,cAGF,2BACE,gCAEJ,CAHE,UAGF,8CAGE,CAHF,UAGE,wCAGA,qBACA,CAFA,UAEA,6CAGA,yCAIA,sBAHA,UAGA,kCACE,OACA,CAFF,KAEE,cAQF,0CACE,CAFF,kBACA,CACE,wEACA,CARA,YACA,CAKF,mBAFF,OAII,eACA,CAJF,iCAJE,cAGJ,CANI,oBAEA,CAKF,SAIE,2BADA,UACA,kBAGF,sCACA,CAFF,WACE,WACA,qCACE,gCACA,2EACA,sDAKJ,aACE,mDAII,CAJJ,6CAII,kEACA,iBACE,iDACA,+CACE,aACA,WADA,+BACA,uEANN,YACE,mDAEE,mBADF,0CACE,CADF,qBACE,0DACA,YACE,4DACA,sEANN,YACE,8CACA,kBADA,UACA,2CACE,2EACA,cACE,kEACA,mEANN,yBACE,4DACA,sBACE,+EAEE,iEACA,qEANN,sCACE,CAGE,iBAHF,gBAGE,qBACE,CAJJ,uBACA,gDACE,wDACA,6DAHF,2CACA,CADA,gBACA,eACE,CAGE,sBANN,8BACE,CAII,iBAFF,4DACA,WACE,YADF,uCACE,6EACA,2BANN,8CACE,kDACA,0CACE,8BACA,yFACE,sBACA,sFALJ,mEACA,sBACE,kEACA,6EACE,uCACA,kEALJ,qGAEE,kEACA,6EACE,uCACA,kEALJ,8CACA,uDACE,sEACA,2EACE,sCACA,iEALJ,mGACA,qCACE,oDACA,0DACE,6GACA,gDAGR,yDCrEA,sEACE,CACA,6GACE,gEACF,iGAIF,wFACE,qDAGA,mGAEE,2CAEF,4FACE,gCACF,wGACE,8DAEE,6FAIA,iJAKN,6GACE,gDAKF,yDACA,qCAGA,6BACA,kBACA,qDAKA,oCAEA,+DAGA,2CAGE,oDAIA,oEAEE,qBAGJ,wDAEE,uCAEF,kEAGA,8CAEA,uDAKA,oCAEA,yDAEE,gEAKF,+CC5FA,0EAGE,CACA,qDCLJ,+DAIE,sCAIA,kEACE,yBACA,2FAMA,gBACA,yGCbF,mBAOA,2MAIA,4HAYA,0DACE,8GAYF,8HAQE,mBAEA,6HAOF,YAGA,mIAME,eACA,CAFF,YAEE,4FAMJ,8BAEE,uBAYA,sCAEE,CAJF,oBAEA,CARA,wCAEA,CAHA,8BACA,CAFA,eACA,CAGA,wCAEA,CAEA,mDAIE,kCACE,6BACA,4CAKJ,kDAIA,eACE,aAGF,8BACE,uDACA,sCACA,cAEA,+BACA,CAFA,eAEA,wCAEF,YACE,iBACA,mCACA,0DAGF,qBAEE,CAFF,kBAEE,+BAIA,yCAEE,qBADA,gBACA,yBAKF,eACA,CAFF,YACE,CACA,iBACA,qDAEA,mDCvIJ,2FAOE,iCACA,CAEA,eACA,CAHA,kBAEA,CAFA,wBAGA,8BACA,eACE,CAFF,YAEE,0BACA,8CAGA,oBACE,oCAGA,kBACE,8DAEA,iBAEN,UACE,8BAIJ,+CAEE,qDAEF,kDAIE,YAEF,CAFE,YAEF,CCjCE,mFAJA,QACA,UAIE,CADF,iBACE,mCAGA,iDACE,+BAGF,wBAEA,mBAKA,6CAEF,CAHE,mBACA,CAEF,kCAIE,CARA,kBACA,CAFF,eASE,YACA,mBAGF,CAJE,UAIF,wCCjCA,oBDmCE,wBCpCJ,uCACE,8BACA,4CACA,oBAGA,2CCAA,6CAGE,CAPF,uBAIA,CDGA,gDACE,6BCVJ,CAWM,2CAEF,CAJA,kCAEE,CDJF,aCLF,gBDKE,uBCMA,gCAGA,gDAGE,wBAGJ,0BAEA,iBACE,aACF,CADE,UACF,uBACE,aACF,oBACE,YACF,4BACE,6CAMA,CAYF,6DAZE,mCAGE,iCASJ,4BAGE,4DADA,+BACA,CAFA,qBAEA,yBACE,aAEF,wBAHA,SAGA,iHACE,2DAKF,CANA,yCACE,CADF,oCAMA,uSAIA,sGACE,oDChEJ,WAEF,yBACE,QACA,eAEA,gBAEE,uCAGA,CALF,iCAKE,uCAGA,0BACA,CACA,oBACA,iCClBJ,gBACE,KAGF,qBACE,YAGF,CAHE,cAGF,gCAEE,mBACA,iEAEA,oCACA,wCAEA,sBACA,WAEA,CAFA,YAEA,8EAEA,mCAFA,iBAEA,6BAIA,wEAKA,sDAIE,CARF,mDAIA,CAIE,cAEF,8CAIA,oBAFE,iBAEF,8CAGE,eAEF,CAFE,YAEF,OAEE,kBAGJ,CAJI,eACA,CAFF,mBAKF,yCCjDE,oBACA,CAFA,iBAEA,uCAKE,iBACA,qCAGA,mBCZJ,CDWI,gBCXJ,6BAEE,eACA,sBAGA,eAEA,sBACA,oDACA,iGAMA,gBAFE,YAEF,8FAME,iJClBF,YACA,gNAUE,6BAEF,oTAcI,kBACF,gHAIA,qBACE,eACF,qDACE,kBACF,6DACE,4BCxCJ,oBAEF,qCAEI,+CAGF,uBACE,uDAGJ,oBAkBE,mDAhBA,+CAaA,CAbA,oBAaA,0FAEE,CAFF,gGAbA,+BAaA,0BAGA,mQAIA,oNAEE,iBAGJ,CAHI,gBADA,gBAIJ,8CAYI,CAZJ,wCAYI,sVACE,iCAGA,uEAHA,QAGA,qXAKJ,iDAGF,CARM,+CACE,iDAIN,CALI,gBAQN,mHACE,gBAGF,2DACE,0EAOA,0EAKA,6EC/EA,iDACA,gCACA,oDAGA,qBACA,oDCFA,cACA,eAEA,yBAGF,sBAEE,iBACA,sNAWA,iBACE,kBACA,wRAgBA,kBAEA,iOAgBA,uCACE,uEAEA,kBAEF,qUAuBE,iDAIJ,CACA,geCxFF,4BAEE,CAQA,6JACA,iDAIA,sEAGA,mDAOF,iDAGE,4DAIA,8CACA,qDAEE,eAFF,cAEE,oBAEF,uBAFE,kCAGA,eACA,iBACA,mBAIA,mDACA,CAHA,uCAEA,CAJA,0CACA,CAIA,gBAJA,gBACA,oBADA,gBAIA,wBAEJ,gBAGE,6BACA,YAHA,iBAGA,gCACA,iEAEA,6CACA,sDACA,0BADA,wBACA,0BACA,oIAIA,mBAFA,YAEA,qBACA,0CAIE,uBAEF,CAHA,yBACE,CAEF,iDACE,mFAKJ,oCACE,CANE,aAKJ,CACE,qEAIA,YAFA,WAEA,CAHA,aACA,CAEA,gBACE,4BACA,sBADA,aACA,gCAMF,oCACA,yDACA,2CAEA,qBAGE,kBAEA,CACA,mCAIF,CARE,YACA,CAOF,iCAEE,CAPA,oBACA,CAQA,oBACE,uDAEJ,sDAGA,CAHA,cAGA,0BACE,oDAIA,oCACA,4BACA,sBAGA,cAEA,oFAGA,sBAEA,yDACE,CAIA,iBAJA,wBAIA,6CAJA,6CAOA,4BAGJ,CAHI,cAGJ,yCAGA,kBACE,CAIA,iDAEA,CATA,YAEF,CACE,4CAGA,kBAIA,wEAEA,wDAIF,kCAOE,iDACA,CARF,WAIE,sCAGA,CANA,2CACA,CAMA,oEARF,iBACE,CACA,qCAMA,iBAuBE,uBAlBF,YAKA,2DALA,uDAKA,CALA,sBAiBA,4CACE,CALA,gRAIF,YACE,UAEN,uBACE,YACA,mCAOE,+CAGA,8BAGF,+CAGA,4BCjNA,SDiNA,qFCjNA,gDAGA,sCACA,qCACA,sDAIF,CAIE,kDAGA,CAPF,0CAOE,kBAEA,kDAEA,CAHA,eACA,CAFA,YACA,CADA,SAIA,mHAIE,CAGA,6CAFA,oCAeE,CAbF,yBACE,qBAEJ,CAGE,oBACA,CAEA,YAFA,2CACF,CACE,uBAEA,mFAEE,CALJ,oBACE,CAEA,UAEE,gCAGF,sDAEA,yCC7CJ,oCAGA,CD6CE,yXAQE,sCCrDJ,wCAGA,oCACE","sources":["webpack:///./node_modules/normalize.css/normalize.css","webpack:///./src/furo/assets/styles/base/_print.sass","webpack:///./src/furo/assets/styles/base/_screen-readers.sass","webpack:///./src/furo/assets/styles/base/_theme.sass","webpack:///./src/furo/assets/styles/variables/_fonts.scss","webpack:///./src/furo/assets/styles/variables/_spacing.scss","webpack:///./src/furo/assets/styles/variables/_icons.scss","webpack:///./src/furo/assets/styles/variables/_admonitions.scss","webpack:///./src/furo/assets/styles/variables/_colors.scss","webpack:///./src/furo/assets/styles/base/_typography.sass","webpack:///./src/furo/assets/styles/_scaffold.sass","webpack:///./src/furo/assets/styles/content/_admonitions.sass","webpack:///./src/furo/assets/styles/content/_api.sass","webpack:///./src/furo/assets/styles/content/_blocks.sass","webpack:///./src/furo/assets/styles/content/_captions.sass","webpack:///./src/furo/assets/styles/content/_code.sass","webpack:///./src/furo/assets/styles/content/_footnotes.sass","webpack:///./src/furo/assets/styles/content/_images.sass","webpack:///./src/furo/assets/styles/content/_indexes.sass","webpack:///./src/furo/assets/styles/content/_lists.sass","webpack:///./src/furo/assets/styles/content/_math.sass","webpack:///./src/furo/assets/styles/content/_misc.sass","webpack:///./src/furo/assets/styles/content/_rubrics.sass","webpack:///./src/furo/assets/styles/content/_sidebar.sass","webpack:///./src/furo/assets/styles/content/_tables.sass","webpack:///./src/furo/assets/styles/content/_target.sass","webpack:///./src/furo/assets/styles/content/_gui-labels.sass","webpack:///./src/furo/assets/styles/components/_footer.sass","webpack:///./src/furo/assets/styles/components/_sidebar.sass","webpack:///./src/furo/assets/styles/components/_table_of_contents.sass","webpack:///./src/furo/assets/styles/_shame.sass"],"sourcesContent":["/*! normalize.css v8.0.1 | MIT License | github.com/necolas/normalize.css */\n\n/* Document\n ========================================================================== */\n\n/**\n * 1. Correct the line height in all browsers.\n * 2. Prevent adjustments of font size after orientation changes in iOS.\n */\n\nhtml {\n line-height: 1.15; /* 1 */\n -webkit-text-size-adjust: 100%; /* 2 */\n}\n\n/* Sections\n ========================================================================== */\n\n/**\n * Remove the margin in all browsers.\n */\n\nbody {\n margin: 0;\n}\n\n/**\n * Render the `main` element consistently in IE.\n */\n\nmain {\n display: block;\n}\n\n/**\n * Correct the font size and margin on `h1` elements within `section` and\n * `article` contexts in Chrome, Firefox, and Safari.\n */\n\nh1 {\n font-size: 2em;\n margin: 0.67em 0;\n}\n\n/* Grouping content\n ========================================================================== */\n\n/**\n * 1. Add the correct box sizing in Firefox.\n * 2. Show the overflow in Edge and IE.\n */\n\nhr {\n box-sizing: content-box; /* 1 */\n height: 0; /* 1 */\n overflow: visible; /* 2 */\n}\n\n/**\n * 1. Correct the inheritance and scaling of font size in all browsers.\n * 2. Correct the odd `em` font sizing in all browsers.\n */\n\npre {\n font-family: monospace, monospace; /* 1 */\n font-size: 1em; /* 2 */\n}\n\n/* Text-level semantics\n ========================================================================== */\n\n/**\n * Remove the gray background on active links in IE 10.\n */\n\na {\n background-color: transparent;\n}\n\n/**\n * 1. Remove the bottom border in Chrome 57-\n * 2. Add the correct text decoration in Chrome, Edge, IE, Opera, and Safari.\n */\n\nabbr[title] {\n border-bottom: none; /* 1 */\n text-decoration: underline; /* 2 */\n text-decoration: underline dotted; /* 2 */\n}\n\n/**\n * Add the correct font weight in Chrome, Edge, and Safari.\n */\n\nb,\nstrong {\n font-weight: bolder;\n}\n\n/**\n * 1. Correct the inheritance and scaling of font size in all browsers.\n * 2. Correct the odd `em` font sizing in all browsers.\n */\n\ncode,\nkbd,\nsamp {\n font-family: monospace, monospace; /* 1 */\n font-size: 1em; /* 2 */\n}\n\n/**\n * Add the correct font size in all browsers.\n */\n\nsmall {\n font-size: 80%;\n}\n\n/**\n * Prevent `sub` and `sup` elements from affecting the line height in\n * all browsers.\n */\n\nsub,\nsup {\n font-size: 75%;\n line-height: 0;\n position: relative;\n vertical-align: baseline;\n}\n\nsub {\n bottom: -0.25em;\n}\n\nsup {\n top: -0.5em;\n}\n\n/* Embedded content\n ========================================================================== */\n\n/**\n * Remove the border on images inside links in IE 10.\n */\n\nimg {\n border-style: none;\n}\n\n/* Forms\n ========================================================================== */\n\n/**\n * 1. Change the font styles in all browsers.\n * 2. Remove the margin in Firefox and Safari.\n */\n\nbutton,\ninput,\noptgroup,\nselect,\ntextarea {\n font-family: inherit; /* 1 */\n font-size: 100%; /* 1 */\n line-height: 1.15; /* 1 */\n margin: 0; /* 2 */\n}\n\n/**\n * Show the overflow in IE.\n * 1. Show the overflow in Edge.\n */\n\nbutton,\ninput { /* 1 */\n overflow: visible;\n}\n\n/**\n * Remove the inheritance of text transform in Edge, Firefox, and IE.\n * 1. Remove the inheritance of text transform in Firefox.\n */\n\nbutton,\nselect { /* 1 */\n text-transform: none;\n}\n\n/**\n * Correct the inability to style clickable types in iOS and Safari.\n */\n\nbutton,\n[type=\"button\"],\n[type=\"reset\"],\n[type=\"submit\"] {\n -webkit-appearance: button;\n}\n\n/**\n * Remove the inner border and padding in Firefox.\n */\n\nbutton::-moz-focus-inner,\n[type=\"button\"]::-moz-focus-inner,\n[type=\"reset\"]::-moz-focus-inner,\n[type=\"submit\"]::-moz-focus-inner {\n border-style: none;\n padding: 0;\n}\n\n/**\n * Restore the focus styles unset by the previous rule.\n */\n\nbutton:-moz-focusring,\n[type=\"button\"]:-moz-focusring,\n[type=\"reset\"]:-moz-focusring,\n[type=\"submit\"]:-moz-focusring {\n outline: 1px dotted ButtonText;\n}\n\n/**\n * Correct the padding in Firefox.\n */\n\nfieldset {\n padding: 0.35em 0.75em 0.625em;\n}\n\n/**\n * 1. Correct the text wrapping in Edge and IE.\n * 2. Correct the color inheritance from `fieldset` elements in IE.\n * 3. Remove the padding so developers are not caught out when they zero out\n * `fieldset` elements in all browsers.\n */\n\nlegend {\n box-sizing: border-box; /* 1 */\n color: inherit; /* 2 */\n display: table; /* 1 */\n max-width: 100%; /* 1 */\n padding: 0; /* 3 */\n white-space: normal; /* 1 */\n}\n\n/**\n * Add the correct vertical alignment in Chrome, Firefox, and Opera.\n */\n\nprogress {\n vertical-align: baseline;\n}\n\n/**\n * Remove the default vertical scrollbar in IE 10+.\n */\n\ntextarea {\n overflow: auto;\n}\n\n/**\n * 1. Add the correct box sizing in IE 10.\n * 2. Remove the padding in IE 10.\n */\n\n[type=\"checkbox\"],\n[type=\"radio\"] {\n box-sizing: border-box; /* 1 */\n padding: 0; /* 2 */\n}\n\n/**\n * Correct the cursor style of increment and decrement buttons in Chrome.\n */\n\n[type=\"number\"]::-webkit-inner-spin-button,\n[type=\"number\"]::-webkit-outer-spin-button {\n height: auto;\n}\n\n/**\n * 1. Correct the odd appearance in Chrome and Safari.\n * 2. Correct the outline style in Safari.\n */\n\n[type=\"search\"] {\n -webkit-appearance: textfield; /* 1 */\n outline-offset: -2px; /* 2 */\n}\n\n/**\n * Remove the inner padding in Chrome and Safari on macOS.\n */\n\n[type=\"search\"]::-webkit-search-decoration {\n -webkit-appearance: none;\n}\n\n/**\n * 1. Correct the inability to style clickable types in iOS and Safari.\n * 2. Change font properties to `inherit` in Safari.\n */\n\n::-webkit-file-upload-button {\n -webkit-appearance: button; /* 1 */\n font: inherit; /* 2 */\n}\n\n/* Interactive\n ========================================================================== */\n\n/*\n * Add the correct display in Edge, IE 10+, and Firefox.\n */\n\ndetails {\n display: block;\n}\n\n/*\n * Add the correct display in all browsers.\n */\n\nsummary {\n display: list-item;\n}\n\n/* Misc\n ========================================================================== */\n\n/**\n * Add the correct display in IE 10+.\n */\n\ntemplate {\n display: none;\n}\n\n/**\n * Add the correct display in IE 10.\n */\n\n[hidden] {\n display: none;\n}\n","// This file contains styles for managing print media.\n\n////////////////////////////////////////////////////////////////////////////////\n// Hide elements not relevant to print media.\n////////////////////////////////////////////////////////////////////////////////\n@media print\n // Hide icon container.\n .content-icon-container\n display: none !important\n\n // Hide showing header links if hovering over when printing.\n .headerlink\n display: none !important\n\n // Hide mobile header.\n .mobile-header\n display: none !important\n\n // Hide navigation links.\n .related-pages\n display: none !important\n\n////////////////////////////////////////////////////////////////////////////////\n// Tweaks related to decolorization.\n////////////////////////////////////////////////////////////////////////////////\n@media print\n // Apply a border around code which no longer have a color background.\n .highlight\n border: 0.1pt solid var(--color-foreground-border)\n\n////////////////////////////////////////////////////////////////////////////////\n// Avoid page break in some relevant cases.\n////////////////////////////////////////////////////////////////////////////////\n@media print\n ul, ol, dl, a, table, pre, blockquote\n page-break-inside: avoid\n\n h1, h2, h3, h4, h5, h6, img, figure, caption\n page-break-inside: avoid\n page-break-after: avoid\n\n ul, ol, dl\n page-break-before: avoid\n",".visually-hidden\n position: absolute !important\n width: 1px !important\n height: 1px !important\n padding: 0 !important\n margin: -1px !important\n overflow: hidden !important\n clip: rect(0,0,0,0) !important\n white-space: nowrap !important\n border: 0 !important\n\n:-moz-focusring\n outline: auto\n","// This file serves as the \"skeleton\" of the theming logic.\n//\n// This contains the bulk of the logic for handling dark mode, color scheme\n// toggling and the handling of color-scheme-specific hiding of elements.\n\nbody\n @include fonts\n @include spacing\n @include icons\n @include admonitions\n @include default-admonition(#651fff, \"abstract\")\n @include default-topic(#14B8A6, \"pencil\")\n\n @include colors\n\n.only-light\n display: block !important\nhtml body .only-dark\n display: none !important\n\n// Ignore dark-mode hints if print media.\n@media not print\n // Enable dark-mode, if requested.\n body[data-theme=\"dark\"]\n @include colors-dark\n\n html & .only-light\n display: none !important\n .only-dark\n display: block !important\n\n // Enable dark mode, unless explicitly told to avoid.\n @media (prefers-color-scheme: dark)\n body:not([data-theme=\"light\"])\n @include colors-dark\n\n html & .only-light\n display: none !important\n .only-dark\n display: block !important\n\n//\n// Theme toggle presentation\n//\nbody[data-theme=\"auto\"]\n .theme-toggle svg.theme-icon-when-auto\n display: block\n\nbody[data-theme=\"dark\"]\n .theme-toggle svg.theme-icon-when-dark\n display: block\n\nbody[data-theme=\"light\"]\n .theme-toggle svg.theme-icon-when-light\n display: block\n","// Fonts used by this theme.\n//\n// There are basically two things here -- using the system font stack and\n// defining sizes for various elements in %ages. We could have also used `em`\n// but %age is easier to reason about for me.\n\n@mixin fonts {\n // These are adapted from https://systemfontstack.com/\n --font-stack: -apple-system, BlinkMacSystemFont, Segoe UI, Helvetica, Arial,\n sans-serif, Apple Color Emoji, Segoe UI Emoji;\n --font-stack--monospace: \"SFMono-Regular\", Menlo, Consolas, Monaco,\n Liberation Mono, Lucida Console, monospace;\n\n --font-size--normal: 100%;\n --font-size--small: 87.5%;\n --font-size--small--2: 81.25%;\n --font-size--small--3: 75%;\n --font-size--small--4: 62.5%;\n\n // Sidebar\n --sidebar-caption-font-size: var(--font-size--small--2);\n --sidebar-item-font-size: var(--font-size--small);\n --sidebar-search-input-font-size: var(--font-size--small);\n\n // Table of Contents\n --toc-font-size: var(--font-size--small--3);\n --toc-font-size--mobile: var(--font-size--normal);\n --toc-title-font-size: var(--font-size--small--4);\n\n // Admonitions\n //\n // These aren't defined in terms of %ages, since nesting these is permitted.\n --admonition-font-size: 0.8125rem;\n --admonition-title-font-size: 0.8125rem;\n\n // Code\n --code-font-size: var(--font-size--small--2);\n\n // API\n --api-font-size: var(--font-size--small);\n}\n","// Spacing for various elements on the page\n//\n// If the user wants to tweak things in a certain way, they are permitted to.\n// They also have to deal with the consequences though!\n\n@mixin spacing {\n // Header!\n --header-height: calc(\n var(--sidebar-item-line-height) + 4 * #{var(--sidebar-item-spacing-vertical)}\n );\n --header-padding: 0.5rem;\n\n // Sidebar\n --sidebar-tree-space-above: 1.5rem;\n --sidebar-caption-space-above: 1rem;\n\n --sidebar-item-line-height: 1rem;\n --sidebar-item-spacing-vertical: 0.5rem;\n --sidebar-item-spacing-horizontal: 1rem;\n --sidebar-item-height: calc(\n var(--sidebar-item-line-height) + 2 *#{var(--sidebar-item-spacing-vertical)}\n );\n\n --sidebar-expander-width: var(--sidebar-item-height); // be square\n\n --sidebar-search-space-above: 0.5rem;\n --sidebar-search-input-spacing-vertical: 0.5rem;\n --sidebar-search-input-spacing-horizontal: 0.5rem;\n --sidebar-search-input-height: 1rem;\n --sidebar-search-icon-size: var(--sidebar-search-input-height);\n\n // Table of Contents\n --toc-title-padding: 0.25rem 0;\n --toc-spacing-vertical: 1.5rem;\n --toc-spacing-horizontal: 1.5rem;\n --toc-item-spacing-vertical: 0.4rem;\n --toc-item-spacing-horizontal: 1rem;\n}\n","// Expose theme icons as CSS variables.\n\n$icons: (\n // Adapted from tabler-icons\n // url: https://tablericons.com/\n \"search\":\n url('data:image/svg+xml;charset=utf-8,'),\n // Factored out from mkdocs-material on 24-Aug-2020.\n // url: https://squidfunk.github.io/mkdocs-material/reference/admonitions/\n \"pencil\":\n url('data:image/svg+xml;charset=utf-8,'),\n \"abstract\":\n url('data:image/svg+xml;charset=utf-8,'),\n \"info\":\n url('data:image/svg+xml;charset=utf-8,'),\n \"flame\":\n url('data:image/svg+xml;charset=utf-8,'),\n \"question\":\n url('data:image/svg+xml;charset=utf-8,'),\n \"warning\":\n url('data:image/svg+xml;charset=utf-8,'),\n \"failure\":\n url('data:image/svg+xml;charset=utf-8,'),\n \"spark\":\n url('data:image/svg+xml;charset=utf-8,')\n);\n\n@mixin icons {\n @each $name, $glyph in $icons {\n --icon-#{$name}: #{$glyph};\n }\n}\n","// Admonitions\n\n// Structure of these is:\n// admonition-class: color \"icon-name\";\n//\n// The colors are translated into CSS variables below. The icons are\n// used directly in the main declarations to set the `mask-image` in\n// the title.\n\n// prettier-ignore\n$admonitions: (\n // Each of these has an reST directives for it.\n \"caution\": #ff9100 \"spark\",\n \"warning\": #ff9100 \"warning\",\n \"danger\": #ff5252 \"spark\",\n \"attention\": #ff5252 \"warning\",\n \"error\": #ff5252 \"failure\",\n \"hint\": #00c852 \"question\",\n \"tip\": #00c852 \"info\",\n \"important\": #00bfa5 \"flame\",\n \"note\": #00b0ff \"pencil\",\n \"seealso\": #448aff \"info\",\n \"admonition-todo\": #808080 \"pencil\"\n);\n\n@mixin default-admonition($color, $icon-name) {\n --color-admonition-title: #{$color};\n --color-admonition-title-background: #{rgba($color, 0.2)};\n\n --icon-admonition-default: var(--icon-#{$icon-name});\n}\n\n@mixin default-topic($color, $icon-name) {\n --color-topic-title: #{$color};\n --color-topic-title-background: #{rgba($color, 0.2)};\n\n --icon-topic-default: var(--icon-#{$icon-name});\n}\n\n@mixin admonitions {\n @each $name, $values in $admonitions {\n --color-admonition-title--#{$name}: #{nth($values, 1)};\n --color-admonition-title-background--#{$name}: #{rgba(\n nth($values, 1),\n 0.2\n )};\n }\n}\n","// Colors used throughout this theme.\n//\n// The aim is to give the user more control. Thus, instead of hard-coding colors\n// in various parts of the stylesheet, the approach taken is to define all\n// colors as CSS variables and reusing them in all the places.\n//\n// `colors-dark` depends on `colors` being included at a lower specificity.\n\n@mixin colors {\n --color-problematic: #b30000;\n\n // Base Colors\n --color-foreground-primary: black; // for main text and headings\n --color-foreground-secondary: #5a5c63; // for secondary text\n --color-foreground-muted: #646776; // for muted text\n --color-foreground-border: #878787; // for content borders\n\n --color-background-primary: white; // for content\n --color-background-secondary: #f8f9fb; // for navigation + ToC\n --color-background-hover: #efeff4ff; // for navigation-item hover\n --color-background-hover--transparent: #efeff400;\n --color-background-border: #eeebee; // for UI borders\n --color-background-item: #ccc; // for \"background\" items (eg: copybutton)\n\n // Announcements\n --color-announcement-background: #000000dd;\n --color-announcement-text: #eeebee;\n\n // Brand colors\n --color-brand-primary: #2962ff;\n --color-brand-content: #2a5adf;\n\n // API documentation\n --color-api-background: var(--color-background-hover--transparent);\n --color-api-background-hover: var(--color-background-hover);\n --color-api-overall: var(--color-foreground-secondary);\n --color-api-name: var(--color-problematic);\n --color-api-pre-name: var(--color-problematic);\n --color-api-paren: var(--color-foreground-secondary);\n --color-api-keyword: var(--color-foreground-primary);\n --color-highlight-on-target: #ffffcc;\n\n // Inline code background\n --color-inline-code-background: var(--color-background-secondary);\n\n // Highlighted text (search)\n --color-highlighted-background: #ddeeff;\n --color-highlighted-text: var(--color-foreground-primary);\n\n // GUI Labels\n --color-guilabel-background: #ddeeff80;\n --color-guilabel-border: #bedaf580;\n --color-guilabel-text: var(--color-foreground-primary);\n\n // Admonitions!\n --color-admonition-background: transparent;\n\n //////////////////////////////////////////////////////////////////////////////\n // Everything below this should be one of:\n // - var(...)\n // - *-gradient(...)\n // - special literal values (eg: transparent, none)\n //////////////////////////////////////////////////////////////////////////////\n\n // Tables\n --color-table-header-background: var(--color-background-secondary);\n --color-table-border: var(--color-background-border);\n\n // Cards\n --color-card-border: var(--color-background-secondary);\n --color-card-background: transparent;\n --color-card-marginals-background: var(--color-background-secondary);\n\n // Header\n --color-header-background: var(--color-background-primary);\n --color-header-border: var(--color-background-border);\n --color-header-text: var(--color-foreground-primary);\n\n // Sidebar (left)\n --color-sidebar-background: var(--color-background-secondary);\n --color-sidebar-background-border: var(--color-background-border);\n\n --color-sidebar-brand-text: var(--color-foreground-primary);\n --color-sidebar-caption-text: var(--color-foreground-muted);\n --color-sidebar-link-text: var(--color-foreground-secondary);\n --color-sidebar-link-text--top-level: var(--color-brand-primary);\n\n --color-sidebar-item-background: var(--color-sidebar-background);\n --color-sidebar-item-background--current: var(\n --color-sidebar-item-background\n );\n --color-sidebar-item-background--hover: linear-gradient(\n 90deg,\n var(--color-background-hover--transparent) 0%,\n var(--color-background-hover) var(--sidebar-item-spacing-horizontal),\n var(--color-background-hover) 100%\n );\n\n --color-sidebar-item-expander-background: transparent;\n --color-sidebar-item-expander-background--hover: var(\n --color-background-hover\n );\n\n --color-sidebar-search-text: var(--color-foreground-primary);\n --color-sidebar-search-background: var(--color-background-secondary);\n --color-sidebar-search-background--focus: var(--color-background-primary);\n --color-sidebar-search-border: var(--color-background-border);\n --color-sidebar-search-icon: var(--color-foreground-muted);\n\n // Table of Contents (right)\n --color-toc-background: var(--color-background-primary);\n --color-toc-title-text: var(--color-foreground-muted);\n --color-toc-item-text: var(--color-foreground-secondary);\n --color-toc-item-text--hover: var(--color-foreground-primary);\n --color-toc-item-text--active: var(--color-brand-primary);\n\n // Actual page contents\n --color-content-foreground: var(--color-foreground-primary);\n --color-content-background: transparent;\n\n // Links\n --color-link: var(--color-brand-content);\n --color-link--hover: var(--color-brand-content);\n --color-link-underline: var(--color-background-border);\n --color-link-underline--hover: var(--color-foreground-border);\n}\n\n@mixin colors-dark {\n --color-problematic: #ee5151;\n\n // Base Colors\n --color-foreground-primary: #ffffffcc; // for main text and headings\n --color-foreground-secondary: #9ca0a5; // for secondary text\n --color-foreground-muted: #81868d; // for muted text\n --color-foreground-border: #666666; // for content borders\n\n --color-background-primary: #131416; // for content\n --color-background-secondary: #1a1c1e; // for navigation + ToC\n --color-background-hover: #1e2124ff; // for navigation-item hover\n --color-background-hover--transparent: #1e212400;\n --color-background-border: #303335; // for UI borders\n --color-background-item: #444; // for \"background\" items (eg: copybutton)\n\n // Announcements\n --color-announcement-background: #000000dd;\n --color-announcement-text: #eeebee;\n\n // Brand colors\n --color-brand-primary: #2b8cee;\n --color-brand-content: #368ce2;\n\n // Highlighted text (search)\n --color-highlighted-background: #083563;\n\n // GUI Labels\n --color-guilabel-background: #08356380;\n --color-guilabel-border: #13395f80;\n\n // API documentation\n --color-api-keyword: var(--color-foreground-secondary);\n --color-highlight-on-target: #333300;\n\n // Admonitions\n --color-admonition-background: #18181a;\n\n // Cards\n --color-card-border: var(--color-background-secondary);\n --color-card-background: #18181a;\n --color-card-marginals-background: var(--color-background-hover);\n}\n","// This file contains the styling for making the content throughout the page,\n// including fonts, paragraphs, headings and spacing among these elements.\n\nbody\n font-family: var(--font-stack)\npre,\ncode,\nkbd,\nsamp\n font-family: var(--font-stack--monospace)\n\n// Make fonts look slightly nicer.\nbody\n -webkit-font-smoothing: antialiased\n -moz-osx-font-smoothing: grayscale\n\n// Line height from Bootstrap 4.1\narticle\n line-height: 1.5\n\n//\n// Headings\n//\nh1,\nh2,\nh3,\nh4,\nh5,\nh6\n line-height: 1.25\n font-weight: bold\n\n border-radius: 0.5rem\n margin-top: 0.5rem\n margin-bottom: 0.5rem\n margin-left: -0.5rem\n margin-right: -0.5rem\n padding-left: 0.5rem\n padding-right: 0.5rem\n\n + p\n margin-top: 0\n\nh1\n font-size: 2.5em\n margin-top: 1.75rem\n margin-bottom: 1rem\nh2\n font-size: 2em\n margin-top: 1.75rem\nh3\n font-size: 1.5em\nh4\n font-size: 1.25em\nh5\n font-size: 1.125em\nh6\n font-size: 1em\n\nsmall\n opacity: 75%\n font-size: 80%\n\n// Paragraph\np\n margin-top: 0.5rem\n margin-bottom: 0.75rem\n\n// Horizontal rules\nhr.docutils\n height: 1px\n padding: 0\n margin: 2rem 0\n background-color: var(--color-background-border)\n border: 0\n\n.centered\n text-align: center\n\n// Links\na\n text-decoration: underline\n\n color: var(--color-link)\n text-decoration-color: var(--color-link-underline)\n\n &:hover\n color: var(--color-link--hover)\n text-decoration-color: var(--color-link-underline--hover)\n &.muted-link\n color: inherit\n &:hover\n color: var(--color-link)\n text-decoration-color: var(--color-link-underline--hover)\n","// This file contains the styles for the overall layouting of the documentation\n// skeleton, including the responsive changes as well as sidebar toggles.\n//\n// This is implemented as a mobile-last design, which isn't ideal, but it is\n// reasonably good-enough and I got pretty tired by the time I'd finished this\n// to move the rules around to fix this. Shouldn't take more than 3-4 hours,\n// if you know what you're doing tho.\n\n// HACK: Not all browsers account for the scrollbar width in media queries.\n// This results in horizontal scrollbars in the breakpoint where we go\n// from displaying everything to hiding the ToC. We accomodate for this by\n// adding a bit of padding to the TOC drawer, disabling the horizontal\n// scrollbar and allowing the scrollbars to cover the padding.\n// https://www.456bereastreet.com/archive/201301/media_query_width_and_vertical_scrollbars/\n\n// HACK: Always having the scrollbar visible, prevents certain browsers from\n// causing the content to stutter horizontally between taller-than-viewport and\n// not-taller-than-viewport pages.\n\nhtml\n overflow-x: hidden\n overflow-y: scroll\n scroll-behavior: smooth\n\n.sidebar-scroll, .toc-scroll, article[role=main] *\n // Override Firefox scrollbar style\n scrollbar-width: thin\n scrollbar-color: var(--color-foreground-border) transparent\n\n // Override Chrome scrollbar styles\n &::-webkit-scrollbar\n width: 0.25rem\n height: 0.25rem\n &::-webkit-scrollbar-thumb\n background-color: var(--color-foreground-border)\n border-radius: 0.125rem\n\n//\n// Overalls\n//\nhtml,\nbody\n height: 100%\n color: var(--color-foreground-primary)\n background: var(--color-background-primary)\n\narticle\n color: var(--color-content-foreground)\n background: var(--color-content-background)\n overflow-wrap: break-word\n\n.page\n display: flex\n // fill the viewport for pages with little content.\n min-height: 100%\n\n.mobile-header\n width: 100%\n height: var(--header-height)\n background-color: var(--color-header-background)\n color: var(--color-header-text)\n border-bottom: 1px solid var(--color-header-border)\n\n // Looks like sub-script/super-script have this, and we need this to\n // be \"on top\" of those.\n z-index: 10\n\n // We don't show the header on large screens.\n display: none\n\n // Add shadow when scrolled\n &.scrolled\n border-bottom: none\n box-shadow: 0 0 0.2rem rgba(0, 0, 0, 0.1), 0 0.2rem 0.4rem rgba(0, 0, 0, 0.2)\n\n .header-center\n a\n color: var(--color-header-text)\n text-decoration: none\n\n.main\n display: flex\n flex: 1\n\n// Sidebar (left) also covers the entire left portion of screen.\n.sidebar-drawer\n box-sizing: border-box\n\n border-right: 1px solid var(--color-sidebar-background-border)\n background: var(--color-sidebar-background)\n\n display: flex\n justify-content: flex-end\n // These next two lines took me two days to figure out.\n width: calc((100% - #{$full-width}) / 2 + #{$sidebar-width})\n min-width: $sidebar-width\n\n// Scroll-along sidebars\n.sidebar-container,\n.toc-drawer\n box-sizing: border-box\n width: $sidebar-width\n\n.toc-drawer\n background: var(--color-toc-background)\n // See HACK described on top of this document\n padding-right: 1rem\n\n.sidebar-sticky,\n.toc-sticky\n position: sticky\n top: 0\n height: min(100%, 100vh)\n height: 100vh\n\n display: flex\n flex-direction: column\n\n.sidebar-scroll,\n.toc-scroll\n flex-grow: 1\n flex-shrink: 1\n\n overflow: auto\n scroll-behavior: smooth\n\n// Central items.\n.content\n padding: 0 $content-padding\n width: $content-width\n\n display: flex\n flex-direction: column\n justify-content: space-between\n\n.icon\n display: inline-block\n height: 1rem\n width: 1rem\n svg\n width: 100%\n height: 100%\n\n//\n// Accommodate announcement banner\n//\n.announcement\n background-color: var(--color-announcement-background)\n color: var(--color-announcement-text)\n\n height: var(--header-height)\n display: flex\n align-items: center\n overflow-x: auto\n & + .page\n min-height: calc(100% - var(--header-height))\n\n.announcement-content\n box-sizing: border-box\n padding: 0.5rem\n min-width: 100%\n white-space: nowrap\n text-align: center\n\n a\n color: var(--color-announcement-text)\n text-decoration-color: var(--color-announcement-text)\n\n &:hover\n color: var(--color-announcement-text)\n text-decoration-color: var(--color-link--hover)\n\n////////////////////////////////////////////////////////////////////////////////\n// Toggles for theme\n////////////////////////////////////////////////////////////////////////////////\n.no-js .theme-toggle-container // don't show theme toggle if there's no JS\n display: none\n\n.theme-toggle-container\n vertical-align: middle\n\n.theme-toggle\n cursor: pointer\n border: none\n padding: 0\n background: transparent\n\n.theme-toggle svg\n vertical-align: middle\n height: 1rem\n width: 1rem\n color: var(--color-foreground-primary)\n display: none\n\n.theme-toggle-header\n float: left\n padding: 1rem 0.5rem\n\n////////////////////////////////////////////////////////////////////////////////\n// Toggles for elements\n////////////////////////////////////////////////////////////////////////////////\n.toc-overlay-icon, .nav-overlay-icon\n display: none\n cursor: pointer\n\n .icon\n color: var(--color-foreground-secondary)\n height: 1rem\n width: 1rem\n\n.toc-header-icon, .nav-overlay-icon\n // for when we set display: flex\n justify-content: center\n align-items: center\n\n.toc-content-icon\n height: 1.5rem\n width: 1.5rem\n\n.content-icon-container\n float: right\n display: flex\n margin-top: 1.5rem\n margin-left: 1rem\n margin-bottom: 1rem\n gap: 0.5rem\n\n .edit-this-page svg\n color: inherit\n height: 1rem\n width: 1rem\n\n.sidebar-toggle\n position: absolute\n display: none\n// \n.sidebar-toggle[name=\"__toc\"]\n left: 20px\n.sidebar-toggle:checked\n left: 40px\n// \n\n.overlay\n position: fixed\n top: 0\n width: 0\n height: 0\n\n transition: width 0ms, height 0ms, opacity 250ms ease-out\n\n opacity: 0\n background-color: rgba(0, 0, 0, 0.54)\n.sidebar-overlay\n z-index: 20\n.toc-overlay\n z-index: 40\n\n// Keep things on top and smooth.\n.sidebar-drawer\n z-index: 30\n transition: left 250ms ease-in-out\n.toc-drawer\n z-index: 50\n transition: right 250ms ease-in-out\n\n// Show the Sidebar\n#__navigation:checked\n & ~ .sidebar-overlay\n width: 100%\n height: 100%\n opacity: 1\n & ~ .page\n .sidebar-drawer\n top: 0\n left: 0\n // Show the toc sidebar\n#__toc:checked\n & ~ .toc-overlay\n width: 100%\n height: 100%\n opacity: 1\n & ~ .page\n .toc-drawer\n top: 0\n right: 0\n\n////////////////////////////////////////////////////////////////////////////////\n// Back to top\n////////////////////////////////////////////////////////////////////////////////\n.back-to-top\n text-decoration: none\n\n display: none\n position: fixed\n left: 0\n top: 1rem\n padding: 0.5rem\n padding-right: 0.75rem\n border-radius: 1rem\n font-size: 0.8125rem\n\n background: var(--color-background-primary)\n box-shadow: 0 0.2rem 0.5rem rgba(0, 0, 0, 0.05), #6b728080 0px 0px 1px 0px\n\n z-index: 10\n\n margin-left: 50%\n transform: translateX(-50%)\n svg\n height: 1rem\n width: 1rem\n fill: currentColor\n display: inline-block\n\n span\n margin-left: 0.25rem\n\n .show-back-to-top &\n display: flex\n align-items: center\n\n////////////////////////////////////////////////////////////////////////////////\n// Responsive layouting\n////////////////////////////////////////////////////////////////////////////////\n// Make things a bit bigger on bigger screens.\n@media (min-width: $full-width + $sidebar-width)\n html\n font-size: 110%\n\n@media (max-width: $full-width)\n // Collapse \"toc\" into the icon.\n .toc-content-icon\n display: flex\n .toc-drawer\n position: fixed\n height: 100vh\n top: 0\n right: -$sidebar-width\n border-left: 1px solid var(--color-background-muted)\n .toc-tree\n border-left: none\n font-size: var(--toc-font-size--mobile)\n\n // Accomodate for a changed content width.\n .sidebar-drawer\n width: calc((100% - #{$full-width - $sidebar-width}) / 2 + #{$sidebar-width})\n\n@media (max-width: $full-width - $sidebar-width)\n // Collapse \"navigation\".\n .nav-overlay-icon\n display: flex\n .sidebar-drawer\n position: fixed\n height: 100vh\n width: $sidebar-width\n\n top: 0\n left: -$sidebar-width\n\n // Swap which icon is visible.\n .toc-header-icon\n display: flex\n .toc-content-icon, .theme-toggle-content\n display: none\n .theme-toggle-header\n display: block\n\n // Show the header.\n .mobile-header\n position: sticky\n top: 0\n display: flex\n justify-content: space-between\n align-items: center\n\n .header-left,\n .header-right\n display: flex\n height: var(--header-height)\n padding: 0 var(--header-padding)\n label\n height: 100%\n width: 100%\n user-select: none\n\n .nav-overlay-icon .icon,\n .theme-toggle svg\n height: 1.25rem\n width: 1.25rem\n\n // Add a scroll margin for the content\n :target\n scroll-margin-top: var(--header-height)\n\n // Show back-to-top below the header\n .back-to-top\n top: calc(var(--header-height) + 0.5rem)\n\n // Center the page, and accommodate for the header.\n .page\n flex-direction: column\n justify-content: center\n .content\n margin-left: auto\n margin-right: auto\n\n@media (max-width: $content-width + 2* $content-padding)\n // Content should respect window limits.\n .content\n width: 100%\n overflow-x: auto\n\n@media (max-width: $content-width)\n .content\n padding: 0 $content-padding--small\n // Don't float sidebars to the right.\n article aside.sidebar\n float: none\n width: 100%\n margin: 1rem 0\n","//\n// The design here is strongly inspired by mkdocs-material.\n.admonition, .topic\n margin: 1rem auto\n padding: 0 0.5rem 0.5rem 0.5rem\n\n background: var(--color-admonition-background)\n\n border-radius: 0.2rem\n box-shadow: 0 0.2rem 0.5rem rgba(0, 0, 0, 0.05), 0 0 0.0625rem rgba(0, 0, 0, 0.1)\n\n font-size: var(--admonition-font-size)\n\n overflow: hidden\n page-break-inside: avoid\n\n // First element should have no margin, since the title has it.\n > :nth-child(2)\n margin-top: 0\n\n // Last item should have no margin, since we'll control that w/ padding\n > :last-child\n margin-bottom: 0\n\n.admonition p.admonition-title,\np.topic-title\n position: relative\n margin: 0 -0.5rem 0.5rem\n padding-left: 2rem\n padding-right: .5rem\n padding-top: .4rem\n padding-bottom: .4rem\n\n font-weight: 500\n font-size: var(--admonition-title-font-size)\n line-height: 1.3\n\n // Our fancy icon\n &::before\n content: \"\"\n position: absolute\n left: 0.5rem\n width: 1rem\n height: 1rem\n\n// Default styles\np.admonition-title\n background-color: var(--color-admonition-title-background)\n &::before\n background-color: var(--color-admonition-title)\n mask-image: var(--icon-admonition-default)\n mask-repeat: no-repeat\n\np.topic-title\n background-color: var(--color-topic-title-background)\n &::before\n background-color: var(--color-topic-title)\n mask-image: var(--icon-topic-default)\n mask-repeat: no-repeat\n\n//\n// Variants\n//\n.admonition\n border-left: 0.2rem solid var(--color-admonition-title)\n\n @each $type, $value in $admonitions\n &.#{$type}\n border-left-color: var(--color-admonition-title--#{$type})\n > .admonition-title\n background-color: var(--color-admonition-title-background--#{$type})\n &::before\n background-color: var(--color-admonition-title--#{$type})\n mask-image: var(--icon-#{nth($value, 2)})\n\n.admonition-todo > .admonition-title\n text-transform: uppercase\n","// This file stylizes the API documentation (stuff generated by autodoc). It's\n// deeply nested due to how autodoc structures the HTML without enough classes\n// to select the relevant items.\n\n// API docs!\ndl[class]:not(.option-list):not(.field-list):not(.footnote):not(.glossary):not(.simple)\n // Tweak the spacing of all the things!\n dd\n margin-left: 2rem\n > :first-child\n margin-top: 0.125rem\n > :last-child\n margin-bottom: 0.75rem\n\n // This is used for the arguments\n .field-list\n margin-bottom: 0.75rem\n\n // \"Headings\" (like \"Parameters\" and \"Return\")\n > dt\n text-transform: uppercase\n font-size: var(--font-size--small)\n\n dd:empty\n margin-bottom: 0.5rem\n dd > ul\n margin-left: -1.2rem\n > li\n > p:nth-child(2)\n margin-top: 0\n // When the last-empty-paragraph follows a paragraph, it doesn't need\n // to augument the existing spacing.\n > p + p:last-child:empty\n margin-top: 0\n margin-bottom: 0\n\n // Colorize the elements\n > dt\n color: var(--color-api-overall)\n\n.sig:not(.sig-inline)\n font-weight: bold\n\n font-size: var(--api-font-size)\n font-family: var(--font-stack--monospace)\n\n margin-left: -0.25rem\n margin-right: -0.25rem\n padding-top: 0.25rem\n padding-bottom: 0.25rem\n padding-right: 0.5rem\n\n // These are intentionally em, to properly match the font size.\n padding-left: 3em\n text-indent: -2.5em\n\n border-radius: 0.25rem\n\n background: var(--color-api-background)\n transition: background 100ms ease-out\n\n &:hover\n background: var(--color-api-background-hover)\n\n // adjust the size of the [source] link on the right.\n a.reference\n .viewcode-link\n font-weight: normal\n width: 3.5rem\n\nem.property\n font-style: normal\n &:first-child\n color: var(--color-api-keyword)\n.sig-name\n color: var(--color-api-name)\n.sig-prename\n font-weight: normal\n color: var(--color-api-pre-name)\n.sig-paren\n color: var(--color-api-paren)\n.sig-param\n font-style: normal\n\n.versionmodified\n font-style: italic\ndiv.versionadded, div.versionchanged, div.deprecated\n p\n margin-top: 0.125rem\n margin-bottom: 0.125rem\n\n// Align the [docs] and [source] to the right.\n.viewcode-link, .viewcode-back\n float: right\n text-align: right\n",".line-block\n margin-top: 0.5rem\n margin-bottom: 0.75rem\n .line-block\n margin-top: 0rem\n margin-bottom: 0rem\n padding-left: 1rem\n","// Captions\narticle p.caption,\ntable > caption,\n.code-block-caption\n font-size: var(--font-size--small)\n text-align: center\n\n// Caption above a TOCTree\n.toctree-wrapper.compound\n .caption, :not(.caption) > .caption-text\n font-size: var(--font-size--small)\n text-transform: uppercase\n\n text-align: initial\n margin-bottom: 0\n\n > ul\n margin-top: 0\n margin-bottom: 0\n","// Inline code\ncode.literal, .sig-inline\n background: var(--color-inline-code-background)\n border-radius: 0.2em\n // Make the font smaller, and use padding to recover.\n font-size: var(--font-size--small--2)\n padding: 0.1em 0.2em\n\n pre.literal-block &\n font-size: inherit\n padding: 0\n\n p &\n border: 1px solid var(--color-background-border)\n\n.sig-inline\n font-family: var(--font-stack--monospace)\n\n// Code and Literal Blocks\n$code-spacing-vertical: 0.625rem\n$code-spacing-horizontal: 0.875rem\n\n// Wraps every literal block + line numbers.\ndiv[class*=\" highlight-\"],\ndiv[class^=\"highlight-\"]\n margin: 1em 0\n display: flex\n\n .table-wrapper\n margin: 0\n padding: 0\n\npre\n margin: 0\n padding: 0\n overflow: auto\n\n // Needed to have more specificity than pygments' \"pre\" selector. :(\n article[role=\"main\"] .highlight &\n line-height: 1.5\n\n &.literal-block,\n .highlight &\n font-size: var(--code-font-size)\n padding: $code-spacing-vertical $code-spacing-horizontal\n\n // Make it look like all the other blocks.\n &.literal-block\n margin-top: 1rem\n margin-bottom: 1rem\n\n border-radius: 0.2rem\n background-color: var(--color-code-background)\n color: var(--color-code-foreground)\n\n// All code is always contained in this.\n.highlight\n width: 100%\n border-radius: 0.2rem\n\n // Make line numbers and prompts un-selectable.\n .gp, span.linenos\n user-select: none\n pointer-events: none\n\n // Expand the line-highlighting.\n .hll\n display: block\n margin-left: -$code-spacing-horizontal\n margin-right: -$code-spacing-horizontal\n padding-left: $code-spacing-horizontal\n padding-right: $code-spacing-horizontal\n\n/* Make code block captions be nicely integrated */\n.code-block-caption\n display: flex\n padding: $code-spacing-vertical $code-spacing-horizontal\n\n border-radius: 0.25rem\n border-bottom-left-radius: 0\n border-bottom-right-radius: 0\n font-weight: 300\n border-bottom: 1px solid\n\n background-color: var(--color-code-background)\n color: var(--color-code-foreground)\n border-color: var(--color-background-border)\n\n + div[class]\n margin-top: 0\n pre\n border-top-left-radius: 0\n border-top-right-radius: 0\n\n// When `html_codeblock_linenos_style` is table.\n.highlighttable\n width: 100%\n display: block\n tbody\n display: block\n\n tr\n display: flex\n\n // Line numbers\n td.linenos\n background-color: var(--color-code-background)\n color: var(--color-code-foreground)\n padding: $code-spacing-vertical $code-spacing-horizontal\n padding-right: 0\n border-top-left-radius: 0.2rem\n border-bottom-left-radius: 0.2rem\n\n .linenodiv\n padding-right: $code-spacing-horizontal\n font-size: var(--code-font-size)\n box-shadow: -0.0625rem 0 var(--color-foreground-border) inset\n\n // Actual code\n td.code\n padding: 0\n display: block\n flex: 1\n overflow: hidden\n\n .highlight\n border-top-left-radius: 0\n border-bottom-left-radius: 0\n\n// When `html_codeblock_linenos_style` is inline.\n.highlight\n span.linenos\n display: inline-block\n padding-left: 0\n padding-right: $code-spacing-horizontal\n margin-right: $code-spacing-horizontal\n box-shadow: -0.0625rem 0 var(--color-foreground-border) inset\n","// Inline Footnote Reference\n.footnote-reference\n font-size: var(--font-size--small--4)\n vertical-align: super\n\n// Definition list, listing the content of each note.\n// docutils <= 0.17\ndl.footnote.brackets\n font-size: var(--font-size--small)\n color: var(--color-foreground-secondary)\n\n display: grid\n grid-template-columns: max-content auto\n dt\n margin: 0\n > .fn-backref\n margin-left: 0.25rem\n\n &:after\n content: \":\"\n\n .brackets\n &:before\n content: \"[\"\n &:after\n content: \"]\"\n\n dd\n margin: 0\n padding: 0 1rem\n\n// docutils >= 0.18\naside.footnote\n font-size: var(--font-size--small)\n color: var(--color-foreground-secondary)\n\naside.footnote > span,\ndiv.citation > span\n float: left\n font-weight: 500\n padding-right: 0.25rem\n\naside.footnote > p,\ndiv.citation > p\n margin-left: 2rem\n","//\n// Figures\n//\nimg\n box-sizing: border-box\n max-width: 100%\n height: auto\n\narticle\n figure, .figure\n border-radius: 0.2rem\n\n margin: 0\n :last-child\n margin-bottom: 0\n\n .align-left\n float: left\n clear: left\n margin: 0 1rem 1rem\n\n .align-right\n float: right\n clear: right\n margin: 0 1rem 1rem\n\n .align-default,\n .align-center\n display: block\n text-align: center\n margin-left: auto\n margin-right: auto\n\n // WELL, table needs to be stylised like a table.\n table.align-default\n display: table\n text-align: initial\n",".genindex-jumpbox, .domainindex-jumpbox\n border-top: 1px solid var(--color-background-border)\n border-bottom: 1px solid var(--color-background-border)\n padding: 0.25rem\n\n.genindex-section, .domainindex-section\n h2\n margin-top: 0.75rem\n margin-bottom: 0.5rem\n ul\n margin-top: 0\n margin-bottom: 0\n","ul,\nol\n padding-left: 1.2rem\n\n // Space lists out like paragraphs\n margin-top: 1rem\n margin-bottom: 1rem\n // reduce margins within li.\n li\n > p:first-child\n margin-top: 0.25rem\n margin-bottom: 0.25rem\n\n > p:last-child\n margin-top: 0.25rem\n\n > ul,\n > ol\n margin-top: 0.5rem\n margin-bottom: 0.5rem\n\nol\n &.arabic\n list-style: decimal\n &.loweralpha\n list-style: lower-alpha\n &.upperalpha\n list-style: upper-alpha\n &.lowerroman\n list-style: lower-roman\n &.upperroman\n list-style: upper-roman\n\n// Don't space lists out when they're \"simple\" or in a `.. toctree::`\n.simple,\n.toctree-wrapper\n li\n > ul,\n > ol\n margin-top: 0\n margin-bottom: 0\n\n// Definition Lists\n.field-list,\n.option-list,\ndl:not([class]),\ndl.simple,\ndl.footnote,\ndl.glossary\n dt\n font-weight: 500\n margin-top: 0.25rem\n + dt\n margin-top: 0\n\n .classifier::before\n content: \":\"\n margin-left: 0.2rem\n margin-right: 0.2rem\n\n dd\n > p:first-child,\n ul\n margin-top: 0.125rem\n\n ul\n margin-bottom: 0.125rem\n",".math-wrapper\n width: 100%\n overflow-x: auto\n\ndiv.math\n position: relative\n text-align: center\n\n .headerlink,\n &:focus .headerlink\n display: none\n\n &:hover .headerlink\n display: inline-block\n\n span.eqno\n position: absolute\n right: 0.5rem\n top: 50%\n transform: translate(0, -50%)\n z-index: 1\n","// Abbreviations\nabbr[title]\n cursor: help\n\n// \"Problematic\" content, as identified by Sphinx\n.problematic\n color: var(--color-problematic)\n\n// Keyboard / Mouse \"instructions\"\nkbd:not(.compound)\n margin: 0 0.2rem\n padding: 0 0.2rem\n border-radius: 0.2rem\n border: 1px solid var(--color-foreground-border)\n color: var(--color-foreground-primary)\n vertical-align: text-bottom\n\n font-size: var(--font-size--small--3)\n display: inline-block\n\n box-shadow: 0 0.0625rem 0 rgba(0, 0, 0, 0.2), inset 0 0 0 0.125rem var(--color-background-primary)\n\n background-color: var(--color-background-secondary)\n\n// Blockquote\nblockquote\n border-left: 4px solid var(--color-background-border)\n background: var(--color-background-secondary)\n\n margin-left: 0\n margin-right: 0\n padding: 0.5rem 1rem\n\n .attribution\n font-weight: 600\n text-align: right\n\n &.pull-quote,\n &.highlights\n font-size: 1.25em\n\n &.epigraph,\n &.pull-quote\n border-left-width: 0\n border-radius: 0.5rem\n\n &.highlights\n border-left-width: 0\n background: transparent\n\n// Center align embedded-in-text images\np .reference img\n vertical-align: middle\n","p.rubric\n line-height: 1.25\n font-weight: bold\n font-size: 1.125em\n\n // For Numpy-style documentation that's got rubrics within it.\n // https://github.com/pradyunsg/furo/discussions/505\n dd &\n line-height: inherit\n font-weight: inherit\n\n font-size: var(--font-size--small)\n text-transform: uppercase\n","article .sidebar\n float: right\n clear: right\n width: 30%\n\n margin-left: 1rem\n margin-right: 0\n\n border-radius: 0.2rem\n background-color: var(--color-background-secondary)\n border: var(--color-background-border) 1px solid\n\n > *\n padding-left: 1rem\n padding-right: 1rem\n\n > ul, > ol // lists need additional padding, because bullets.\n padding-left: 2.2rem\n\n .sidebar-title\n margin: 0\n padding: 0.5rem 1rem\n border-bottom: var(--color-background-border) 1px solid\n\n font-weight: 500\n\n// TODO: subtitle\n// TODO: dedicated variables?\n",".table-wrapper\n width: 100%\n overflow-x: auto\n margin-top: 1rem\n margin-bottom: 0.5rem\n padding: 0.2rem 0.2rem 0.75rem\n\ntable.docutils\n border-radius: 0.2rem\n border-spacing: 0\n border-collapse: collapse\n\n box-shadow: 0 0.2rem 0.5rem rgba(0, 0, 0, 0.05), 0 0 0.0625rem rgba(0, 0, 0, 0.1)\n\n th\n background: var(--color-table-header-background)\n\n td,\n th\n // Space things out properly\n padding: 0 0.25rem\n\n // Get the borders looking just-right.\n border-left: 1px solid var(--color-table-border)\n border-right: 1px solid var(--color-table-border)\n border-bottom: 1px solid var(--color-table-border)\n\n p\n margin: 0.25rem\n\n &:first-child\n border-left: none\n &:last-child\n border-right: none\n\n // MyST-parser tables set these classes for control of column alignment\n &.text-left\n text-align: left\n &.text-right\n text-align: right\n &.text-center\n text-align: center\n",":target\n scroll-margin-top: 0.5rem\n\n@media (max-width: $full-width - $sidebar-width)\n :target\n scroll-margin-top: calc(0.5rem + var(--header-height))\n\n // When a heading is selected\n section > span:target\n scroll-margin-top: calc(0.8rem + var(--header-height))\n\n// Permalinks\n.headerlink\n font-weight: 100\n user-select: none\n\nh1,\nh2,\nh3,\nh4,\nh5,\nh6,\ndl dt,\np.caption,\nfigcaption p,\ntable > caption,\n.code-block-caption\n > .headerlink\n margin-left: 0.5rem\n visibility: hidden\n &:hover > .headerlink\n visibility: visible\n\n // Don't change to link-like, if someone adds the contents directive.\n > .toc-backref\n color: inherit\n text-decoration-line: none\n\n// Figure and table captions are special.\nfigure:hover > figcaption > p > .headerlink,\ntable:hover > caption > .headerlink\n visibility: visible\n\n:target >, // Regular section[id] style anchors\nspan:target ~ // Non-regular span[id] style \"extra\" anchors\n h1,\n h2,\n h3,\n h4,\n h5,\n h6\n &:nth-of-type(1)\n background-color: var(--color-highlight-on-target)\n // .headerlink\n // visibility: visible\n code.literal\n background-color: transparent\n\ntable:target > caption,\nfigure:target\n background-color: var(--color-highlight-on-target)\n\n// Inline page contents\n.this-will-duplicate-information-and-it-is-still-useful-here li :target\n background-color: var(--color-highlight-on-target)\n\n// Code block permalinks\n.literal-block-wrapper:target .code-block-caption\n background-color: var(--color-highlight-on-target)\n\n// When a definition list item is selected\n//\n// There isn't really an alternative to !important here, due to the\n// high-specificity of API documentation's selector.\ndt:target\n background-color: var(--color-highlight-on-target) !important\n\n// When a footnote reference is selected\n.footnote > dt:target + dd,\n.footnote-reference:target\n background-color: var(--color-highlight-on-target)\n",".guilabel\n background-color: var(--color-guilabel-background)\n border: 1px solid var(--color-guilabel-border)\n color: var(--color-guilabel-text)\n\n padding: 0 0.3em\n border-radius: 0.5em\n font-size: 0.9em\n","// This file contains the styles used for stylizing the footer that's shown\n// below the content.\n\nfooter\n font-size: var(--font-size--small)\n display: flex\n flex-direction: column\n\n margin-top: 2rem\n\n// Bottom of page information\n.bottom-of-page\n display: flex\n align-items: center\n justify-content: space-between\n\n margin-top: 1rem\n padding-top: 1rem\n padding-bottom: 1rem\n\n color: var(--color-foreground-secondary)\n border-top: 1px solid var(--color-background-border)\n\n line-height: 1.5\n\n @media (max-width: $content-width)\n text-align: center\n flex-direction: column-reverse\n gap: 0.25rem\n\n .left-details\n font-size: var(--font-size--small)\n\n .right-details\n display: flex\n flex-direction: column\n gap: 0.25rem\n text-align: right\n\n .icons\n display: flex\n justify-content: flex-end\n gap: 0.25rem\n font-size: 1rem\n\n a\n text-decoration: none\n\n svg,\n img\n font-size: 1.125rem\n height: 1em\n width: 1em\n\n// Next/Prev page information\n.related-pages\n a\n display: flex\n align-items: center\n\n text-decoration: none\n &:hover .page-info .title\n text-decoration: underline\n color: var(--color-link)\n text-decoration-color: var(--color-link-underline)\n\n svg.furo-related-icon,\n svg.furo-related-icon > use\n flex-shrink: 0\n\n color: var(--color-foreground-border)\n\n width: 0.75rem\n height: 0.75rem\n margin: 0 0.5rem\n\n &.next-page\n max-width: 50%\n\n float: right\n clear: right\n text-align: right\n\n &.prev-page\n max-width: 50%\n\n float: left\n clear: left\n\n svg\n transform: rotate(180deg)\n\n.page-info\n display: flex\n flex-direction: column\n overflow-wrap: anywhere\n\n .next-page &\n align-items: flex-end\n\n .context\n display: flex\n align-items: center\n\n padding-bottom: 0.1rem\n\n color: var(--color-foreground-muted)\n font-size: var(--font-size--small)\n text-decoration: none\n","// This file contains the styles for the contents of the left sidebar, which\n// contains the navigation tree, logo, search etc.\n\n////////////////////////////////////////////////////////////////////////////////\n// Brand on top of the scrollable tree.\n////////////////////////////////////////////////////////////////////////////////\n.sidebar-brand\n display: flex\n flex-direction: column\n flex-shrink: 0\n\n padding: var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal)\n text-decoration: none\n\n.sidebar-brand-text\n color: var(--color-sidebar-brand-text)\n overflow-wrap: break-word\n margin: var(--sidebar-item-spacing-vertical) 0\n font-size: 1.5rem\n\n.sidebar-logo-container\n margin: var(--sidebar-item-spacing-vertical) 0\n\n.sidebar-logo\n margin: 0 auto\n display: block\n max-width: 100%\n\n////////////////////////////////////////////////////////////////////////////////\n// Search\n////////////////////////////////////////////////////////////////////////////////\n.sidebar-search-container\n display: flex\n align-items: center\n margin-top: var(--sidebar-search-space-above)\n\n position: relative\n\n background: var(--color-sidebar-search-background)\n &:hover,\n &:focus-within\n background: var(--color-sidebar-search-background--focus)\n\n &::before\n content: \"\"\n position: absolute\n left: var(--sidebar-item-spacing-horizontal)\n width: var(--sidebar-search-icon-size)\n height: var(--sidebar-search-icon-size)\n\n background-color: var(--color-sidebar-search-icon)\n mask-image: var(--icon-search)\n\n.sidebar-search\n box-sizing: border-box\n\n border: none\n border-top: 1px solid var(--color-sidebar-search-border)\n border-bottom: 1px solid var(--color-sidebar-search-border)\n\n padding-top: var(--sidebar-search-input-spacing-vertical)\n padding-bottom: var(--sidebar-search-input-spacing-vertical)\n padding-right: var(--sidebar-search-input-spacing-horizontal)\n padding-left: calc(var(--sidebar-item-spacing-horizontal) + var(--sidebar-search-input-spacing-horizontal) + var(--sidebar-search-icon-size))\n\n width: 100%\n\n color: var(--color-sidebar-search-foreground)\n background: transparent\n z-index: 10\n\n &:focus\n outline: none\n\n &::placeholder\n font-size: var(--sidebar-search-input-font-size)\n\n//\n// Hide Search Matches link\n//\n#searchbox .highlight-link\n padding: var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal) 0\n margin: 0\n text-align: center\n\n a\n color: var(--color-sidebar-search-icon)\n font-size: var(--font-size--small--2)\n\n////////////////////////////////////////////////////////////////////////////////\n// Structure/Skeleton of the navigation tree (left)\n////////////////////////////////////////////////////////////////////////////////\n.sidebar-tree\n font-size: var(--sidebar-item-font-size)\n margin-top: var(--sidebar-tree-space-above)\n margin-bottom: var(--sidebar-item-spacing-vertical)\n\n ul\n padding: 0\n margin-top: 0\n margin-bottom: 0\n\n display: flex\n flex-direction: column\n\n list-style: none\n\n li\n position: relative\n margin: 0\n\n > ul\n margin-left: var(--sidebar-item-spacing-horizontal)\n\n .icon\n color: var(--color-sidebar-link-text)\n\n .reference\n box-sizing: border-box\n color: var(--color-sidebar-link-text)\n\n // Fill the parent.\n display: inline-block\n line-height: var(--sidebar-item-line-height)\n text-decoration: none\n\n // Don't allow long words to cause wrapping.\n overflow-wrap: anywhere\n\n height: 100%\n width: 100%\n\n padding: var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal)\n\n &:hover\n background: var(--color-sidebar-item-background--hover)\n\n // Add a nice little \"external-link\" arrow here.\n &.external::after\n content: url('data:image/svg+xml,')\n margin: 0 0.25rem\n vertical-align: middle\n color: var(--color-sidebar-link-text)\n\n // Make the current page reference bold.\n .current-page > .reference\n font-weight: bold\n\n label\n position: absolute\n top: 0\n right: 0\n height: var(--sidebar-item-height)\n width: var(--sidebar-expander-width)\n\n cursor: pointer\n user-select: none\n\n display: flex\n justify-content: center\n align-items: center\n\n .caption, :not(.caption) > .caption-text\n font-size: var(--sidebar-caption-font-size)\n color: var(--color-sidebar-caption-text)\n\n font-weight: bold\n text-transform: uppercase\n\n margin: var(--sidebar-caption-space-above) 0 0 0\n padding: var(--sidebar-item-spacing-vertical) var(--sidebar-item-spacing-horizontal)\n\n // If it has children, add a bit more padding to wrap the content to avoid\n // overlapping with the

    I6G=UBv+cRP9qAN?!O2NAnSX@I&=g1Is3qGa4B zE3aLCl$YF$rC2AU-(ekQa*7>O)5f!&!3z>DXN4o(@ZlTg(8AB_C@Ks0YxE&>j3T06 zf~QaO5iiy&0MZ2weJ09${JY)LbaKX#uqSDAXFqMI-}BBpl|A`owYug_l=!AD3B;XsA$D3$tK2Dj`Y!r5UJ@pqw4V!}tKx`K z^gg=>XG6X-`LV;0)7Ju3a&r_Z`@=|%kGm(6XwXMi+%9IO;GErHO zhm?uw9pd-+(Zh6qbt!FcZKoG6UWzK>B}l{-?ZLLDIRMvh zzs)Zo(_jO~zlWv{<9@=I>WH9+F8fvP3^#F+r^1BO{4r$O)uio(ikI@GAKn)RsKU#9 z7yV$L!Et;jZV-GZT@$`d7-+w341bAC?}OWTX2sWk{*@~hqGCd9HY7+{p4T1?9F0TD9pVJmS(tdY6k@rg84ka=^5uF8*0MSc|Cfezjgs_?Rp0Uouh z@D|Q8%TdV^DUGn%mIF3r4!;Tf0(I1P ze7xZ5+NuWRbAIsgFmv3>n<6)EFVG6d!@^1r6dHQK@Rpz729X^F0}3yWAc2NhB5X|Z ztOODMEpKM%LC^6Ld?cE;hj=TG!3GmK?>HKbH~P97@I#9nF;Sr$oIDQ*xSU?e$Djte z08h>&t7TC9k$zDs{q8W0`!FEncLkJJDee+)kEEW+DKC_U==j6rp~<8aJh(`6hHsHp zz`TfEV_HA-mFLDQuP>Fy42B|a=_S~9UIt;xbA@F*;h~B=;Y68pEXp-+EsE`^CR+?j zCugS3S0NNe!po2I&>5tW7>@kodkx+_sQSai;EchgOm=^fu26Pyesk1G5B@ZXfFF}V z2BJP%1V72aWS%;}fRUJ;Ho2+aqz9hVacIZ~CbUd8sC#5S_>y)7H-A22dwv@A&H!mK zb79iwF(HdOj&hEjXJjz>O<2-`Vvz~8Tx6o+hd@Cc{*G|Qt6(O^Ii7S$gX$@f5J!}e zg9vCJ@C*xWI6T4>ePz!sS!=)IBb%M!qHH5%rf?&S{vrAs`QvVc32rqMd+@% zWCF%a#@dd_Zac& zz$aS-O(|;V!P~tA(xJo*q4ZefzmD}WDHZS9#fnlcQ!fIy)O?-G1 z{{9tv@$)?(+F=dQ_w#B(;aS=9RYQd53cs4JAB3&%_73;Ay-FPY_yW!ND>Gl7ANm*I z@n&u}JWe6U9O5Mf6jfI!tTaD4LxI(`B8weVL8E?CCdXy@3=r{guV%lPN0Hx*udU<| zJ$}#-uE-fzcH0-hpb0uJC<5>=^pNDs?H-_q9(>hy^zjJZ_x2AG!z!I z(_`t;gH`VWLlJ-i?WogMO0T`(%6FxZ=~82Sc4keFkE977eKw{!ExR5jB@<~XV?WJR zG{)xJX=F9KPQbH}{#J9>*1?_^ppnH21f`vwPA{K-<6TyBb8*BSN1WY}KSwySpw4bJ zc62Zo@|;2O^X;-rjcHMO9ULB|gVv$z+sx!xnwMG9(yX-sqE%gZ}nv}cFGr=Nb7KKtx5@1|qSOl|WVLuJLVhvU~ddW>&(Ew8So znduoTBwxRJoemEVBY3SUcXMS zU%&EEiX82AaM02m{;icd_wL_M-~Yk)(~5Yp+k;&njPu^Sd71w7$KR!|**W#{dD@Ws z)$?aozP*0+ENyRZq_%i77i1-a;}1`cTk?DEx#W`Oog5AM`0*o`!Ijzle?{`s)`;$2aL45txJ#+nFuw79&Qo_z9I`sCA}rj`32r@Lb_>Gb^CM{IUgw@%M!-<&vt0#x%^ z$xoX@Nz1Ws(>^|uw!~bUwj6DhHtRaAeC9>w@d>_-HtBCbv$ld_!QYU|w6x_=XmMmH zyS{j_les5;ssQu@stYL1INFq5O|x_JX<>0OEiWxvnM7OXlL)k3+ggyCq}u{>8O3E zEjj&4W28TYf?IY@b!m0Z)ZXqWpJvjW>LSPOu{({v+DF}fq|)$c+CMx_JNs>w)4A&>?Tg)(OvSgi`Ig?6+VL5^sNx#V zN@jM0&8E5ed6zv3d%n9D-v`t)NP(dx9h3|G2K^9ycK*>hQpc;;Zb0+&f&VHGKKCf>nNsx70WqYu%Homv*w9+R~rt~j> zzxOU2d7{UP`*g~V`Zlh5#@b@6?eTn8yH@{8*>hwiYauAJ=>yM{R?3LFqOA2d9+wy9 z%-c$3@kRL+Ylq^-&_GEdoqkRz?Vc{d%CiGMXJhTDK-3r8n&tppzr7z<%&=$w z;>W*@yaGQJ6Aov=w;;5NG)WN?j>S@~u=dDetM{0j`i0Zn`}{JZD}`wWibLve%P zL+P6EZNfnNZDaULWO^Um#xoRO|M`E{gdPZCeHBZ=G2&J84?enO0t^p;je-_Srr}OU zY8#lSq!mIItRb8(#X(~%_-qX?{fNgt7R4B-GT5`C%^2T<4iD`5nJ#=m!#F4c7n8ff zyFush0b%0Kyqg?MTU+eoTaMcRZFXb>rI9BqMik%rUcyE`)GonU%!@vw~#lAKU}D6>!4DY4&%m39 z25I$?8u_R?a@9HJCl<2E5dV01$F}TC#qD#qHTdxHdJ5-!aI(1}6&c_Z{pA4DzYr`> zSbKr&$0S`cuv4U#R7rM|&4Ed~+b|Dl=#?I~`J9J5(Oqg(NWy#zfSiHvkOm73o_Ls3 zr->sJm$9qQ3QkQ&b0=fAUINyK^gVY z=cqIAl8<*6Djtq2WY-uUFhAvpgi{T0g`=Lt&bJsq0v?>vZqgiI7#t3zGs)69(uC!lL75c@;1^NblErG0el4vYz>88rpO87e9=Eb$FBf5z!(W&@fuj1;mRosCK(TX zIB-W;;Vq|pGa}sh;}##cUCKH0bojcwOf97Ccm_Kh4ugjm?!?zrrVU=}jVV`1+p1G&}{Cn_yXv+)V{l3Flw%iu46U9SE0G6&Wd8 zPJbr;&W}2j+$D!^fJM?x-jQ~vD*u&}4u)sW)tm=5v(?p#weZE?Q0&kKR~-H~lUwXI36t~Baq!E} z<3SK%_!s^Hc<3sAnIQX%5`S#)&sVs)q8`G}=rRU^fuY!Y!}fqsy|Rc0<6(z^AD3Om z1s>vfq0(J-ZvcWDV0{YJ3?p^y2LTVSA0o!M}D_ z7kyN=_ws7s^>?j<#O~g!)X4W<6+JF+l~1_j2T4^UlrP5R5CN1#onOXhFPv0K@R%O= zseHN2%QO&|_8LLC9A|Nu2FQqlYg}1E+rzu~Au}Ul8UA77MSS^^+tE2l!Gi?PnBc9I zLhJ%!Hyh({s;L)H^>f^=Gj$zm_Hj9>rlg+4sTlJ0b3y*<80jm05`xB?9)pX9u_|L` zFFW#*r6MgaZ~0q2qUD=YGcz+Dm!D`J$PNe=q`l*6bVB3sD<6Bv`1_-eo}`Bl9;MaQ z)%5V;qx9hMBOlXu#|xOmfjn1fc4i_ydAOFA7U!&-VT_Cdj5zsbE{pt=d@opYKGLjI zTTw8=`2G4aO^)96HDON+j>^2eICGx!-5|avH9g5SZsivWFMpFsvQBAk%{4YQ;XGsx#Bq(}Jv**Y7O=Q$ zzdUa?XiUp4lS|EM`JJAfrXT+B$LU8u`B_?6TuqZxvzn8Pr*^07#axblL?PfE9TKeD z?f6?+te1K>gvtr!$F$~K;}g>gcbwMOH`ALp>)v%|r5p2P1t@DCSC<-t%IP#pV0LeeB(0!<@u1 zGUnZ4rzfqnzqjk76JI=knw~!WGChC(b$a#cn{=!+%t_vlo;nn}bHN=e zsrZK9Zra{tciEe?wf-t?y!j@*Bs|~WlY2+_r(galJ^kwQw7tEa+O31Mr!a@gn~uuy z__(8Sfa?#nne?e0olGcO)Gv54v5B%j`zoV6LmSNBf{GImV6ejV-J0 zuPo1{rG+`~P#U2uBnCTStN=h^q4F)e5ow3)q(fXp~vhrP;Zew6L_0R#umNBG3{FulYG2?>8Yj@0wJ-;wZc2g?aB%xxcoY9_U(< zo1HnQrx#Z09=4C&?&yCAV|nDyi_IuMP*h=y;#E{AK6uCWk^B-Cxn)@)B~qa2|^C?5T?veEA$ieCsWaeT9aq8_&C-q;HR%g=fOWCoZf2 zSN-sMp83ZM#e|449sJ>^=Yztdl;M*VyqLf#OYF+yn8{P6o1I%IJ=@*3m0~-)2Wew- zH%+L{K7Mr1F9!H~{_J#Af5&$b)#W8t`c5z2=3_rma;a~({8!!uh77C=vF^yr^VBmE z#S0+uEK=X4d=`=NkTp*F$2elv-_PSQsy^S(N7iD5S3=AKT&&Ru=Lwm-WZ*7i1!!PT z-ILXJ9wC^tEneE^Xh)QLaRoohz%zSj$w$gfKNNf9A>XXysK>p1b_wq~?|aA5Az!(S zK^D71uKJ1xz3sH2Y%jQ`SpX-L#y7mo!~C+JOp;$n`uX*nK#e0mLssX4(cIwOpySGR z0DE<1cO^iEpdTEjK(Y6m{orufUcfl$`#gfj4eADd(A5ut8_X-9#2+-@5(t;A?}Cc| zUl7HIz#!SHqYlGM0^~}sYT^cniwZ{~uz~k5Mb4lUEj5X7YK2tQD|tG+2{6Myv&eBo zroh|Zs5QRkcFhs+)mu}*P*ANXJOTF?!K5P?il;)HkR75L(YMQ*& z$ev%GIo?PqvWZR) zVBYRP`Q>x4HCf~BmN7j<7)bD;V`Q=H4n1x zzvU?8mGX+gB6XEK^d!%3?65OTJXH6hPRGQAwnLUOap9xa5|!z&!lVHFWSA_wV{stD)M2x~ zY<#CI@{B+6;A5NYCK6eW%lsO0;IAvXCkOBeTQ7;X`WO#t9@-|B#^2kz2&) z5D|}_Hz9SPEFw4YA*6A5gEv&v_A_2)HgqWz0fY#gx%i4_Iv}j#h&*s^xPJ&qjf^bd z`3Od+@RiFfa1~tfk1!DfIQ(Q&R+Q|_5ekSq^T?=JV2jW|gzmdU(u^x?mBhZAhMxsR z-pq-c0y{o%GE4o(&)(sTGL$E7?xZn$$&T!H8p1zA<_j)pY|FgmR|sXXzi!Z1{`f@( zS5QSIwAVR}Kq6WE=jMCZ1^=_Y@zoEdZ5MCbZR!Tj8ImW*{Bs7GDy%mk>P??#b{76M z(9cACh4&!n4@W*$@es@m>|wK}&*{r%peft%4_s|8X0Zot;EHs$pP=9~jluS?VyUgg zzsOR2vR{tCeyT^VgVga%SBDA0%B?G8z-=#5+Z&c&v73&|kyt*$*Z9oDJ_T3%+sAgE zEA_Ka7C%dZCY#`N)#11zOh#2u=(uuL2nvpHy#Wesxth@LXKyuR=ZUPu)r2N(9Vb^w zBYA~;5bs`I2=5msoBokO*!LmvLB;kh^JdK!*u`rLWAz2;-l|(;SiJ7siw?*!`W} zyJH$RUwT2*N7v2HdQp>wJI@a_W*HhD^+NRK=8nJd#O|9JzIipx4h~+N8*`SjE2MSU z@kjspW)5%l^X(rN^_dG!PEK3#Gd4aM(;D)FveA5@nmAc%<|w?7#@IZ6$7fXgEC5Sot&~8q3a{dm?x|(uP_OTc<#xL6?P*{Av=qh z%CB+7!Mqk;>?*TT!3wSk@7Q9F!n}lX)Kow`Py}e6B>5fWD9or81zX$O>8N!`GMr9!7_lAj|wHE&iuAxBVJP0z3+YdP^< zZxjdYwtDmCO?vg}RodR!PJDmK3*DMaqf}wn&f>ycnwyQCZsZqpd6YKo?n&yXyv{B( zcT)cG4J2mhSDM@NoiKLau;c9PQn3p+uCiNNSxd{SYns1I2*<8Ll#QI~a+3J&-cf5m z?QU+j3WwB22v-iXw`V}oFhmtPF>!|?N-{|*;M#f zO52OHr*xgOOVai6%-_@5+1W}v%D4SJj!x`&-NJQ8ndqknnQ40lyJfmhpgnQ)J#OWd z(l9zPZDrs6M<1mJk3UIIKKY^CAEo7ck5pD`s_V;XYIY$_NM70q$1u`vy27{0%tFRgS}4UA3F_A$CV0FX`q5V~+4cp-tOnUW#&x zZ#Pk^$z#@C4pe9Pc2P?vN7^x;MHuQQ`Nj*Q?10=+*|rbcs&{+_W7wy_a4aFa$51M> zBXm}MM0{_nqx!n(Z{8ir&ODBJ^M%?m#}A&Kst;0LqR8QxL=;|pH;evqZfYzo&rhZW zlpyR98o879x7O3||LtE?KQ`0-2M^P|haaW+G9*t>_!OlR3f!ZkL-iwFmo@prPFa*w)Fr=MpdaN%xzG=~ z43!u1be|IIaH?jwWd~vT9S@!a1~+-n`B?cH4~sY%25*j?rSvcDa7cbGo%G94bZef(s*dmL+viU8I? zDZkHI;=ENJ>zQXIt?IsC49IN-nn*Wo1%*BeQxul$L=43)`M`5CcJb=jcbDg%@burp zJ9&OaJDHB3RI`RydT~MHpG-eW!xi`jjeSg8!ph8Y0Zp0$#qM#40E5eY ztz;Y&#soHUT=@b@U2H<6y@noM8TxU9Xn+!D6CCFN^8R=ONK=%>;ENj5gns&de_?Nt z^+RA#dIrI5Y5ZHkpfp(V^-urlzx=8UGy|yqWC9t3A(P1t^7%#s!Z(15DU zg{A=h@CF|llPSbA1Z;+oJ^l_6jj5m&2PRkU2r^;tF^U0ri7Seg_`q;CQRW%4fKnLa z`R8Be7x-{HPW>}V2I0b8S@?6AHZBaCS>|XGHOe&(zgJhPN>Mz?4ZCpR20@00SjHJPBJX zBQzjZM4BXUKJSE;3{{*&h+P&2c^(KzF5bvuJ3K_ZWr8f;$>V{99yg>-bRJ&upktSk za46&afoMbIOXQKA%A0to1vt^~h8z@VSl$#;RPXOSL!iTrm7!+7(D&8Dj!r; z8@bg!m{{;ZU)lt9@>qklw@mH|b>sn2d*`+8lCV_A{=uP^;ZmuON`yeI4peP9wxHz!&M*)3&0{}izwWM!8DHY6+NcGSU3exq zmI#~-ry=KyLqm#bMBqcy)5yz$&){%`a6r+yj#Si@8B7HgB4|o~Wtj_+nUebKn*|GB z?!knkk-|@IP)27rHpVEBbICIsIkX^$k9?3DXHZo%;S!LsnZ{JmDmGrtalsXd*{p-x2 zMLB(Tm<JoO>c z<@_o3Y!+y``{T1;UlcV@AUtbaHv8fLnmFv1T`168{b_NF>j_g#0$>R@0Iu+_gVeGW z&V>f(4TIU67Fnt&Oq=aMe^}cIE+eB26+YYRtBJ!FWyMvX-#*9<2D6#I<|RyZ1rDkj zz|qbJ$ymU4wW*vtzUPSROW@?oUSCEFnz*cDaH|R3R-Jq(WqV46&Rru8Y zy;sveXoT&-85Pt$_#Z4alS4Bpc-0tke4|{eup@&Dt73lFB za0LywxNdY)nc@NG47@-$-s^)zMX?& ziG^u)bBy}CTrme=QTw3PN{2F0uAH25T=`osY@&TRN5GO`=!9VaEkKi>o5Q07XncbF$ZEkLB4T(W4y!}ii-)&yT``v z>T$35RbJQP;cqsv0BbutJ;*y`WOvwPY9AeW0Uc!oa~Brl$EW7fCe(fqc|nvp=6*Yn2J@ZcOQ>zJ~%Wc5o^g zDg*iq=I5Bq5m|g^fgQySZD2+wJ9W5bW~LNxC^uPiq3&F$EZB)g`#nY}(LGk%?4}mS zjnX!c+Ns^)60X%r`>l4`Jvd6+dng|FRVNQqmpQx2m3o097+F}{KRi@8@qj<`Y2=w# zzAP=ws%=T0>G3p~6$hkmdwVxMfBq_M$z(?n>kKGBP!=&?W@ndA22wnc=6K0;YW!}x zw=|s|uP&t3nXxoEs=`n{t-pAl{`J5AUy^et{rD$8OF#SjU#e`PP2ascn!0Cd4=3u& zG|ygMT1xlT1~{4(I8?pd-`!QaJM&SJ^mU|<^$FS=;N7W8FG?W#MXyomvLcD{IzMy& zcho*qyKdQTg`)HO)Vx_Yp-inDQ@!>J-U?41(*M$bV;=;8kG|gPbqeSD;rQ8E$T}W% zC3vxx!b`rC1?{(1deI)E(!-Mrw}0>zFTSzJOA4%+u%1WTf(P}8Z@1AV>F0=_ILF3E zl&8yXx2(_c92xgI#$CmC;0Q%M2WWFslWG^Uw2N_-Z5)BPcW|iw zO@04yyyPB`O&O&BTlnr43Yn} z+ZJE__@-H|;trFJF3Jfrlzfs0`B+OUaoHa2Ht1_U#x&f6%mRb(*rOkIY!$9RGfa&Q zXwm_Zj$Y`e0d9u7NdtUHoCOBs75*0bfT%MCN;%Zf>kqt}-@9Q@dIrH?6UQKMywoe3 zgL&tp4*&UAOr)aA5{MQX`GV*KB|J7dpQa7_wfssJvV5jTpZp>mei61{GSYQM7z<}x z@KfuAD(--c+XXnLZ5NOeZezgJzhskZ1jN4{!A_NG-hJ;|^Wn zxl@C9aPt7+EeqTAQ1X^%JHPq5o-Oz|pW z=Lvv(qSK#;1Rsh-F~&n5B^uxSVzN`t9OmdcPaX&<`U}}n$na3}z(<2R9yn(j7{RtI zWHcX;5p!{WI5hMBHo&`|a|u%6Gos)TkqfYx*xw8gAhc zwJXyAvJ#&B98uo!wiOR>-gxoAQhD#)b>y|&ZsRH^XrM>IgDjNsl?EETb$BT{lw&Bn zW;iloe%?ndz>|S}*-hs5p!#9Oss@4#1_^&=<=L6>_*1r4#*M@qIF3)ElSJwo4{_c| zMH%RNqB_A~0y~4-3EslgAd0Q%WDkQ62B_3C_*F_ZaV#GzB`guJ+l*GmpzW9sx*oIW z(8yc_DcPyKiM*to8gC7${Xs+>8d4hEe#IQQ9hSVnN|XxE&wUl;sS(zwCS8k~eDek@ z`A{iFY#@v12?t+?hpp_$1IqqFiluDM1L%TEzOtHC1PQ>7k==yT&0!r)pbgO3O=SGV zFiI!`^bnAkaON@;9cE5DjHCXVI4DVvQGs_n8JyRJ99kSsOz;lRptD(ig^9xwCnoqz zXR{Ew7#z+~7~=rJCudNdVk5&ONF=O;P?!=n!r@^GMN;x0D3n)DkNzO=@-4^ffWa^5 z!Eg^-4k8d=_r=66Jb@h`(p~BjfWJNCPa&CG#24X^(cwS=$WRX`&=%ho=JG zp)Ut7s4O*9sgYkKzfNC?waAm%%U#kNF$Fyyq!C_$0fMLOptuSin{mM_XMKRg4qD%; z`0cgL{cB0y;5=W^!fKn3Ik zL%4njYWX;E!Nd7sR~-fu{I9=b#aHBMqz8Kw`rW-imQcaMm6XvdqZAf zh09jki@VrM*a%;s_|>>NedTIK)5Pn416T4^Ek8J!bat z)$3nh0YMX&?)Gbzc!8S6P)LM=Rn70afo3}18F!IQm*-QSN70^?1mGfdwhIsKaWfG zE4x~FyB}r1+p9b2R5+A5EK;+}g=Y-M1#;B67Z1hxSaZkj@o8#z*ag;22d$&DyML5A z9nArm2Z%S1H2AaV+-eq*TEQ7(}d7N`CF;Iqrr z>7IBYpE3HvoaQN-uXs+Nd|-zS-> zh6p%qA}F0s=A)c$QRdu)cTS4dr(I}%!h*gRUWa&5F1~@rE;M#F#qNNybbc9YJABJ% zUUMpxKbspH>6>q!rS^6M#_~Z2BpZ-Jo`7i%p>Bm3&MSAq)dkVj-G97hUqFn5B zT503Wi?p-#CY`J7*e%4)AznD<2)4-y6kah0MG3~vM0UOH?QW)hU88r0e7qxRroEq@ zo~Ql2eU~xEHL{T3Iga{D{bO!Uxlq;|lZWX~0jNBgSE9_~CDSs7U~Wx&L z!%+(2$L>k;basYM0nDcR%X8`R%6wXxQ(by{nszqU)0cn#GX3tizwt4fKl<@c(?9&; zmukxs-dRX`QJi;`X6E3;#c_@(tohd8=H{l4Eu@d)h*gx(tY^{Zp$z7mSA0tkWjE^< zC~4_)=%>odx|9jK$KCXDLT-vQx}2iYtt-3zWCD@(Gjjq$*M;Y#9Kip&hGS zSOdcDs;nQqhS!BMp87!9(C0;9`qWU8QFcJZBSUQ!AHPI^tc1Dp%LItVaer3Ms@}2F z@=R?4`Jq8UMjhSVRej#tO{eE?RX^D+8{g}SBXT*;b5!ziOl`=-`s3Kxu#W(xKjwvf zKBd9&tsIw#Sl6uc$Ru6xqK`a9d8@j6bi`4N@gfG#2fp#hOAp8&&(v6hL2=1?me-bY zdnr7To9BTe15dw*X-6o(xSU6pL3LkYP})&nX@i;6aWPlrc|jk^GY|zi#~Je)f63=k zPDEPDA<8slYvL-q>R7D9WhR2~k1zmsU$(g?|R~$!2kX8xz1z*~sE} z3a)7a*lSln(;w(}10RALL<4~D_jwoXO;Gq-=mT6^3_(|yNkHunyqnkif$$%~;jfLS zAA;YzdB%>ffBLVQ&^IcdASy4mm{1iTOfG0k!h$Sp+&StHGpe>gPb*h8bD}as4h_6{ z)XM~CS~W_ZZn#Y@UueVAd~D6Gf(thVSt#%WU=*^{n9QLv!Y4w8FSx)K4A!71si_zk zS11ElrKj@Aa+zu2Q0RrM@*~IL@c5xh2wssNx`HC(@sXL?6y6!DU$`O*eR?6I4$bTQ8dhJP|RSLK{hzT((!vBt|vo0 zY<0=aLz;_+N+>*d$YrHh!$k3g!U81~0~{Uz-q9uSaff=K@eqwI_dMhn3~?kKd6Mg6 zmQzUn9u#tv9?)(d>1yjir3Zr^)Z{R6^YA4wZ*+uW4#m%~(m3zIJ%bi+eHQpl7ak%c zPY~(+3!%>H4}wDOhD*Yk&5~$dV8;de6s-x^mpRzc>c_>GPcn`o65HltZ zBg#7l7k=2Qj#$y9ANk89#)1;J%5Z{@Bx};fIsFXqs6%C&J!Bk-=$%#?08Gx#nw|mi z1m}~>kB?LPp{zP~b&-`{3d>;7gFgmTil5Cb-qkl6M>n8M@|!fI9l)ycMPAn_Mb1tz z>MeDTfe7_!LK9c)1Yp-9b(f0gkNj$I;;;->#hWw}x7iENkAW6%Q=XmhMw=2?vY0^; zLV%M&+YY6Ues}o>LA)_b9Y;ncjFwm7NE2-q<(hX#Qdh-?l(|jHPF)`v9`z(~YHG&( z9CZ+J6OSSclH-AQqyND0J)lrfcc2r4xCC$rzY-$yBU^=T`0I+kEXV3wfT>8d8#u{= zOY~QipZl*0qThnl@(@@M)ZlPLXds#i0c0qk!)7~qL2&M#ERc^Ffs`QOED92p0|1vCk>QE-j|Kgy-_ z3BKEI-rOR9+IHZfY4R~--T*ke%nbQ64jwj*FeOmZP~~Z61g(G3C`?10icpy!v=I2O zbX3&_D&h(H5;okpY~^ly)VFYb*E_y2>)aa*wam3yza&9>3w#p>;Q;Xc@tL+y1fyK{ zg1^Jr-OIb!o45kCY<0L&j~Fi&a7v<*+GQNH4W7Mr?oC-5{B@aAmbIABV26AVUxzKE zg2Joc4m7NN_@MLElMY*rtLejD`Pp9c0tznh#jMMtT(#IWu5ud}yfUhysp$scYInIB z+0%n>!fkk<>DTLD$LTwM&}12!Nv>64V?zQaPM=;;4~UUw&#@mGwM?K1CD7Ro{SG1tP)bC|I>3)+nB zPdTRU;>=@a<_MG>yB9j0w*7cMGS+2$%vgG6cFuDE79v@!_pn*l)Wnn(LNA{`_ihRn zwqxOuZ+gA;POhWQiH|{Kw+Kg@Asa^pvS7$Jyy&Bj#g`pr%qvmWuz<-?i|n3afs>sH zC~77(=e?`+u%OMNBtpb-{1@Ima&jEUEY41&2pLXo6ndx1Q^o1USmv}IvpUDTV_{}) zUimPp@F>AriSLDtvEZ+Cb37dj{mg|uS5QEX*BaM+X@tBb>xE`+O1fAawL+1_Ql(*P zdLqruPpdpHd;$jPW%m%}LHSH;9#ikrkyg)AQoZ;`l(I)ev(pPJ8>myXwNO6BG5*vw zl%3QGlqe`@*oD>6WhIyDDZ49M2QBg3x55i$^Qr1E^IOHbn1!b*7&irY<5;B zF0x#rJR9{(+DqyimKW#K)XbFA3_b0UJfpqNs=h7EOr+(x$+SExoa$n?y`TR0hu^0E z^S}L{>GLoC>|LHe{@KsdKm76^)7sja{9Ea8f6vE(vLleS50r3Ix=^05tCajf`NtXu zM?_9cPC9?t!G_X^K7}x>gB=~Apl^E}3?(u^`)8d4rMLSw<&oFSyc3BR#`*p@{Y2yg zCl%S>>ut0><{L2QZ+d3ZyG40^P=_Uz(!xs#e79}F%IvM3!}Rj?cG^AAGedbv z-KGB^?W`rTCgNSPdOjdK^%8zjxA<1tl>Nw1+LYI-NRzHmGRMwNzMIH%gBK_0qxp_l zD9sg*o@wk%L|KW#mhT?=g>A_k`On$`>uSnJ@1O;=cCuGz$;I< zphq5dH)4|CynNw25gldXU5rZm*-1ywc5uW;S(Y-c%i3nsp3Q!H(|yy-G{qejye%*G z@DCH{p~r+S131#$ghB^2d4xsvNtdky=m6}sE1>2Rb#o95!uR9e6}I2!X4u=~mhU_K zfXJg>nx?(Z!*}!fFo4I0aQR!r)r8>pZl0Cmiv~;=6k)jKOmb%0npv4Z4-%Pp=%NnM zT`?0SQrmOAv=GJ>I~H9IFM3tr$e!@Ct;t(%z=}3H&Fp2k!<$v~Js@%8=a}N}#u4%q zWt`_lSagdnqu7fLP{&b4Qg8q==$_LC6n53(DlS{;l(6RX`FmQ#h^H{5U6=wzf|3-V z3Q>656KwVak1XX|T}5W|4!h|x)5x1lYl>P1Tp_-1A|pWfyHClyBhT;yRlAx2I`$qXqvQ*s%yZ{yPk9*rvVEd z6++NtlI?!LS}36u-scJ1B@n*2_4KPqxVP}BHWS5FT9pYh4BB=X(7@0g} z>pv491`2-QE6>>h$N-BlOqj;>;OFDD6B@MeRuGdszUzY`?MwszQ@>@VOXbEn-Fy`G zOasriDobc6Maqx?C<8VIC)7W7{&`25CdyGq8Bn6o!p&P$ac(k`vr$jd;>{hm9VM5# z-~pyw3_PiKez<{`{A3FC)dN5c-gq;MH%u?iQ0C@*GdS~f386n_O8(g)V|b(ixh#XuD( zz(NHMdcfuD1{q-rZ}&@>;KkTR2_HdC>^O1DuPlavGf`w~mPawFEn`CFI_)1c6$P#c zN}RGf-oQExK-07zI1!i^g(PpA+27vm2Z}j;ATN`92b5vD?6UqDOU~suAKP*#2GA+o!oLB z(<&6VvnP{=oY|r9_R9WNj8$@BK!*h|L74V;D$UcU6P_{Ucm8$~kQWN1c2tsCE_6u2pcMrMk|1%U{q`kDD zCPdw|Enh&GA$Km@21I_}geJa(sc;PzgTjLWUnY0JZSerbuZ|~NO(>xYt?wCGjk#^F zC>!>Iuha1^y5er2`|x#G#$C0$>DLUSI@F+R+JPQ?BOQgL&<9=9j$fa@lh~vwW}Tmv zpYZ_&S1y+Y{`smx7yp{w06NiB=%Ba5P{&dE-GXoW_4)@6Gp1MccHM744(d$3RugU8s+`_Fd&VK0e>!}bo zp@;SsXwnR%#mV@=JvIJ;ig6E}d0f{Vf9Q)HU@XFFtgLw)bTI}M2aTa&fYj9Wh^x5G z-L#Gb3dY0Ye(hBA02Wu-=|NsIfAF`t#GA!j7Ei&mFgiOo zW4_?M@G2hsyt~2qa3@WSu{%a?$;UI;eW(&nYI$jrMfFq7ACEd+rAg`a+(Ppj#W8e8 zb58klgde-vW@Z?Z^SvL*aeSP%w>Hwo#)jrH-TZAPj#nRXK{3W>>^`YEGBWVuUyKix z$2M8)A5mUSq}kai?_@!db}n8g$8F8u7yP*Z=32*tJ#^SQ`i2A3w z5DWFlIm&l!Jg;J|F1OO=`lx{l-&^BbUQ<(J>Cxjy>G9*on)^+;OiuU?nBurIgo01` zH#09fjtZPk!=sauMe^L8(EMmZam;x4)|9SE(N2kWX?ZO@eDrbp;g5cj{{A0+kv{qU zr|JHKkF2;`x%bG*tofyTX>4LnbJ;1C@mM-JzfP^AP^O-osV?U{8Bv~0O)sSB*~PTH zdf&>p`wt$a#l;oTu%En+-PM`ho$LZrwK259l9wKkXVZc%cKe`M zLt#OlA}{lK+R(_|J84pL?8y<;yKXBzfBNV2+h6}{`v3jwzoh3cU#Nb~rhoXwe@H+1 z+0Xrbd&&U?BdK{*<;%k4k%IhbwIa9535ixuQ6%5G4)bMV>_2kOu*wfC_t*SJ-a@)+#uyhCa>o z0{R3lT;(e39xi|UlqUK|*8`cXcVJfb>RAwgtneW${zOIpO`Tw!hNCq3?jz-oFz~S= zRhSD&ad6Qeb)o}d^l5o+383ib7j2T-=6G$Y?p#L;i@(!5{15Z|*4j%-C%j+D&LHQ9Ndk%stITO8HNMLx17z{y5& zO3`p#4CJ5u$Oke6T5lAfj+(FcsybhJR`G11P6a(RUG;W?BT&`no^<49zF$~J**Lc| z(q_}1&3=2+ebdY|#jSrC7kF-3`G;A;RrK#L0n=tT&%^>1O~b!GTmkI0OKu)28Jcwc zFvzbTcU$=WIDroh8&IcfF!YXTp^vKoEh^yMd_D}|@gZFP7I8Hp_`RE_6<`1Ppa1Kx zNHdMVqWT|!y+A^Kz^qD$?mQcU1gbDSg416YolT9$2#?4N6Sz{EwJt;P17UJ*YRJa& zpard;ErAO#)<6I0C@S7UWPnc=CSyyOh`~w4NxYdg`0Q(3gezcd@O6I3v|Rd`Fz^`@ zavLJ;L62KEc-sIGm%Vi7&FI1#y70#tG%*ngh};6=?!^z$Ij;jHry2S(&V1@{EFe-B z0^}!aP;=AWEOpEIfk!-Frh&p4|q?g5R3REwjcB| z{icIuq7#;%=*j>Cc~GJqAD=L_Gd-6RpA*auACz5eC1-NRg9mTYX2p;mE)L5B_*;Tw z(2WNJWy$Y-(4=VEkqI7r=yUD(ObRs+W8lQcP0`IT{|pfn5J|fa6%z-5EyVZ`*wWH!(--=#Dpi5X}1-NIa0y05_A`Q{k*)7v`NI&y34{(GK$c(g$ zLS}_0sO-j-n85ibexL}K4d)#Fn|;4q#n+F2`A=4S0hO$Sz(N;)QRV`ObO%22rx%=; zx8Qr?gBQ0RAS^Fu^!haGOh5F;)r_au=vkgHktWz)Ic@<;ytE+fX@%oD0 zQt|e^pW7aD4nwHqGd78MC_nRuMs`@S=vl^kG%IY3m;EB7u1s!vUN+;!L!bPCKXb;5 zOON$e*H}28^TO!q>09qIkyo0USxnq~ZlVfRNZaPh9e9a>DWg6D_dsNS@ACaz$o{kP%Rt(I{#J7~F+sp;VCBr3Yz2dmEanEbmsfJQPQKzZ#ku*Adop!g@ z)5-CX7e~DdLOdAxTwbcIBm@iU9M8zY{POB*n%6wP-8o7xUp!6cr>C0pFQ=)gY00c| zQ(wtn9I>VcoCC2I-S<;-A~KQE8ZP;cWgpwyOZ`0I_c%>jr8i( zy5iVM2YW5=E+fx;!ii+|vrU=h_R8N4o_RA1`W)YhGKn=1)@;~$q;ZMr7WIVrH+3Pt zX*83jrn#n!XJ-=1uF1*KG&P}XEEGx86T_-^e6wy`obIH<_HpW{?Xt6tZ}g#bSYDV- zYs(x($hW#;cMJK8oU|w6rXOJ*Th?(|;==$obKYN!P_2Yl}$Nx3`;+MZvzE7sJ zlauu3^=lucIHmGiQ8`R&PEGxZ7qxkTTm6Ib1;vULDtFZ{kQUM;fTnYF=%W)`hx=-0 zC(0SxORQN@BJBEN{fzlON*(-YTmDYHaS23%}jCn zlj@Gj-rs;cd+YkhZo6suv7?ToF4;Xr|Bo_hmX`;FV;3#E!;lrZ=swsj=^b~fL)99S zF5H3Rc-P2(-E1#q#nF~lROY^qZ@=SD9z}LXUm5Yxm&P{-d0Bw^hhmO?lC}UXed4Iv z5j(Y$p4Tz9qkZSLZaa)i+m{t=L}s(!-gMtIGmUKJ)E&o&pYeg?Sqd#s=uI=gEbuP> z$}aPr{sQc^>vp;(d?@~1bp1Xb8aAL#*G-7F(hInoxZDN>?~dog03IL0Z(Pv;}<+$ujTxFW6gvfEzREi;fE&;*6Lglxm% z{E$_*AW_4{jWFQww2v-#_%bu^;DKMb0Ofv!v543+7E_nQ<$N(0j?SXhQB0Wucxie{4)&Q6tUp$1X2PFJ33n;uF1U%UE5cXhA z4{!z-C?~uP8`F~-4Yc&Y=j>+iesE|I&w#e<$Uz1k>O7=)3y;pfya{c|od0n}IxLcX z~-s$ia5~7!=_ba`RAOV8HqId}x>v1UuOL(Py!CwH7Z_B`8-M-M0j@(4|M5 z9Z{c39lQyJeh~1GT)lTM{rHDJOrQSXQ@<6%o09C9BRirbYaqL*gGRfe%U(<@!t;z%#+ZZe@f; zb>gE=b14BRk2rGRQgxMyHucYgZ^emBerrdx_%k>m4wCJ@)~2(-wBeB9Jh;>(=vehk z^_|Ee4lx8_iNOis8`U(bj42VcC?FaT0E)zCSuICrh z?DVV#PwcA9t=lpXcf=oe;q%4aNzmmGlr3^)g5ZM#H)iAo5YGfI25ALbVhAucmqjH9 zhH&N^f8P{yxGh7bwOh7|huqjDix+${+Hwa6i%D*ohY<~#p~?8bA-m}1fV6l7C!FCA z&oaTFE=M~Q6}-hS^3J5D)gPPrIsp!2l>H+#3sSP#BVFWOAa-e0q5UV2fEU{P49X zPG1h|AlyhtrZpOzT$R7>MIN9EuA3UDMKRz{{n6c4{IOs_P0Zko%0?BN_~1uid&o zFTCx+4O;lf%=M#=rvP~2G9Ua)dbs}Wx4-}H6kosi5XD#EtF&6q0DAV2zBg>4?T045 zgc(FzA80DKKq+}ZviP{O>6{zGUCct?e}74W@{ON5NO zV(X39V@>&G{^n8QGm1V!V@i!BuikP328*$mLNiv;xQCb3WX1v*^qGgl2T%O$FMBKo zM%?i9Sc&mDbi&c+F>muc(PLPS6XY2D^Tbi(4<4+grR5dbQM`;RGI+(fogFMFBv^3e zEq;zxW1K#!F|xl4G&|$PdFBl47U8>9C_&h1#EBvtd2fZ7(&HT~y!C%~EM3b_laX|H zMDqs8*=Zl9llD;>6CXw8`7As+qK`$>@iAV`REm_ZEW-L2GF{{hbCZ*kGk;^r-#udP z5ZUB84T_lAxrH>hu;@H^{_N}Yr$7B6y?*t=c~3e}0`guQyTMxfyJ=@<+xf=4JQM`V zN9FC^^j2w4X@7q^{a^p>|48fWZ=B}V(V^!poMJ)bluJ=Mfn%=4?jyb-w7IcvUTdqX zX?l7_Nl@;1KEaq5g%aOrI!*2FaXRj@^M+kF%;im@kQWyxCZ{BC?0TS%Fi&GnPrU(Oj@svC#VO5o z*zv*17|biFFNn@!vXACdK2U!sqqi#mj^<{37jAoRKW*>qrTv3eI^+mCrH|c)qzUCD z3+&S~)6Nrir%X&tS?R(qI`Rm`@X!d#O6BF;qQXoI&C8%eX-x93tUX8%AAgdbeDBlr z=#$UV^!#$Vx-;VM7M+|%9v~})6Xk;9DHh97N>K(gO52FyIFiiUdk1M_Ygc8wopxn! z^W8e-8?BD^hH}BDgGfFU2gpe~iFstqWmOqmkKA4rx8s#RN`W{YZaOV5E~KTUdDVx- zv@l27@l!reuq)|qnweDjj1Fm@f0){>opgAxou<_$_;wq4&aNBEi~2U9x%|9%&`wb@ zd+x4sMY((S!;p>ak+Feh7{O!M`KmPtVX?t^Bai6L#jeCvdfBWD5V_H?2ZEo$P z7cX9={Z>0&vU77Rc0;0wjiXp&4F&}V{P}j@`uaxN-DOu_+b?Gk0YVWhX+bAlxgfF<(OAqw7$6D`)ces zJ{5lyRPjwo00pj3AflfUZ|XMR)kEnxC6l(m%MHA6O?@RD&3uadj&zg$*!iaZUvWUf z^MDt(Q6BTXH=Z+9{`jITmYsX>RDUaz^-ut%7tb*ILj2tpWYT=Euat(j=ZYIj;wP_> zCHh`u!s}W$*9oxpYr1oN8DOu?Qdec?-|v^p9lL)Ge`66gL-8xnq-~l&WtSOt%z~=v z0NhQ?Kt6pi2tSB#6L6Qj7{v8`;d`N^>n4;kq-_OYznxc2-@LvZ+?J+(cz2pU9D>h> z@e0M)KmXTXnOrvqMqo2h1q6-TwVgqZG9(Z1qXFp3G-PTv!b7CIEpA)|au}h83_t8@ zcw`Y+^TdRS$$Tq+^Y$Cb{_}$}y9+Il{b~F3-$CQMJ<%D!t3a_vrvrt|j5J^K&S}Sv zpbXrzA2g&VM?egYGx7`5NCSp>+d??X%aa2M$a zR?repEX2Z@-BWbfdNO#Biz2}aCOz!@&{K!at}h=aC^wyl3p>{({5^oygOG;;yS*5c z)0r39yiglaS3o*&^7sYd#sH5=1rLijK2ZZB@rSS9*g{^m-6KnWm~-)q#o+8V`i-asx`+*4m4EXmYsRntlRhn({fA@EPpMLgtKTG%S-*>moOP}9FeH(R+xCBCr@k@-n^?N8Oyh9I1w|Gm@~6~gc;JhfQ3g!tKq?^F^Ht}YDp2qxFizit27l9K zz9Cl*i_-+zBn}ycOQ8?mPK~JyILL%d?Wi-K;6XeAA(q^v71MOGg@?lwn?t&95=Mmd z_l37X^&VON?Kl5(6km}Kksk%Z9x3PtQ{{S7!rTlS(6ko-N7xEPLVn!@(e#OM8^4()H(zXSt$0`l*b2~%#&TLS@gxc;!c*I*|2 z+y=pOP&t+hXu5A+h;&oF8Y+BLrW;_tzN?oqhu1#h61+gD=;fmnNq69+OkSlu0F0iJO_IK?Gz?`nZAL~DU>cDw5Ml?`1PU0X?Bx6+9d=Gq_f&bRzL}vumlsNvj)|%1 zw7Rn5;}|=Khw1g}SLyYu=V@UN<{KA=1wdkYu+YV83ZuL_5!!k%Puh#8{{`HZXT;VxKP}* zT8HW2fbU5i`KUh13S}AdxUmV%8#Q;2b%VE7WLjAw9@G;>tuhUT5xX^fG^8${5`yB# z;o{jw8aOs^O!A@p;#)q!>r66*QZ073P%lFfWd)nUu<*{>0t@2iKOSkN-cp|INYh`! zjB4H~{K!NapPWq-(~D_xdcofdJG)G&eN3E+hrAKFkA2id9PB>fgcIr?t-?E;XCO8TXMV>ColsL&NzMq9ciJgxe zQ@FM~msXeO)6yb1cFHKfhLv}!^H=H%(uL~Vh34U{t+es#Y5L~tFT`ggJ$mvu@lALu zKQ-o~Jg7e?5y*481j>77XD_|k*!B*)))BkwP>P-_|H*r2pp^vVFFSD9r9+!S2|9IT7`rc|I-s&@g}?3f^5rWl z$#!;j6*py+>+``uUW1|?qZn~d8THZQu2?6jb_tE}Z70=Dj!GpS(?wrFo$w3cqAO!I z^0YiJP(rw01#1r?3ILCP6Z{NgPAaJ8$^vM?veOjhjk|5({3#Qj3u;HKIryar5qiuh zKHkkG*^mzf5OzLIz`W4(ZmXh|tdx^qd{#WnziEe*7kvxsFYKP1omIXoyF_MX7Hy5X zigL<|KJh^*y}S@F0IWb$zd4}TM%mx#p18j$ZIu@XcxL%U4COy-jjf~ObktU#?0C;4 z2QMxRdu{OWU{}wx%QUV&Pc1vm&rVyR%Gx5&Nld_bhC8RXyqwHwJG^8OySG%fiW9{h zN7C{+7M?#=lnL+k9bM!Dyp%nD4?x>c9_suZ1E1>Bw z0eto1`e_2*M}zxjs2V;bjv7c$ufN+}#)a9u`l0q4Ok2#sfG>GVSYLsDFBJLyTBv1y zKjfnh|My=hR7`Fe$mGB^3-H;U6BI=cZB%MUstb&pZqzJL;m-H6Ctqvf`}Kai=qLvchRgl|ePq)Sh^Q*3V(^q2XcTCM@J7pX?xvazgf; zLXZ{M1v$4MFf{X_GE1ahND7}S-zs+x8<~=W$_*wXBTVF>X>B1*;J`#WDZiR~{D3fZ zN5&v9gm~E@u+1cyR)|n^s#egELoc-7me50okKp<&ayolDwML_aiyvT&$Uw=@J5PAP zS@FfTV3ZZ-vg_dpz5Vpy6CHtsaX1FW3?%5shlknW!Fm# zlk^Y&@b~G{Pd`hmt1EtZ!jy;m?#_-T9eQAsFN%P4l>DIsb=;A(xUdHnf(mC!xv3NN zf*BrFpa85Y4@2?tl`YCYg2zNB@{Wi5$e0GJ!c#YfH9++nOYA^W*${W>>^%w8z?N^j zp{zmi#Xyg@gDzE%IELd?1EZ7U*v02|B%VGy{34WIh~oMsJaG>zZU$KF;-Wnvw(%OE zxXu$sNZznvN1|$>2kpFxIibli4+bl8{Z>^BM9CK`!dy26&ZigzVRbnu9C^vv(4C{M z>vsi2OF)7#$e{3W*o_fwi>iXmBTVR&5BR(NAcwBVw+K$WR>Wvv3ODZ>)8K284{CEB z{sbTSjc9YK#V%@oK#m+!hI16nPXMMZajgNrF0a3RkA9q40$cJ|QazhjSVV6gy!u zK}1|ff~B~FSdis3L^(zB$TQ;17x^MH>VDWUofj@YOt|3}Jj|7w`DN2cL9v(008d9; z2pZ(Jn6s=k9g^Fon`N>;H~jFe!PU30ZrTl^&f$CUfDqsmhS+%il;EXg;yE8+(TYok z^DfI?AnJRz7rBvHR{VmivHE4+y4la3y=kktnM_xX4StyAX5sLQ@KFyl&VJAY1&}cr zB9`K|+2aVKylC@X@A#_Pq#*LJq@qBiJ7;$fc(E));bSw?HhC9l;!0eD>A0g1Z164p&;h)1+VFb6ixpFcIhKKp|`k7&c;|l1f18&lVJLqERh4qQX(OjF<{Z4Lc?<%)uVAg&w!b#xVgG8+H)U1AEYxYc(JW(M;Q znsPPeFm3U%JIsKf_hkb!u82FXCN%j5ADK`^!UkU${m_&@`}gxU|3RIVpofNQ0D!H1 zimR7@1P>EM$u&pP^LF_a#}V?K9!|>Oo5-j3<5|U<^dz7>`(sh|Qur8a6OCgsU;KGl zEXJ}iA5=KCX~xy~F}`B%$k-b^^92@N+4aQ2Jx3PuJs0pOtgJlYMYxj_FCua@Rw!&V z-_XUkuGp=^c#X^7_|ZIsBMedfaO5K2N!oAm{hh;fe0rwD^ZjX##G3JO;X{)3h{f#I zL3;V>W%?Y&(jR`8e*2qWr?0;HD*fU2zfaGeJ+o4V)KMPVlZL%|Dp`%xT`Syt?KW|BgCG>G|_#>HkmMe>K~-WchvAIA?qBkH6kj-Kwtc zGF{aM0Gk8>G^oHE#Rxv~NeX=hJvCmW2#Ewk0tqrCks6rzHp0I-2>cKNF7 z?>+wPeYW?0AN_y-kvZpFYwvSSHPAiQ%9)uXM~)n6XPTLrpMLVO#(HZ`3w8j^&CPle zfA#sZ`1LP-<~zc;n{9q}+9y0rDqR+r7CiRdlC0|+>+$T#(^!7?OtdSpyR)M)6uaM) zo*L`ti5naPna3ZJClBs_9uFRT7DtDB;=|$(i&~7Sa?+Q{XeNmVINDIT$H%%JKVp%Y zT@~KdA^zk%M-GyYEFd9QPK9!-qP7wOnql!C6K#q-Z zuM~by{lOx64lTRt_yCf52j1OGgtPF)n3-`TckZyj1m25!6D$^uW*SIdj$-qKGX+rT zQ9t<24>_rGOjZ+T7Wam{@Wmn(lkt=j?xJF+2xBzzyIqijPmVX)(L(tjP`M)wxsPpZ zBo%o|c^u$_V#OEW!%SqMo6Tb3?%uH%hTuy&ddG_DgFn<%U0~-?E^JMB=ghd`$b#|Q z+)T{POR0=3sQj=Sk~CmJiUlRg&eGys+`O?6HlwDnUv?Aq^ydmWotFd6ZwYeQD^80joB{nxURfaE={v7E) z88;T^RW?T57Hn>@+bWL}oEjgAnF;Y7z80qkoALOw58}gL{WP9F`aF(R4|43L`Z_uh zvkNz4>DHYXpPY`t;c>-bB1R`?V`Q9TNvGW2&~CA_XhY$zK3`QDaLnX#tgJluN4bH`Z*?Brsx#%-pYsiW;~pwf1z3{#J=yUze) z{cGEs?Q3U|%XP9B@PY$0w9!C!;mc6u&2lTA#6jqkrPPxWX6{O(4a?JVXrFU8Djx{r zo*xp086HGM_=4H$0RdAzLWX()Q2H&Uhyk?P9?YTaSIU`MyR%^032fc51?PaZBwd zyND-Pd{r1Mx-p04#VVy8ZxAnhIscT8v?r30cF1iRyACA_<-+B>v@4`FX^U(%uSn8d zcv3!=w4=?UT)WK_9Xs#XKyY2}*THMKdl0C3pDl8+rvY}hV@O>l@wN_KQPtk+^s|$X z?NZ2EX|UTJC-JL`W?lE`g5>knczNOL@BX`g{3j~yvPv~Vkg;k| zWX}OC&|zwP#gqgGXS)D9c$@Q4U8_#V&14mWz1Yl-N?U%W)vtO=x@;s95@)P%kd=B^ zz{Op9rIV>di^kqq8XZNOrpMt|N^69MR=L=cSX*e!D?VMCG%50AD9{r^($uGUE9}Hr zg2oLVnLWv;V6pOy7c>x!9UZ$d=9K>Q;wpipTa7a`Y0E#4;`TxvBwK47(`Q0f{2F!= z$PB$z;VQ2~YSb4O7Tk%Z!Sy5q5kePl@~gfisjL`1fRW;b#*3Opo{l=ZaCjm5#V5P( z%i^mM%!DYCEuf>%K!)QfS{WIB$X4>i5zJ_0z<_bcBISrUalbnCA4itA^QErY7xU5-9dB}y( zbY=*ivc=$s&ZXl`2dsom`C*}r&PDQ0{-b zQaZ)Z`T?CD84kqByEY}@O=dco(6K<8zN{xvIy=gC_oI4FqaIi@RZUUC5hR&$28RO; z4*6_|#K;&(u#3*JI(?GL7>6yB0wIS}VptcyXhv0o{5Jx$W|I`%sPtsWGy;n$@rkSS z6<48B$yA997>I*(<1#)NyJWcg%Wxs=T4-vVcvvftW>e_jN@$+=F$UXT@f}~C9bW)x z=r*kf(vF-dYcUIL$qTLr`dJ9Bq63%tRzM`ZDOYmtC4T#%AJ?^a!!lk*-V2!f>AH~a z(rqd3g~aBr_@+(Amz#Omc!{QhN&4J++-2;EOM!;2L1Cx8$u`Fr)3p8?KLuKQ8?lP3 zbaufg)wt;gzH;i)S7>NE_%EVq-O#buxS-Mn=N;EjNrzlDS37=-N_@%=Tz3Bg zkaIu%7pea6`{UMy#{CPx9J~Aq7?0|>b=?yhD%%pW?WE7bT|M3j#=_T``nKmB7f*j& zGKq#(tuZ5}*mT42L?;yD#o_?{Zpi4r(Z?km`uuz_d3bPGj<4dwH;xTt67j^7l=O{; zm51zhQYSu+j?ZFkeLFTbw$*nZE(>Gq0%F(5Sj@!m% zF)(yJPBaeSXtbT3{k)fG|Hz9We5F4<`-L4e=ox$NjP6 zY+z(O7H;10Ngs6R*4Ed&(DvZ-&*RzCCyMu3+_`-t*je_gU;Q#Z{P2CnYbIW~bK6H2 z65rXG*?8@hSK?JEKH?)EIQE}~Ar=&uSDs47hq1f89lJZ*iu1PcXFi60VPVl@iH|?| zAU^u&*YV`xgLwM*fx>`3`-lk+Z)tK}}3=Obbf{ASEro?vt0hR65 zh2lj!!$-AsLCWJIKqr$DaUeQXl8266Xom#WU++>BQG9l%*osX$7-T8PGz?p zyEITa!OcPiS1Ry9V(u_wabhKczZ#chrq zP&4ByyX=w~i80B^VlWGSlt1L2kUpil!QxkoXVF$QO7-gg{ZHe=58jUtKl<25D;}R| zd_Kkk5J$|-#?0)T%FIOEd-ctjU%DNe+xzi+bt|@{uWjtb6V;0+Pgmm6v*mdDblHnV zdx{6sKtn1AEY4AOXH_?6r^%~aFd>eIEcCGxP-(HVx9`O)jvQoxnh#2^OUNnZ@A&XF z=`2Ey#oob5tZ(jk=Mcx!%}h)vQ`IY76SXZ6j+*tRqhCaJi#uMpR6WZNmviyb zckStqe7Ts%Vqot4@|}!I2jn71PKRRQkOkA-y#s$-%1&91LuH5H{^5zzZ@^`JQe~Ef zDKCCaPpZ7LdvVNVe(3t3@e z`6FY|i=*urQctMn+TK=stEW8J?OSx|R{2O3H!q$_HF%!92+~;aHWaPc1y`9HKGL&{ zb@8nZU~X**U3Z}04ty2dRrbriTKF>my-?FJ!MywIUlqO%Z3TRMtuSbBeuHrO0Uot% zeN`wszW)B75PlUR8G*ozRv1^B{2LEJEs)0Hj*FfANOOZzVTN8%G#5gft)Q&*>4#>Q zPLB&~{@w7|V0wOOHi%ZCnCOK%QKrX366GX>q65bsyd3C4A~d$k4)x`1_S=0FvFAslA1Pkf)l9m?J6FoXmHq}OL?l@bY)h|KN-C!L0oifY_w&=)y&K`$@A^o6TmH>Ai(Pp3}( zS()jKDc8Y?n-{&*38-7R{RPzNv2Z7P`Q=O8jlN{%Yd^lsc=3W5BNtnO$JGho#oq!u zSTgOays7gwe}ue5m49+n+LKsMCv0L(99D+XRj=0_>a_VRN0GWQDN zSL@Q3!LT~s-}uHiyxVJGZeDg40ZAkB^t#ViUwy7l^8pt-D=nQiIk}G5mZ=6+&5fM} zoQhDM$!~pe0U7@SkhuJ$n;kJ$g31#F|I(Q$;~01L%+Kjc=Sm$Nbt>4=cU>JGyQw_* zC!Hh0IAV~aP0;B`9Wr1$I*>XlM^WgduK*}xEQGQ6m&aDp@ybP3%J`rLK6DTf4Dsn) zusG~8C^;EavLNN7EnHsdDCR<48!tK`d;yeSWC7$MU+$T&!pVVyu1Kf+Qv z<3H zFGlmQ$BIBNe#sl@bd;fU`7k|y6DAZRzHm2<_z@%7Gf%(MzyX#mz14s-UkkFNhddPq5F}|K#z0k3cqY)(zU_t%Kg)@k@?<-46Qu|& zirlL|9OL{dYT&5|uV#i$MsBW^#r9<2Lt*V_*+i!UfZW?}HymDu)6xB}__a(G?n;#>D> zhN72qKW$Z4!6h2AO8%(;x$*0xg}gC~3a^b%yLH^LG|=MuRTr+pRRE1!NjWQijjj0Y zD!X;eUku4JmB5X)6#s&H8Fa&RSmj;#Wl%!61U+CtYmD` zRO3!|?yzHtcyf0a{pQ;L=gynKvGJIgo{yP@n=v^vACuE_apTtQxOw|tOwG)Babk6C zBOX0^5})6H;6ETSZ3@k>~Z!zbg;-McZj zu&6W{h^_6Ncr0EVgUGI}t<9}?@bE!AdHOUCG!8r#U+*44M#<_sm1bw-mSlVN)z`cL z#;&*N>1mJ0*Veed==1pCgZJapPdjw_XjD@xjT*gr=0HYZYwWNy&y-Lv9n`hj71ratQ^b5718<*IF$pB4=LFL z8vCi7V8e8P1T=TAT+Eo z`~b%}4vs4iF5=0v)p*Fx!slx$ONz((mhU3lllIy9iMKf8L^Id~o$O1E9f%fcu5 zd}D4h#s<&h`4g4b&puF@{Wy;#l^+Tockxk|UwPx*cfC2e2CGLzjX=l}z6#D81NZII*F|U_2 z9zVAv2K&KpF%w>`v$hNGHXJ%xC{v^dZ7CnkbGNt`w$vW6=!AT@)BagTcqpQ@S9zQ( zZC9=P+?#gc1^dmdEiYzL7PfcyT(;J^+iqvuY0L+{%!jyas4Q_m-Q3KqKLB7s3fV|Y zuF7ENDo1BhKG+SMcbr{Q89t9~l|7DFW!^^OslAwrMU~Yl(b8V!d=qUg$J}zv;58q| z%MrCKq%X})t6a~z)mCPW;))ZVn$h;oz14uKI+Vy%>kx6KFPpOM@}xVV~dyn5#dBW4|&>Gq%zd zLro9IhkA?_uFG&MLqZB9G9c_k;S43l4m56IS$Nv)w@zSHU;bH5i~ z(0F?-jkYp1eOBsxvHFEat;U5S>X)SCbuh&(U5P2WFnm#kO?3WAcV|TMau)O9kzN>jVbO^I5BMua zI;QFjww;O+NYTC&QqZpe$VOa>^$I}do40Pnx4!-Dc=Pqwy#NGMvFK>KX_NnD|zdO)7>X{$89F^6;_ z_%e!)GeHv{FG%qf6@wL-i6>uHB6B@Qn+_O@X<7b|UD2cCrgBgCwUY`^u8|R$YjWim zTSJ+m@=MvFgU+#;ETno-O`W9kGucTu(gOiWo=(D%jM)x~6Ln2#MMn`}GJ$~~Ul>v! zNmJ7Ax(4;62W6J{Gx1QWK-|-k~F! zud|GsgLk?o4H#-kE^yEZ%?>I2n6NRi2%V;4RK%A`dY%qX=?G-oB6`_V_6$e9T}{A~ zcZpR{&f6?JB%fs@5WwLj9bl8?7M@61nhu4+O0U8=J_0ipzQ;mh$Z;PO`NX|}28#6t#&>cL*38hQ}Dev`IBL)QV?2XiV;_D5pr zPg_Mb>~SkR8eWk0;gXJoPWpya1~0G_yyH^vs5Ga<gr@UWso3obi&mF?aDcw+RBK zNykFd&=nbN?%;8${W5U9@zHy?6tJ$JYHsbc{oV9wdAGC$RiMRZ7&v3M{9TpghAzI} z-o;fO2^HVccZyJhtEymS&Nx}Nf^X^4T#%PkagpDi;wq==zf$x+`|3M0xvWs|;(n7CzXU#kKw;aif7W}^ zb>zXFKDWn{>fdwP!@({K9*42HwH>SL8?nB%E433x$A@}%oyX{4#P|sJ+m3s}HT!?+ z`-=bZ>3QsM3WF3Mr{%Hh>H|Wge)i<(aNJy&jvGsPEF4E?u}jGJ6DgjjlJ)T9Ja&&X zZoL@rF=)5$yc%!5{cgPb&2Po4Z@d*ZZoL{4lXG4W8y*|=v0J-)yN>&tufOV@SR4n& zn1{Q=*4I`%M!qf?&m@Mr=bq?4;0~yZ>oGCC;6=6h`9)8Vvf#6_vf`uTxEF`lD~p25 ztIuQk`SVy?Tk|5->hl%fFSNb08?&B>UU$;nY{Z*RqO`C;*8hkMNS zcVlC7BUYY2i#72(*gvq`jE~MV{yAY$N9lZACV=t3zV_V5F0MR#6ptT%77y-!9G`#s zems8gd8|Bn7%NX7#^&m?Sbp{(jt{nDW^zJtnRA(776JLGisUtAfQfQ1-mnvCisQ>B zJXU0k!(t41x4(Z9hfIR+?J0iSiqD~U@Gv3FPKfI-PQ81H`>MGAhlMPTC7d4T?lt8n z^BNixvIA~KX|?uzId-?!VsBSzy1yCwdmC|buq(MvyudO)&t&$D7r*!jl^tJsCs*#U zVnUjBKHvBGjzZpR*UsfW8gnxz4glX&{%zS8wYEZ(>ybywv`4Z z$Z(vTzVHIj+S-QijM`%2e{bK%_j%!q`4p8`@9v1w8hhMlBz3GZe0-9-43DKab%&jlERK=JEFumJaYxyNn2*Mbff4Z?SKnpG{0Aw& z=hxy$VW1=Lq5K`IOy~VqN&^-!MaxI79A7v+J?nX;+qajzWAVlkNAPpsH;cX(F3Y=n zhq1$5c#0=;MzlnXdr4;&66U6-VoCWqJ)yDrMb0Oks?M+hba!9%`tZbU4m*05<|krw z;5?o@_&DDG)lcH%58wBZjVFwg6_1gL=~%dVFJ5`$8*%%!cVb#&($-#~H3mty=Bu?zpZ3ZFyxk;E3l6$P31fepgc#u5&+=+?ySa$|ITixSU;vIgw2K z$~|nO+-El79eC`ZgdsdVEOk4JP8(Y7Mu zHy5Yk-pyIn_uN5ATgM{w*f{Okxbl{TbdDnB=)&usi^-3!6$}aGbmm8%^6{_grQ*D| zcc8k#j$Phcs{gceXGikGd=%*`KP7`|AF<|Ljsw!sxIVq1wLROew1c-)X>aH{^px?6 zH%XUQ)srV+_o7#Og_JWP@u_SUi>v$q*t?jzsMm#lKfqVPeOXu)GX1|=7=Zc6slUDf z>2|fhm%-Pi2k`NA{AIc#?`4_44rG{LPu^Vk`a6GL1N!uA?@lN*N{126FKwj(^rQzB zD)CvG&@&>q+sTt0>13mjE|mV~&#Vd`S5^F$$sT^zWi^dyK~)@uJVP}tZU!n*n(WQ= zQqUTY9IgQt-IIEDhf6ZX36<15(o(8#{Y#aw;9*#hhA6 z4;jSFW>}Q)GB3cHk1}MfEI*Ux4&Fr(`FY=2m z&fWD62s+eW^w7&mF8~%I*xJvR9(g=n%7}8Ry+DqdA_R?2y7JWnvVlyM>5*n$q%0WV z&evG(RH^ggd^VxDOP({mP!tI(er4?T{Wilr{G9O7Z&VFa`;d~H9ExSBRs@Vp#&ore`T;+!}@{XkxG|QXZ;pb!~ zG1S2|J$4fa>{fJCVO{GBoebpV1!>-5MmxpVIUbaXma;;b;0wBOb!_=cha)%W!!Y2b z`gkRHg9X0#0?y|ik(iGj}ei7e=Vktp%>)HHz{PN?m3d8cSlz;Am?;h_;Pxe z1?r~5;xJMI@OTI8f)E1Zkw*{c>;&F=(oj`EAg@WFH%@lwG7z-^)cfR-4y_D+*dR?F zGI-h*^umXq{ZOuo-{L33q`W30WU`YUxH%n_9+(s0k}~HGKzxfY7@KQ)q>gfU_V1K1 z0xOb$aoAG!hYpnqd6cmA$i;v@kX!N=;Egm8!kh^QcjJqcrscyCLP^IaZW&N9XIMs2 zUJJmPG%=qlkF@$8Nq^{Q$N~ZB&cDzLY=XI!Ek>qP`Gb9iNB*Oyy@?mT>_>`622*4+ zF$NR++XkaR!o!>(upO`s8e5aHrAV9I@?m=~9VUS+H9Z^#^k`rRS7uyYN2F&zDd`HS zAz38P>c>3H3|g5?oc?e$n?mI$I1JdKFI+&`tH9x)OZjzK+#7&_(lhzUNEnzKqH0M8 zLNN!z6Z5t|mSwP^PZFE$-oaHlP=A$oe0}Tt|8CEYFCf#5e9HFE@f2hn)8uY!V^45i zX9Ux!nw?A?!U7f7=zaWv)=F7y`FC}c>(NWx6Vkmx}Q+di~dMUT!wXn7CrKxs=9+HuW^y)|eBpxAfJmL<@&T z)iP6kH+~vS2PajbAD8A9pU~1&Rl@@+t{2RtQH^w_MeFl}xv;Emtvh;)>v!*(EA5y0 z`7*kSOX#Jos-=}pTGtL#Q{peXLs4;!YJ3&IUni}*Q2o3NC~iHxrLz6*0RB6w>r5S> z%vQf5C}h?Co5}T6;7fg{Af2#~1zmRiQg&2nL-TJsmNMKIcR#Q6UFomVAJ_ON`*H&F zO&@nr>aUA%5C;HbKb839Kv$f@&MteIuo@Bjs`*zIC z&WZ$l?d z*IxHY9`rlc*Va6aBi;OwUWq&L;^?^ToqfqV7?YDTv2^pc;&mtP+_@94z4lt%d*z;Z zz8W{~+>7bi1&I5Cb> zc-~Q^aUbI@7EYLu_Q#6Kqp7Lsn3|sUE-l}GC7jEYQ+4WY zuv?Tl2-Uo}HZ&5uho`w??fIJO=Z1G3QRZl`Xj_IJ-!QH41XKE6`C*{R6R(>c{6cA>Hm zN1gOe=~5Q_)2qabcnXfZr0lWi&2DEF+6FF8dy(?&F zi@DVcpK8Zk@s_RMJ@uq1xQ-6kz3A0mp_ZK%M|vn6z^Kc90Q)Ispx+(1%Fk8sWpvoD z^7&QyRcP_u_$Iu}&lkaO+#AvzW&}H|4AdX6a&th9f{Y&g&Vhm z(BD)pU0I>hspGSjG2Ch;6rT=-Kn&7*!RzTj5->ACQY^_s&P_PYBRkLqVaTvB=x-+) z_$q56i53k4{M<1vv>6Um`jrK^;>-9#l<%Ar&}1&@m(HzO0VU2zD>UoXo`k6juBULar)(864Djj4ZtkpQIs(Rgyfn7u2dbYR#n&n_AkneuW^78Y_a z9Ir1Tex}oi3g24ixfT=c!;~5=%OMcFI)m5)Dk|zG&1EQ*J#Yj&>Qe}?=a9C-4DUke-7cW*@cCe zpPTiTf64?4l#T=8qU4t{<4d7c#`1_mb^PFq5)EHP`s`}eRTexMFcUrlT`#P zkFreIYWJ?5kK$M$-$``VmB+|$&p3#tniWP94rweP4=sKH%M5SJO&yUP8HMuXExd7q z7929z4JIxTSS=a%4De2X&O8dK=hWy(%>VbVpD=$3m>~ffZ1(+ z;*&mQva`{8n76=@APjIIie@^Ql8A@E$nmhky2P6c;h^E#Fi2d+ zT}lSD^k;+3=0=$?oiL_FrF^ET>EW=_1RX`N@lf!o3)0Iav;n(RPx2KOmd|cA%+dsi z*xdwUATD&a7k^d9Xnv%J>R~ZgH#nQxR$?WC%fBi9N*BJ~`+j@WVJ&Y>ddu#*C*`)N z8xNkQM{oTC_UBj@=oo=6Er7irS0S;K-^=b@+*RRK_tX>F^^@@^reZ{g2IY7cbH7{K zX{(51+WPOO>F1sJjQb@Jd9VNU z+l%XsQ@>kANB%BH{SvK3??CG&`7%X2O5hiaRIz>$bi=t4I_~{6SNUkm3MpFRR|s3T zE-xj75^t?5C3+DC+b$x93G#kZ_G}NVfE=>__#Ih|JvT>$aHq4oW;r6MI327$cLAn zcojd!q(`S0vAKT|YogueD|;V%b)o(n3qw+pWkmgWWI5M3mPIh{cu|;4m~+q2!SRLc z;(L8a{eF&xoAg52(TT<@iZ@5nO;524XfdW{XOzenaj>@?TkETFdVJss(UCEZ;=3+h zEXo|l?%t97UiUp?@4WMFeEZwqinrf-C+@xWR@{E&&A4^vwYYiv6^$R~yvv9MoF`8n z$MW*ic=+%^Jbdslo-IG|@sJ$V#?CNycb%ObOCpVr)c@z0JC2pFA0sls?6C^q`a<4y zR4uc$9yU&Tc+AfvHz%xI#OtrU8bA2n_hOF4$cs}iL~JO&$47e_dmP8n!CvfcZ-~`- z+*q2Ah56YS<2bvKVK0=hi-$X)^60^Gf6xf`>9E6zB`A&chJ;soGr>JPIxhTx@>He6 zWtg!8!YQwLQbZ}LDr?+RH8DLGGjmHZw{Y9{Ro%FCHx?If3ODP8q4noaz(h!-Ft7v*yLQCsq^JA8?sTxG``~~&QZxfN<2roZ(8+2ZqyyBmv=!@zodKd zPI%@72IQCVFL}T`8TE^F;sg~IR2JqYW09jDXVcDoL=)pmM-6w`8N)G`?5trI*NY3K znF5;_9g693jeTF7#QfB_7q5Jb-N=x4yXF06;ypXz-F5RbGcr$mp^zizW~Vq}GVfgC z9wzSIqCC(}AS3fkEN&2Y#s^-s5x8f@xSP5lcNQd=4`C5tPjz@tb@xPd`+`MHsd0rd zH!~%9)JB}_#Ql$d89)B>e;Lo8KJw9;cW>W`ci#P0y#DsLV)6EyF*$!HMyHn4MvO!p ztIaq#h>M}II6A-X`^>n@Yinb}3y35r$LWoaac>~^It@!Uc5rD-t@eq9W7;3o#f!S@ zD$75MHp~MsM+5jiIq?|cjw$6OAIe@==_QU+D&vz%Q_36lz>7g{YgInTYlQ<4U(!nn zX*_1qleUs^C^+o==<9e9MUd~)1X@@A6`FRrB{8n5uHQP2>jD_)>in!__Z-ey9I$w# zvgK2G%6kDFWlm~Ga(7miW#$h!8H%F_S?uH_C{AEuhv5l}W~4Loh$YUnS1e@h?CyKV zAjcKb9&^9eK1X2g9LD!PXDVmcU8Y%h zW3GktKbCBVN9W>y6x;jat#`zr%F5)V%K6-!+cfIM%^M3bq5Nb1A?L3Y54~UNA~y43 zxX(ppUG17RsC{2Tz*Rb zZ0AazcFkAlwQK;rZsH}~ChV9?-s0wek9*MzRP!ahYwpljXmJ^SG1f#VL zhI8(N*o0fQCQ>w5c2FU~iaS;ncI^0;UMG^^nS4#!fL}rdX*6M=nFxHE3m5(2i#h$; zgnMzu-BYlTCgRku zw3W)b@z?#O7rVWdmKMFOm%)muMDOsCqlA?K2=ABMxf^6&!hC(=;|$f2U;*rmg#{XG zI-AnHJI5WHG}Cz_w_rImOy`ITBh{%;1IxR$`?5s_pn19@i&3)i0sw`X9}Y!kQ`3PO zV6lh`j1Pk&8@$z8?)Y=3!M#u7!9U~ez))WXt(cd=GQoy0NQ-`G1K=yFciwp?zWI%B zc(<3Mk9_=;)>u*Ab)+<+L$OmXD6VN`8vInx{u6qA!IkhF`J^GfRZalE8Ct1t_{C9a z-VmW@AGHP3V6YU9F9_nG6;Dv(>M+yUMJAu^tZ*1$ldAYh9ZIFO z!m_L~Gcn_kH83(>GJ7W)0~=BJ3rBU1_)3$(5B13l&SLK0sqj4nmRjxSqGr|8O@WdU$KEpe8E{nuSk z)i2Ma$WHOSDWDRDJBmk*oqfiq#SiXmL} zo3hl9LGY+HJxz#=)(SuAa`HQc^uS^~a-^Gyq>7XL;VLr^nVepx&G^{0c+PSM6I7!4 z0Hgx;grsZij%3BQ;MkP#aK+s*Ziv#|E|sj9c|Z&J+4xCkr$_PYpP9lNbEQhX<5lLQ zFaL(N(o~sg7gZ3AHx6JhFC%ri;>^ncrnLc>GmlG{#uYQ^0!j)_7~QVegqC{s*EQJ# zHY4C(tc@Wx6t0zTe0w`D>zy1MNdA4Rnpa5=OOGbBn`& zpPM;#Y4RP$Bkh&8ln!vllm6)rn8y7!{{4QH7E~aiN^{lV8=C6J|1_Jlp{qFYsp(SO ztayi{L-rA@AmagbKD#{IcD>qD>ESTCc7E2$^P+^14#$?ZSOtD_n6C1ukYk|Auf?}K zx_Hc)Cl#0ORgNqCba9GDewm)C>y~+anMYS;_%%!nt(jjBbgd0-8@5%4$Rw3lQN`s7 z+{>WX{mcD0W7~q*s8&moHeF2L38&&4_a23ZI;mr72mI326FYYQ9b^k09EX! zX{mvhw$ca?Ne14H^yewr?gyW%PwKw%xyn$=O>N0OfqGl&lbO!6^j+0Qq>m>%<1+yM z@MB!a5rM#&c+%%}pAJ9b=8w|!-egC)kHOp7iM`!D9}%^^yC17-o3XO87SC5#V`F2} zMbl(bya>du0qzpw2s6fNqhn(+roKJ> zdv<=%PiIWaF^G|)x+0!SFygSY|J;RA7 z${W&Zn&T0rCO9fh@$yl5N&~-bRL-e;9`p+c;KnZ=WL&RbP>5V8{!OEX2&uP6v0LaoqqD@k8tcV?zJ>6&dvyc4DJJXo!8FZPZj&Ot>ylcT>Vt-iv z@IN9y9I5IPgjC1axyEk1*{ShZoS%xDbJH<7dM$Q0p2dg1{7L-kr$3IP{k?eW&9~zF zKlt7F_HX|nUVHmnF)?>5PGiVBKxs3EnI9l5)%`Q!*HvGiFE6_;vQR^sjw=twRo@tI zQAf`L2e9wv+Nw=T2NsO8NjPKca9y7Tqy~L{%cGbJ)23N~i z_L)3uBAs7$vwG=)bngQpx->?>r3cqflkjCU*t?j!_vY8Jk-D`+H;D&A&{p3R>A3eW(@AAXHH9_*WBXlKR zwPnb-ro!A>(?X`E+0UfGfLWq?QV(U`i3gx=!Y!KZ1@fq>^p8V-dQ?chX?I+eKAv!F z(S>)34+!|7HN0uiuqWP6|HaWXV5@&P;g}{mDRiV4mzMm+7@bVwix7^uOq$W*xsCj7Yf4}gB1^g=zI?NOAua&85_N1M)cy)3y#46VK@YwihJ&i z%R=Y8up3qoX)cA%p6xCr=^O{_UNn#!UpCR%lD z_e=G<0;$>Mu<@#}YwhBh9Uq86@yNw`2-@3>9Ai2XKWY>E`|y9U(71 zsna5P>Ch4Uh2+l;@<0r!6FfCNBQ@oCQ&#BsKuafqbG5lhHqV&n_=fB(;_h;%xKoaK zq0_k>6b}}LywD^684br!VJi(J7hjC#jjPW&|2cab$ z>ep4|3*mcFg>uf9S&HPaI$fhG(>@YG@r3uOIw3Xf*r5b~!G zVzBg{Fff1OhmsR*q9->+k!c~ngdv}WVGrP98s`tZlV=j9%mnK^ES@dD5RRGtUMw+l zRIwL);*yqUQV4Lv*^w<8;if^F^mHn`v7#r>nkNmBam835WflmZ@*oA4A_qlEU>lw* zy$p!q_oHon^o1_n1kmc|v@)UaRTwi$qoMdU;6@no*LroT3JAN6xeYkb;5v;eU@xYU zro}2q`Fj#VfX%#%j7}R2^4|%u#bdUw;!nS7x3rR{22rU%PzIB4`t!iVvde~1KmVoD zAU>t8X8FRadkxlGuutK$QN|3WO95n1gulk!JL2Pk;4SL+1Av ze}xNQ-}*rwb?A^Y;Zm+E%x&(q(7Ig)cosv;r<(Z{zg@kW8?OcDkc;kqnh0E00OMr_ z-)ByZ&?;$PxK_4UC5{HFpiPNWufKkCwc{g==*sD$jKpj_1TyPgV!!&?Zd&{%eVXxC z{9w19D$@dEi%Z^eY0L=@r*TX2YPQk?e$}68O^3P2X_e&G8zsDOInk7=<7nQ-CBvf7 zQm?ogPNqf6t4TxiDgNv&)2q_i-85BoXbWCi<6fcK6PK!n397}n(BsE#J(E~19{T$8 z-#8%My2|en`;*mxIqlV7+B@;ZFHV`&#l55Ks5C<;lc9H%c%_j?Lf3x_*fU%Qb`_XU zQ3V=46wt1twPJ4YsrV64wPoZ$Q8v?TWjRQ*EE84LFdc3Zekmkv!X^LcML9&}Q~pfd zqq=@u9#EpEmiW|NX5@}5F^>}SDwYw$DhaA^T%;`uq}Sq zVsu3PevP9@-V60@7&mcz*7Ve9OpXrbq^tEYA8-E3y*shAu;BFdWG;6JX*_iE=8bs! z?YE`A5pPO=<<-}Mdw?0M&}}4VhlJomJ3}>m~$81?98K(_-ZEfzw_U?hk^c>%KO=XdCta>HC92Ge^KIENeECNxt zCfEryF%k>2<1sfi5_4liaqV^BlGy(@BeQ6&A;_W@y&1lc1$hY zh@I1c*w{VtBJ`;0>+k^OA!2B9Hm(nkd$D}&`HGL~B+g^1lhd=aUWlYPvm26~NV!PN z=|(4Ue#(w8%9i4$bcN8m4AgZJ2wp6HvY5#n0=vtO4>&%NkFXDeD;8XaRc@IN6~eo| zSmYRS`e%E_;)&Zwl_LLSuJ2g4;YH=RUV$Stc_(?ifCeMvl0Tr<3%ASA3z9~9dB0-! zH5lSy{srf`hGMRO89EeqmtprpmBOQ~&s|;36 ze8J)tqb1eSYv*yezZr*nn|gO0i9N>=5|;Q$7Uq`-mK~)W!FYJWUGZlzs{GqdtN8&}^60@~zD)B~pwhME zU(p}xk{n+Q{ptGkAj4|I{QA7gQHTGYk2-ApyL{6WI0%e3m4EYa+W-y$K&ryGk+(zQ zr6_FKAlW2yaW{FT!k(r?RC6|ti7q&sgii*>WMfxs!uxDw+!HAyjT(AEz*YZl;yF(I z5Vqhs>afeZdN*Bqkb)rHj86hXYMEXJ)1}`R;%#~yDfFU(-Z*};7{ebw#cU`>rl&A< zLP)&b3vme#YhoOrO%+@gi#y?_UsT$=Jb>ImkW>|2oIEiJK)kd>R)xxCE|wEl&YW#n!LzPbCxYS{&XCVB^zJ#aPhDQSE8+pcfJQnIL93E zaYO;wD@Zt(#o~sMg@gRkMWk+Ys~d)N(?ey{*n&$U|?%#+YUn0_# zz$PzGGp!1!I?g4YP7&mGdB`xy6VAyVRtI;~U%Si%=eaY$bqDDz7e(plus}tJlLfCs zzAjT4g9hQUGnGdGkY=PY^0P36&H&W;YIjK@ITW}%Jq+;hf9Az12H|wf(=P){(%(E) zZhUN_WOKfV8GOx@xM5d(I2ZatauYx55Ce4<(Yy%9K#nw32kPR5yUhHQM=sx#bH&MvGnR@phc^TAk=#wm!~pRZ zWLTNM$dK6L&s}So#mn`HA8`byxZx9r49bu46bNZ|*nl)q#w&?%&rq;ZL~4iHad3D> z@-%n?1wVw1x$ra(^3*@YMre`fk#ch+Y-K|lkzOv>_%uOvgMX>>#!pvAI2Mt@5Y#ed?4g#p6D2p zqCU~nHJ@(B^`rCwS;i$dVW3=IOFfYn=Z~3`_PbaU?2tx5a_*X2TaS*WFbM;3ErZdO z4(MW9b5(xk-#mC253ZR1su#YT_9W0tAj^t!!tz;Kn|nbnPV@xRRvKy5+=Caq6mL&y zGFQ1(z44O-X=?oT@sY7wp>O<3zshW?#;gz(C%fwhRN6|@()RMH<}OZ#=o78rS$W^ zYfq{UUAntP?1our@M67*dcm7ls>V-IEgpX0ioO1fOng=L)n~UK+i`2%E7ZPh0;bk~ zrIV?(^DlTH&8hljZE;;Z=)$W3nf>Bu749Z+5v%rA)x_+@C3JD_&laa%d?NepGNfu` zkg~ZtrCW8cX4`o}Z#*Eq7+tPW#ZSNAR_U3V^_E{(wNTx=DjizY;yQZ2>OimUGPGe; zTD7wDc|8WCUzur6pVzs>$F-PBUjjc><=Ck5Q{PQ}Up(_mzgW`^I*uM=R|;bY$}aCv z#s=&(V6lng(V6gMx5dH1zQz(L?tMOp6O94j!I-3u$rux!93A^EvBMMY7CVpKoqg}{ zSy^3;t*vc;^-ml)ii-ZHKaf+uzm7i!2J!?7FTi+Aq4?^Z&i!FizUybqyV5o`IkNsN zMnpF?#h3j9vAeY%pMCbR#&;`mu)iBSTWfJ~d=S?)&gN*uo$d8FmwiYbJMPAsp3*o$ z;|0bZxm$)shtXKNal;=~l6K20>`+>F+&HG|&h0z#+Usw`TW`G`ckbME8ne^lgm@X8 z(y3*#2pWSxX42~#ljx;GZGfgK(vk^p%7MlllApz!Z-4W>c=Po)y=x7b7v^T;-rc*( z$Lr3U1Am-)sD7*bopEGhemKj*z_Id?V<`C`(kEz?zCGhRPiTvhiE?%dviLHr^i*l^ zk%|Y3AE%|Tn7{(ltdA;N@NTOSr5QV=4n()MwjAqgc@NsXS6_`k{2PB1zx}-*#cOZA z7q7hjZrr@}S}ZKxjm4YyVs7D9%rD)FxurWcPt7jI_2CI6%V-Rbj4B^kgyW-L#b0I3 z_nK*(H#n$#l58C7$igW}S^JliZ5EAK2;hiE-?6nY6Sr>8$L*!LxM?--Bh$vjgPl^>pQkb&blSs*(& z)ENAf@uGOEd=HPXaFKn;Yp3^-^8oz|& zwinuh#v%L9w2!%{-V=sYS|um#CFMZ*!dwMyHYYS49CB15yXq7#WW}H3RpXXnDGowvX9LcL=e^8-1t}ss(7CX{79+$e|9h?Jdr7k$4H?M`sd%W^^ zUB-jVjnbC+WGupd%LO=(O^d2HbpNGD zM;pKv9jIpe?dT4ngR_-iU)b5*^8<843-p_-&G^>I(50<#6%OdfUuEz2`7&M=zKo|Z zMYZr{JS$wy>&w9*e#I~#GG-}~dg|0gsQFjKu(eP9AafEk?4nMo*5 z9+kk^!R5&l*oekOmXp~w+d%^F(%FR2MQ3KU0sgB<4?K-&!P<) zkMOr<*-WdSjr!G!2V`SeagfRkibT-gFA~#AA->Jna8ENvTg$H^%o|}H1YM?d!GwgE z6M;=cM8aB;*(!<9@x{-75H&q`UGW(C4dm<36eA*TztR`-OR;_Yz3OJ@7^BmE`c z3JU2V%jyEqk@FWYqC@1D(nUsgl3jywG&{^2>R_rsj_HxPX zpm}WI-dN~yMf7W z$6ATO7bJ9q{nentKky>Tp@U;bQoj823E|kTP0) z@(h)j#Oc8cpAP>w-}{z2YOi?k#!JBE89Bt%b^-uwmr{p>t@7I%fYCYN{xrayBFmco zYx&@rFDw38M$$#;R9I*IlGOH}od_@?YAet0V_NakG< zaJoCMH0EEzyZBOKV{Tq=p<3;1bAhlJJW5my!r{Owf+7hOAA z_s?XBOHGgJ&sb=SO2$n!guq8g=np^guP*lD0qRTx8)}pb$iyGUm6BpnD2(O_uPPrj zP^6>1B~Fw@D9gale&k|DyXYsJQAQYAlgte*fFw!jFe^LChtk1iz+}aPa84dEVX?8q zy5Zr6gO`f~O27}cY`&6rVt{IwsbONQo+)2JR8t9$UmLyyHb9u=HG`?t$&E;w4}sYL zPVNp|ZqofL&WSJYe@wC`#|+ObfV4LB={M0yT`36zT(&WdE3}PY^y;JgEHq+@_SdoF zt3t*zp_(muif6qpE;sJdTXTyCzSInTlM20%;hG?6I%L&9di8H}7jI+cYU9_&e!7>K zt*5!gr5WhK7c)@pUA%SdjTya^wLZF}!kqRrLsRW7eeP07H{&cSZP$!m zlz+7CEzSr7wFR7>Jg_x%$*<+ry7kf(dqdaa(r=L+l$2|W&FHunBR>pHJUVWm?T)$9 zrRt{zWNUwRNbJ@0iBC7eM%jj=%t_ycmPe|R>m3|4g%6KQ?x|XQO>1oU>G(6EC__Ku zvK_zKo=M4ERSW5w_@qf{Aj?EmU7D^kSntyHnp+%z886c9r{L<(bgB2NgvQ<)=RP9R8B}?n7r+nwRy@}CAkOrAv+s*e zKbl3QA+gE)qA$(v7k|827$O$;^3rc-Ov>(q)3XzeSx;=v-B(Pmo~WWw zV{>gic0_Y{u;=&_CgYm@y@Oa?-;{hO-pRuv1;;)vudc@0`g%Ni^f(?qeB`4cIZBLi z4@bza$(`|JX2=VtFXI*W&kK&UPQ9oXjH@y)6I@byf1Q5I;^K|?cmD0a9e?9*{#)_e zzw=!mNyp+G^0O$pvHm=sKYwPOxNWYl#@5DK9PID;v<{!rpdX=oAx82O9`g{#$1IAm zP{8qJEHZ_6%$*$W$A|C#I^KW(gLv|E#m7)m5(gRYF(IzZ`Bqix^>&`3j zNB_>>i|>B__hNSOUJQ@TD=()N+-RI%8;R5N>v4K97-ykz;>`N@7oJX=e)x-c^w|fo{N#b}9NXO3a6M$V z*!;}2cc_p)xj@K{8g@6Gco){D%H)>H%&yAz;lW9n)IafJEyu=jCm0{!vS4&3JPW30 zjMqiSLYH@yp;QJ>G&DUqyB53q$FaF{5L;3lLC0~8^D`{!O~t~D#=X~6H;;DX`im3C zd&KpIac{)-`f|Mgi=V{LfAX*5qYr)+AAk6M{Q6hFbiHBz;CtWu-T1)|{~%s@^$qVD zW8BPI2D{6c2N=~jdv0o6@f?Zs>niW(*L?IHabP}Se0(A%rl(_ka@u)tt~P?Z_x5(T zT_4YAH>97lleH{JkY2P^EP4;B9CCam3)|cY1|Q1${KCA)?R*r@2ej<$8&$ocouaKl z_G2Xw^9zeJ6LII}tQS04Xas+B%v>5DVA2jz-?BZ-2i6yE%RDv~vUy6ltaI(Vl`7nQ z*XFn>%>el1lkF{aKj$2h#_l#H;J>!Zd2)?skj(>H6#XvGtyxiT*|7v|^2Kk0{K(94 zrr_AUn7iFj>`YYIu4y2d(=YtXJ3-;&4_D90h>r3|y#mR}JKm+M^yVW6%OpOOd-#yP z+zrMZVJ}_`#^l6g%+4*u_|$Y<^R8I(Ol>;jG?h;^$~I3b4_PohRetRsavY-aOl>Lm zDYCHT`A3DvTqko&?Czr+a*SxcV`w`#5s3RD)rN8WqT-8rTlHi^?KpP`?rd)c_k0oG z8fQJ6ay6~1ne?%q#&j=ky>z|0c@}f=;54c_ zcxyfWfXc6$8%u$!=wAk3MvJ}Q_ZRU4zKo|ZMYZr{JS$wy>&w9*e#I~lsfQ}H&Bhm8c{X^8ugw&=)X{(@TSb7N7PgwjTlG1erQB4=;L2b- zI!#RiZsu71o60EJk-b=?EJty#T(UyTK)B{!sLf9XAPI|GMasV#GJ`ZG{Fp2@EdZG# zf@853NBCOF9TMDdbvj@(S=ws{&h+|adZ4Eykf#5HN@uL2Z-gDpznYVx<3DYT^=WZ`L&hBt}kdq5v-jQQ|Jd&#yfMiaw=`?VRn_d95Y(s1LYuxh*I3CiCfy|`I zw`xQfUd=)dJZ(mkf4vm>f`^Nec`3n@m!uap)B&Qy>O?Ex#-8$2>_83QAPaWAHw}cF zFXS9_c@iGS>PfuoNfkAliC%M`9WP38cl=uo(@NaA9In=~2xv@G_FA5bM2Loy`+q>C;y$DrJh zY>A?S!eC=u9q;M6xfq+6@BqQy*$E}yS$^nDAGrhM#Z~D(PEcmPx*`q9mmx2nQjT&V ziNP;l&?)CFW*#--OvR#n7H{+5D=KzjWnR$9BV8$r-=TfI29oVwRQMDTb`s zc~rdUAPzCO#jFmTIz$YpoCJz{c3Ly&QrSgte*Sn#3jC%qRw;zF!PXI5lQ)Nv48U`bQKBFYQU4P=4h}3bx;IucDbsW>VxTnz+RmSv@I2%~NZEzJDA4Lax z%?77`it*QS)M1GuaJ5()!#m|gyg zy~DTC;N-z~u>xJ1hOC1tm=3PrF4aSm^%hm3p%bd&Evw(v*sFWeR7l!Zb$PUI#0g~L z+xS)b)-9ozM^&!Ln58vsVpYWrRom<)o_0!_#?B8jc+;jkQ1KO&Zhh`09~*ztdh8&I z0%bgkw%YD3n4eWQUsBmm9gPfKp69-AIV*`oDu?s$NKyzqaCn+^I)t)zr-nsi|dFU z?rSq{WE{b%CC+QP`R*uaKW z_G~#OHICu~R*ux$IXsQ6{nOY#(O4yhHRu?Nfw9?`m|cpI$ytSc5xe_GQYW#wyXPHj zoP@G1wZFIPbh&f;c6{fzz7scZ-0+8@jAd@$c_m(X?ajD(`<{2QFlo!gGUF(6$q8M+ z?N9;bVlm}-jCljbeTz$rarf@+c>Q&DP%Xve)O3tbOvcFAq!$vH@MkB)vu7*u=+TpS z_~>CgeflU?SDwVq_J)|9c$W-!B(dvl+zX$|Z~DQ=B*oZ=c?taAfA~07R@Z!=)8@{u z7ro^@oF|}+dhUQSjLyhL=1he= zdUHZ~O`cGGI5lEb{GTqbdI550_b`@MWmmk|MM#<1-dc-;y{$Mt*p4lBX{|i6zVhr* zJbw6DeE9y)(?woeNv+RAJmo9U|T= z4k9mVV|~MO5Bmq~qGK_S#YWXFmxT+BUsdd=175rucG}hZk*L$dqr<*`Y=#|9s#o-D z+1=zL50!o+?3Ppg;Yh*dC->vWfBrAxXFvJ#c>Lh=*j#%a+k1OnTzccpcjNm%{87B~ z?t2;+55>Of&zbUIbMH7FK3$EK^=#?-`DN61(B80%E=p z2=GDN2!IaBw#>e+&T=;b`Z52bkxN^xhFq z7C2{TX1oB&PDyr=o~iy(&iQzOqinZSu6I-i*eQ5=!6{YOln>OA6Sv)zWfraIese77 zy*syKetuSEOlhQaV19=%S5{X1aXKGZ?CrA1edxtzjxhA`rW|Lgy2uf#ymOF=g|UgT zK`)Lnzqh@icFE=N*x`{}`umY)rMb<<7M*mLqK{JWwLR{oOFhjkZPjIfb?V^w+icgw zb^HN#*RR|DSNDE8{GuAXv=&d9to9bLcQJPFB3v#ow8(xQUAT&W7y82kUd|7ECq4x( z(yQ6uf8v5%DtwWxmJWh3rYo#S zlL!+0*{%i)8rz#vfO_8XQyAplnv?lr2%yQ z!BM(jj?x)`(BU6ar^sLUnJ&{DbK#&LPoa1UkLC$;%(xXDyy>x8&zGu2Q3U*QR5)~m z`2vWSXy$cxD%@cc5idad!JGV>dkF$?cqqN2jdOSfa8lYe9R-Iko@QN2mL9yM=hZ2C z@4ffD@OAUXEx$<9Jp*1f+~~3RvtR49<(^tEFS*1JXk26mxcF3MLPM9jhH? zQZ|#ym@|L)V#j63cBnF7`>XK)NCW%t*DHl|(K{WL?ry)taFjvX!n_AQX@FYTzS!p#U>44Y$idK29#MZOcIXrm^^PgU-|OQjuxG)Vy7dea!O|^ z^Ezdv40?b%qJb(MZw*xI&MXEq#2VUqYzLtdmKQXLW3eMY9d;JBYATRllrg@{LSBDK zNj&-LN$KK6Jf$1uGh>rJp;wJ73vziBBz~}aAx%K|s*$B`$|rd7a`_v~O!2V{3KxGk zg0&({Juu_nVY{x7mLSPu_f}=;fZS@GKm)R^fewlB1D2SOHd&TI*_-)gI5n(_OZR+a z-lm`QZC_dLtRpkw%9S+4RX94l<|}*hlLr~#R;q=8v~xLeVJ|q8J*AnTAWvR}2saZI zd_lJ~BES=M&BV#UIMZM)o&d|5K2s%4E+nO2$Q{q(juWM_CI$Hh688)*ee$e%<%f7U zXfv!d(y=-`aVNdNNx9D8#~1-L_)9H8W`_Zff=zdYtvqzFCM&KrJqlD4(%Wo)tvi4< z%ShtQ8>4w+qyA<5s|@LEkG2@w;hoe8DN^DqF}Q}8c~gEeJ@8tofoe{AsU#_QH!#v4=IU3Q5B;T1eT zXl>1OaQN7vF%AvN#L*`FRW5ve`*;6Nv*XKYSQ6gm05+CXp__(3wWRhNh&m z0XO>rmwF-_X9)l!6Ba}@lhy^gcIQ{)QlNxkvW}h%FGE9@?tW!8P%Y`6`O@Lpr}BMw z8Lp!3LW`%IR`*^7D&1r)a4EDT!r&kJ)v6cT@Qc!qdUTz>q5AbqCaaU?{&GE?Aj2tO zK?-mE&y)^+g^R8p^Msir))>1o7Gg|5U!CLgxZ??W_q{y_13c;lvIUh+io>B(L^{QRT%XTf3>gNmU3fx!a&pX* z+`c>f`d~~>&4}M(%*@Tj{L&5aydBdl3K53J-#4UQfBnsP=bd-s-S@r~?|$>!N~1TG zwzD43=h1`Qy*1*+8uD_Aog2#6DdjPX7^EA!1=&qCJ2mB@^Sw-_6|?u z;OJcWPx<4BJQhk+p02AL9`E{|v1gAzi@56gq??{pU72+Hu*+?jdMP=n zS35hqULa!}%pA<{2=|KRDLh9S=X2yByX6K32{W&JV8_)*zy4|b`M>;U@%}G=7JHlP zF+4V*yt@@|zw^!b{Xh6y@q-`zq3>E_!H%71FBGSp!;5&dx)WPU@9P}LI5HaBdq?r; z*=jsqUW+}|IYx`LzuXmfd~%{Pd_Pom8r63MQskeuvPdO&+E~x85P$)_niHVw0<9%%{r>hVG#9qK zAVr%Ez5dKy;L~9!-ST~tss-_qyq1%3WhRv6_f-(I>GBUF=sdsTwz>Ed2jYu=u8P1N zocY*~Ep~@byZ9AxuJ!9TvGsG%goXxnR8na>pmn6ASMsOCm*%+MtdAW?~L?8RIm`L|#`9R%eb zs9^zJb3gREU1jgV$nr9NS@tixUB+SW#l4K@%b+FyYW^JJR}7=}`Tuo7vio{GS@^p4 zAO9!+n5y1*&Ft;6!j#yY{47PF@s)Z~keO;gBn@LxlN4yVROrKCROiC?mB`GC*i()) zJSNq{FK6krbGFiy)UbhW2=-(hFYu}I;KMRvR-tMpUh8X_Pg<0-~M*oRL7oy z5TVrWKa8LL^r!Lg{(}r(G}K7IyrjrWW8foyHE%OC zcHVFtpD1vnL*?`&zSKF0TYez;YR|T!8LDWEGlBGCd_Df}1?e(85OW%&-G1$rxOMkV zj7{*h7kPUv#?)c-1-MGfeIKc?Eq%vZ$LW+Dkw?dL{&P{0A74^wWRhn2^|{RokIo*8 zUA|LJZY=Q7E_&;{IyFap8K$!Awo-zVuY3tNra|hMI`e$3N%9j{c8IYEMVUV1t2E&l zY}46eAa|+`s!DxsW!J!i@dL`kSH zhFsRz*+#s5Jcr6qwuL1JkxO+E9_r${Q^Ju8BkI&aPo7R|;CE~BW=v^tJ)*(ZAd7BF z6EA$xsTL1+j>QnU=)haXl0L*I%MI}NYNt3|3&@5IV8y^-Rm&=^j%6drlMq^wG7-ihgw zGD=~0h)$FQ=V6jr9utx>*71vb4Ig`2-3}=Yvpp!`+Q>stgv$_%lX=LL7TXCDu!|X| zCBsM^1mVF8Gqg!q$O+r7nZ{|CElC7vPg9{YDmga(?3SDWl8K^&WAYM(%}LerOp`z0 zk-*r&dRHVaNhVao$Z;zzdipKCFjF>(I5>MTPLIOd6CC>4N3t_Cv<q$17g;io9 zOA{a(DT->t+vOzby5O|aqlRM&$%IrbKLG|I%*$z$w4NL{lZgNFzy5zTY6X#nh&!GF;-WlIRckj!1bj#(47a6;60;g)F8$%45gMS};bTWimBtoEwI zuXkyQ)91wTCf=K1K+Z0(;5PtN}q-Jrmlis=}GC1e-~PZgDiZ3jn96?9&(j$;WX>mxi1LQvlgm0tpWTluOi zPFt8&??T(y#KW$Qy@{Xvo1^U+PRGfBob)YPzbS>o=->>Oa6B^3t<2W!j@-#Q-GGJ; zW=?}Fht*#K@qvMjX|B*Q*7DL}Z|H_sJ@m@~^pYV!z3(2~=*L-{lz0mz4_rg`OR_M=1`fYrarM~INSPYCz#=z*bIOKSW_+>vW!Q(yo zVZxbX?O0skm_t}H!AXCcdyP0sjQTY_HRXi}#$!yh^Fbh!#f&*~(w=*B^7u3No2BZw zi~c`hjH)Tt6u0rKKlKn>wwaO-8E-wbJ(r0qcO+szQ*Qug%ro6aqkkl_ZXApq60fp zAiL&;3wDrE-WWqpDLfYO*xj|Uu@&o^Tgr>Q;7+;IV@?`T8>aYk*B9wHJ2MeC7CC;9 zW77sS&fQTN+gI4R8heZZ<4YKo&GUwBEaF;BD{&<)jO(?lj$D~+*!Od||`O4}? zzn}4bj)mF5vaNE$5s@r-(Jy7^3cF9Z_iI%7!YhW|TF}2ZV{DZ>UO1A^N5x4t#;4px zP5nJodT?Ldp5ni?yJtIfkaVLCFfL`zgR;j?D)_NjIi`HzXwSpltyq5gAU^r{*YW87 zr?I!S83V(^%G0~?);r(y$HKR7-S#2_i*frZ-|MPJ>=HcJfbig08KZblPEIL(uE+M~ zW;|P7_QJ=Y#`aTFb6%_)k{jVOzi@UY88mKZ&T4COE%vrIa^Xwv)Oq)3kyQLC#uQ)L za>_$~$jZm5#BEgR#?D2Bt+=w#$KuAx!LI7|P|T}MQSvrz2D?Q!H+P(4@4h-4zx|Ed z8t;$B^L4ck8@sW0a31?dXR*7heA?QMJ<00%7s$IVP0_+8f5*=aLy6@O2`T zSGqq!;g#~|`8nyByU@1PIbKHLpLq!KnTX@&aA-eOW~f6o4J?`yC({f5w7q;3?=Z!m zaUOAJkt$Evp}kjmENwD%i+mH4^so3Km;1-!>l1k_m;8zk;9YQ(qf)lWB+4u8`zbm+ zM8S?w793}$Ce>cd$E};UTu)dS+uYbxdLMeus4j;3C{OXGJ`omkC!;F!vs2@0r>Dhd zBtLAJ(R)m8M`~ASV>y=f$ahH|xSY>SO~kFGxws+4E-~WA(S^IJAJ5mhM{L(0La^hP zk1k%hcPI9h-yf)bWq#FVt@IB)HdH#e4KgC@cJ}SSXWCm&WA?`cJ#K}zH5WcAoZvDW z>-(2>qlTMy`~c}c!EXB1@PO)G^>j;B<3t}G_fq=&bg?Mr3dz3(^Xw%tRK7qB_bTXj z>)O9+SQWZqcHwgP*n4r8X}%a*@_v7$V5VXh9O73D!*dh=TA<~VL4Q5I|L}kPA6>il zzyDAEk1sr!wOhC% zrlsqZMFtR!U=`#8tNG(r$ckWo>X8Xn-O^J1WvJy@27okB#fuXCr%s8fxN{QXPt)~r0+QPeF(!IrWd1sWn^p&#uOTbH44*p3YZ1GsB(^}F- zCgT+lFAa_qxOwN6JBJJ$DCpH6#7#JUm*^ptFEG9AG>|w^=Y)HWIIo(^U^(iLfd@KA z3DQ~cZWa0QJzua@(c;BtnUq&tCOL4O^R>C(i|0I6)v!BGy?v4m@GQ1feZ8K9CbVz-Kh&t%x4KX24 z7{CrHeduIm2QNEl?D9HON11!W=-5~!`6J$R>^OFCNb>QeCOfPgXQ^TF11Ph6nM0YT zf>~uWRfCk!e2HomV(E;S%0KWR9Fp?a6bwrt95%laN>jrs*I#KyK=hHjMOZr+D zL(<)YESCi?JZ7PoFBoN~_pEwWC;TY8#FN1@1CSA)?XLlocu;Q{wB1;^8H+QEs`HaE zLPwTB>|O1U_>im&z(Ll@2g(>fFM^=(f*(C_^JJT>lr4UC=Z9Rx113q3{z?mt(R4z( zOk%e?08Sogmk7UgFfW`eI$;RNb4;bwy0e@3tV4AW;Kf(-l0q{h9MYce7Z58fAo=GuP>Y5Wv={02 z&NDgNzw=3D16sR5S3FigUfGQ)ex1;O1NGl@#+rsu#kr)NW0QY5XWVeI5B!S{xQ4I& zR8tG~hkuhLZ9`dPgl7rSHuE-#Q$kSemNB`sdi9rp&0!Iz9+yH}JvVN$C=QkcKPqUJ z2Wu(grYii3O~y1`DnFPLRcNuxl-^4b#R4QnrjN{0VC-s~wZs&+tSWMoZX;OdMgB^{ zHIV+HRb9j#yJ(CqJh5c9%WlS*2SA}P&42M<|KE${-#qj$d;vBWYZp&jMBN6O^s>37 zuhDQ^i{E}7z+CgE!At9>sc@CK(fM6PE6pXD_DFdEzMszN4+^cg@gy2vSSG&Cv*Lzs zJO7qngSH=;OFC4%&89DQFM74Kw1EJ{Ksvuh%ba*qp}zsbzFF&nV=AUcq=RSx%H z3Msr>e`$7DCE7(Gx8nwowG31y6<{kjdQ{L=zG%rSaa}u5aR4oDk3Z^AaZgb)>=rUz zvZ7XlI5gtponynuKB6@^>2 z8Li)B-tkv(*eVV_S#FR&^9^XjOd9MBAA#E*K}(0i?7Zb3N5 z^9#bNr5659VUc=FL1%w(Jch;>VqlnECEUG|?MO)(`7LzP{n6pbNQ|;$MH$Rkj$JO? zqr}(qOklIXw6wIOKKwvzZt>xq#&t{#7a6G&_+v6Ok0#6y7MVD84CKykjk)>7n46o6 ziAnAtW-@!i$62w{hm$EXUm344naj8+$F@u+pK6@J-9npNyS@{N1%=VE5%;-=#D8IK z%De{Ehi50jvz5(QS=-R~Esx;$j;p2lxHUf=+Z)UA`KKSm^Ofb;+S=4OVn60J27T?7 zdvW{b&6t{=jmha5ja$a!#?4#ao#SXIeb`lVpz%pA^t_0}lZ)6p)EHNy)21CWAuo5v zNi3W&7cf3P;)S_u7fPRl-PqsWh?V6>@vC3{B0jl)-|0A|an3k9T9jA2>`2?&@faA! zV=VMdO?&*non8C;hZ+yd4XBG?E=S}kg@<&b+>y^pA9if8lVWlzZYqAvR~Yas{_K`H zk=$E5+sZSJ2;7RD%{7y71Ux6mu;4%*E-c-Q8@H5Bckacjuf83Nx9*6|u<}J?^_~4V zVl1dKz{2U6@@H~%NNLY0A0uiCltRi&+ET_4J;+9iIIF^z{X6RAu zm|;OM$G{qYst!>%rzSNnRUUJ%SdP0jCet`}e|ICc)|TVhqX+TXCm;A8JMx*u=R0@q zD*xW_E=3l;>F%98jp zF99#EJs>^#7<>KsN^EVedy$p#I%V7o9+I8-pLs5UHcCmTw1o$|?6@vultuWm00ckU z9TrbGHt}e0J7y+E_EDKB2M^9+WEB@=EmHm-{;zv&AJ3wY< zD|*fg*}pKiL z1nP)9TXyK&Hp>t3LJ0GAs4B0NUHQdM8He5<{7OEj1>x3t7sb`5-^f347+0IQpgPBK zu5;{mmEY4-=3_*w@D8XidZ+BE9ovzaWT$-@Q~Bk1)w$W3n3G>IzlQHfJyQVrY37? zr(3Ej18Ii4%VIa49sfXv(SqH3Neq=Qa1{^A(^dE`VDDn=-b>O0-7ve*&o`O$;x5y? z44}*LUqZh>QZQ4o3s8O4F#h!{e37?*IX=1Y^^g8DjcKz{0+erJ+#5w)(q2u811m4{sb)tg-6^o;AyuF{i_Vj84U|Dx@q-3qM@zO$CpxI; z0@*!S?-pY0{Q7w3fTJ|x0`wY%j6VE9WVlILV-H&93j$1g7Oqk$&BR6lhLRG-cX(8~ z4t+KDqB|xTiBF0KC)scY%v(_0>`ji2ssI$Pqx1)|dV~jf{4;dm3m;+i;@}+QrKQEV zefMt6FD&@W9l+@!-ZZ9gavt+y7LOM!9_Yovi-jF7yqwta#SRu0yqLJ>i!nNY%|)Q{ z<1$6S@Q_AFk{2V5^@)0EEP4${)%@o|Pl5$3g)5+5c0{=FK`!_@jc}IkRI;A#2GXRd zFT{?N$c`*8LKcZupFfYsPoBoZhxdI3H%I9a$DHgJ6#q3EQxlW%jrYFkBMP~+6eJ4{ zbnf_KgoT8J6NAO9pi{NzK~Pwbcb#Vo&h^Du|<0#jPobSZHJcseW@&`B@j z<;Q7E$3v{>yj+4LO(^j(@KPo&$ux%aLZ4CEP0h{3s5+uE3v)j2cubv@VLB_~eRNcI z5FYNAGNtmQJgeK$NfQX38BJ{em( zbw1uuopU<4-nK91@TaqjJG;a1&mCiwW73{Z4f&3|*f|DeM6!^7+)c*USkyyyqPdeQ z`T1J(Sbiuonb+h&PlCC_?!hQ|p@GHV_3Ugi@b}TL5==?uaH!Mx_SdZP!?;Wd?FBpr z0NjB<+!>%vPtL0IwGeYt8qkkTSbi42JRt!uC~jGe^?4l3A1*Z z@awuRXR0pFW>p`^m5`>js%^B)kmVW&*5M zm%+lY_)0!hLcr|{Qgz~sXaCI{f^<(q%1|&RMrk5!_`zFYINbDJwWJn*?C>#0D0?Yx z$qy%CFhB=U;q5RBQPSy2mjdtlCHG>+==hW{^)tY`(A9LcwbTiW*-=dzw34(LcJW=f z*?_s59!-K;esE|>=-`sD@WY&Ohrsz+2pW#bz<~B&{#So>3t#`i|MGvUs!{?Mbj^)S zq+`K*mlF9!{76%xBP)aEDzs_){JQQ6XukosnZ=Apo8hJOAzkdJaI8EkTxG6)Y_9Io zobnd9g?|55E(B@MI+u3x3UcFxHmw~B^ceM1nh-bWx?o!eXZH@z3g+K~&(JX1Ev+6` z6YDBp)-@ZAvmBirUHP8N`h!ev6HD5sU(8Tg>JnJSr1I;6UCV+bbU^(Gga)EEtpH)$ zs)y49fM=y4I5hJ@Zex4GtY&0(lOU)#G`wV1RL9hcXh~#nqRF}X&F~s$<1<~lkm*&; zRmPewSTI||WJ9GlNVqP~)>sY6tLvpg^+((*cw)1|k9g640xDglc0DV$lntJl4-HMh zSLk6aH_8RNZM~$IpjWO6CEp7)G?i3(H-3O=gtDwxu@p4%k*aaz>3-rh_0Na-T7F!8 zXO3Xwh;YWM>Nk;oO!%pw`dD!FrRbZFjEwmsLU^$l;CsD9!&r!Z@(qn|=jUd9%+&Me ztNx0fiAhpuXqZKVdMaYcEbck-oXU7MmLz!44&MJiYSDJ;^mLzbxhqIt?_!h?SL9 z$vCV~2jk%AB!)FE@Ue!H(f5rV9f^JJei~-H!N-c%U&M&yVh7az{&sx)@rUv0XPA_Ar@jE#1SeNlXGR|mR`?vn!Z^rAdzpl6*dMteZ{^#-QU;j#D?rp^#P`_Mb z8kZf)jT;Nhq&#_}Ja;+EGEH_t&q*nN`1`*f?|u8*KGKc}{MF~n@#|myJU-RfcVj*8 zWJ-{K(XgO5GCC1=@4XuDeB)d3`WtV@;*C2>gK_VQ+uh5>6FzigLBhMgII)9%yF{W~ z`2$P2kB#IhBIFGd>8B?eQ?hU(IauV$U4VQToD<;Z7b>9&pK_J+A&lMGiNYkg#%n4c z{1`iu&m0lBG(Q>8u~u!E7KJh_vK4@m1Gf`X8Y%#rNI^Odz& zUE6Tk#*N))Qz~N<%6}GCha@)(xX4D?_vAl|4QI+XWdUW0xN%1w<#>9M`>j=nm7aVg z%*V%%AKs4#pMM(nKl?cLceY*6Zr)l_e&33Fuf7^@zx|HN@?30gZpXt%Ph(|uL+O6* zMQQGXJ6D-Ok>A`M$6`45C?8VqR0bus>+g*li!mX0J|;bTaXq&7Phw3xnZuzi+1=by z8G7#YqD0b%YR#(Wtbkl7W30X!F_dOO0V7hv)JAf-T5_@t<%`r+4Dj< z3->I9P%cU9dS5y92}Qfgd*^Wwf z#_%ftgx!2_ZIQ%Z&eU5L$B7@JSKgFo#{bR2p#5k1Buy?(v12iJ^Kzu^Y)nnh2si2l zIpV=Pi1*3?a#3%UZ=?+$YEu^$7WF=un^eoHy0^3Ij~!U}mH08FIzk)Fj?S6Mk(gBb zF+6llGQs18>JSV39FaO4M@pOL>pSt;gJ*I7@$=YHyB;TdY6+Pq&9tIjbh`1g-N~;s zs`eIdoxkae{gU4GN4pEFVy6)>sUE_0%R(MGoMxcQlOOP}YvBv%<=+c-tA0z~7nhdj;&hxRxg4{4%J0mzJ)}tBdaiQ(cmy7aI33Ci{v& z-u~qndEtwr4zV=RDjA0z_Ek@)7@)XN;iV-F4GB-&q~u`gX0*Zs%4{?XqQ{tkB|8W- zo7EY;CCvtvVnm~xNM)Yo>G+X>0V-4`(E~RgP?6mpG*rj(tTeDr4Qj;?-X&g@r)e8V zTZwt`Rb(vSLT09-L1e;^-9Gea%3uME@aQ5lhTw%O=r$h&4Vq{AwMjem-nz9_{)W>17#7S8&{U2bJjP9Zvd0qlsCk(Uhe zhrQ;JaX4FM@?5DPzh1Wl?{aLM!cqz}$&czRZ^uzf6_rI@B>Wtm!gt)Vy^dZhidP%aQj80FzFqy5_d=4c*UcYtt^xeG31(sR%*8R@*(r9id760b$>2Jj4Ce1{Zwc6v?D&cx8v zm=^>2`jKN5xU-9L#o%sFoktc{FI<+?c~OUh1vlo2+<}n{#2tP^L&F+il$s1uaYNSH zF{J~;f-Rkk6Ak=0Q~sE*tV$aAOHy^>MkNDBRb=O%-H|LV=9fb(_R;|&{ax#njw~`A zXkf>Vv_TD)ra8ty@~}wEE-T6daUbC;F!7|r%wX_DgA)cM-WjRE50IT3>FUrDKk%e; z9uGkrS)f*!%5#oB^kSN1;phpzgrZZKapB7#>7wWB*kN_5sJkq9j1BW8+@w0!3$dV1 z9v69Y#M6FZOrnEd$R<|R?-Ou93 zftPj>nSk_J9>P@~fGPBFy*0)p1w>gbjiU^OPsRCNXqWh9$2v-_xYMhIISY-M@YZrlR9X_D3yUrCFQx|*fYZw7x z^;_NTn*RD6?I-g-ss4+<;)O5tCVz^a<-N)&D8}p$p!;bZsi`$xdfK!u^zah&(8}zz zD^T5xuY9CkMFTYS{O}{?a))laTB^SIbj^VM75To^E!RKbPQQ zM?UB(P1Uomcl;HwY_e8djVoZB`4_wU3qU>_K1HKLlem1>R=TEtCdmFQevugy`Jc4- zb?v7d8`Z`u7s)~P$`53ICG@*h|J`_Du+g3>KXmL4wt>VI2V2sya43Gk7JRi=X0Cha z#a`v$VRPaef1SV+mucGKTRH76bh^}dv|y_n(3Tdugrx8HV=%7tVJZk!X^A`Ihz6=` zm6xQ90?4ZJ(w7DMK2SY!YFX@?#9vc~Rzm~qywL$fJm0t8^ImYVM zSMIql{NT}(c)q&kem7%2CQ5x|;^?qL_vsSqzvr=7^vBPAnhE{xJUWmM=dw>tADv0k znVIRBo1OPgGmcf{$gHVp^`+Hr@lo6Q#=1X<8yw~iGRA&mJ_?Qx-!{1KX?@+t5HcpX zF+US`Z!L&l-fOhCud(&{b&plHINEIgz>5%s&(U&I6Js$uJr;3#==-fc|NPTfS$P(Z zA3yS<8d-3pu@k`VDId?Lw40q-@Ui*}H*TtUU-w-}+zqD2*5jAs!+niqc9fQ<`9a^o zeyl6q_I7vj<3feIySp7vpFPvK_R!(@*gewRi%q4hULT3y{;l8fU0HW--|~3w7r*#< zeDcXB8uJ`FY{o%H2kd0%g35Fm%sd3{Ih@d-^ZiJ4-^HL7z$0N*lFyku^o4zz4PvS@!jwJFy46k z8$OI{-x0P2MBbvu5a;M&u#<|>cH#s%oxeY|9A8}GH;03UgZe(P@ zJH%#GS0=|slnZCEyS*8Y9(*1jfAnGe^4GtNhY#*+{CTE4zZGx1`DVQS=3Bm_jH4?@ zN5?&v^7zri*xJ}snjgjW;fWZToR6aurHRsoa?bH^98=2OZj6_Q2bAA5#^U?p{8(u= z;+>L==UIq;wzd4=E;o->M8yvblnQk4&k<9#7K-DO`@~ zqkSX2Ngw7b_I9>?r`i4?3*Lv`LCJ@vb2F21b8*ghu#r|=x4@#|(7=$}p9{&!afsJ0 z4prU;yg++;F{pfH;f4G-^1|2AF+0@Q$;IM&?pkDSjzZ@-O92biUTl}l$Vc9@(8D{3 z@<2YHu^=S9w)<$r^@TEYP<6*MQ+ARsm0#jb8^uRT%)8`ql|#u#?##Dj+sbjY`N1(j zd%*%Zb7Rei}|o<@FoH*j(e{_3tY z$5UY!D&a=l)q}r zK7JhUfACT4?`)`ClIDnw+@(#j?r3Cs$dc|=FZBFztM(op9(J*+c+W$TE5+TpB;8b% zh6r?^v<$^oNrSdT}ican5*O1xbf`In7mIUzgb2#i`0e0dI?00Hj^K`W^nJ(h4kirzKOMD5#w5F6fIoXZ@a5yED5~h%yXcQ*4>p>8TG^k#X z|B9;tK-+5hP0&@UtNoXQbxmOxMzSTOuP$Os_4p96=g0YzZ z?fSt;+k_i0clm4bhxjHZ2a5rlk3mx-&n336sZ%kpjwPKa)A5k6?pL3L!D~kz6;8f1 z&h&!IFJ7eREVIxhJA)0rSYe^UU(1M=j*u5Bcqu6YF|2{scfa@j_~DO!HP+saqexuM1pcCNI*Ko{&>``zExo{#xl{p@^Ad4bAhL5onvtgv=fWB?7rump)fw{= zAPl}FRGLlA&&Bk@TnwobFr*hhUq3RK9MV9F0od*?Tl_UhQkkN&$w1WG-)Xay$^KGK z!qwvjeIJ)PIdn3RD|cGG(7-ddvjYrBNIQ-*@DU8hCmtA(Z+zkBj*|v8?EG?PO0qKG zsS98JicLJkSjnb{3P-8q?k>J|q*FPn&OMzz@`_^)kb}WGi%$#^N%LcMU|IMgd^%8k zp~%;ABoB*O{5aNwJZ3SO@|ya1ew=0!8{DJYSaf@c|AXdAwM(ze16 zzEbtwQSarlT-c!|&R~d#e#9-!g*`z-ZGQE1B9o zfpjvN!CoN|!n~xA%u-?DLA+=e2oKMRH5Gr?RQQ{5%4+`=3U88$qES7)JlYj~KC3>oVMk;YBo24)g zWR3Gb`LF(OM*men|H2pGJS5)5+yFB6(D9@K5Z}Z%?tQcsdj0phSG(J%;*<*-3FMK} zyE+Q``BgW}#31VfX`L$bx7S>un$1K1l%r;j{yqLxe3YrYcL0*B@h`0;Uqf5%`2mCY zSZm$7bZI6mh|*r6(h)h+fRv}MpSsWoH29=!>=k;=ZTM*iVWZ8cBL-RCQ0lT>YhjCi93iVX$A*OuA{3pYeK!*ZgS~QN#dx z`zd*C+A6pJd!whZc&KhwWL*~*qoy~pw%xW~aGxPf zMQ@>3?gT=BPwQ0dl$E{^uJYdx{WPsS{ZPwRYW-k7Ul1Ny&TNG`oqE>}$KVJbpiOx< z$HldwIQGY3InhgBnB4}H>)|1eoSN|XfH3IuA`5wN=k`tC-@@@=_a8izzU9ej+TZ$7 z81(rOAjkG|H2sk$wwqlEh@`$WAEVKCr@u}*at9Lk0dXhssK4r;_np}{G^V+^xF8wB zJIz)%HoZ%LT_`tiEXB=*dC5Ge@yA}Qu5ZNiRk!ur%l z>@$A#4x3Sqf}Dz5ckYO8QsHr2l^)k7u#G{48E5Jr)+1;>N8z;y3OEj_K)1$+jDxeELZ& zuRQg*$lxNU1gmYI3#i8QL!-W{jQgVA`_^~jowwiBSaHmEU9D~I#E#_iwGJ0_gfwPX z`f$wr^u%z?PL9R&_^>C$8BZRm?CmNKxA&x!rtBcg34ZFeN{jrnh?>G&xcst+#;zyQ zhxq^&9QSuNV{84n(rP7c-o6pPt-Knan2xP2A>f@?xCnC8f+PviUR{f1n9I7wK}5 zNqIgtRzBb@V>ZH3@(wF3?n7f-J~qOF8s&F4R##SH?fG)7K3`EBpT~pypZne|^5l&- zl^1Wm6>}PsE^^1)jhjlN(Ky`SjZZ)RIG#RRj)CFPn4VpX;n7LY8EItgF+cf2U17mu zd`xw6bSNfBSGgT2&A5W%kn=fH`)PqiE%{h&~=rm?N!I?wb$QPdQT}0k7HwNKi0Q)V@GA}?38y6 z?{_}3%>_=HSjto0Eyg{B+=-qGvGnb7froMaiBDg+rHHst=1~ zDh~>Wa!h%sb6M=Jqpfs%sj|-E6YaBigh`QJ)OB`#`lwB%BWXh&^*d1hhE*px)|4wN z_+Wq!$4MK{kEo8(2KpUB=v3hfgvpOOAs!=2M|kEUAfS9QkL1HVOBYgR@{~m_`YDMA zM_#i?>^T(0H9wfpyGhDr!1a*hPgyMEJv5~JWk>K_EX?w8`>2moeX_C|D=TY?)2?`i zKgwWdCySwH7tBAsh+B*E@y5LydOu9W+WJ=f>5qREAAj~RKd7csDZNQ5z$gBApqF;1 zha8=jq(vb_uX7KLz2nx>w&qm0i$604vN%b=gHfC@q`!oIGe6R2}Vv)I+nueuNClt?Ms=wM%Z*d(U z0J&I1H3$t9KIrx%0#AtPU*m>_%&^T)FoD2i($e6#nMs8fZyRo)oF3`Ze(VZhvIkEh zq36VKra?dN+NeW_8&)t$R(L^&JN6=T7ObR7nm!;6@FP053G=nu-P@dbeLE(mr)Ys7 zDqfZ9=$0k%yx=%1SOy6EV&`SBz%Z z8G4sVr%lI^G;k1tOphjNq?v=y#U-1h*;M`NXE44bcmp6sK>!{(&=F)Bn6UE z9j^XP1{%l|$AmR)s<^3<$9m$ey2+C1!J_~KvJ+o+C+(`U@cHMT$4`Fp(|GXUv$7LU z9R_(J-S{C(2}))q20VJ&YzHEGg~v+{Vh732wCwEBLBQe6ossGzxl(IghzdTj9S}=8 zOylZ&PcLxP;Y19Nk8032?yt2tK7n0>91n1yPVc$O7abQbqDrScxh%*I)CC?oSiF>J znV|E)NAl7sp<_m};f=2@k2Of3GrXscF9TiT$pFF~9Cg|T#E&n2M%2OK9CE(sqO8+t zV;epbkCfk>fK=yLcshkFZgIvpg8@n4g)as z#ZR(mc%O8tucUEyu<&0NNl9DPBfeNAuK1^82jEVJn%!sqDweQiCr^-e@R|l97kqs* zp$^)OSki!fob$ECn?amAxTTYrUlLMZm2$W#zT~MwQ8@6E?lj0Zf)m&pvLvNJM&!yG zmvyz_r3Wk=E$QY852<8mmI6v|f){|($^Pxje)O^7v{N>;JpWtJbOft`wfL%O>;7MQ-KQEF1OQxL#8F+95= zSvtIC02uLQw+b%8`ZXM?vja*xTW!j)GWqq8{Qu{nR3z1X^(?Uzz z8()CFJASgSQFsYzckEy?CJCE)4yoE6MaI!Y3c-Qg34gqzo-oI-6w9eiZM;W^%~RZMpA)-__~;3b^c$ zv|W6+OuUqlW$JI!u7aNNb{Ev&`Xawy$k$F8cG9VzqH)qS`rqTTF*-3D*9ONz-D&p= z2M6*fI^?C#$4L=G>f3OF2uGFE-{*KMCiTZKu(~%v9XDIqxt08E+gOU3kY36Qmp4yIyedE&}nIo?sCyWpf{1 zfihO*loDWad^l#O#-t`=RAT`u`ffXKGJ`EeM4z66?2O>#CIYN zPdQdh;~)LlB{MfYt?}1z931R=;fpZ}cT^K5ldbf3SZF}DYcGx^0SkyMQjQAGPNH#N zoxojF2Z}gV(|3Mzs>Rt+Y?fmP;dgj&tiGMbI^vf*s)ntzz(9Fm5sqW=m{1-cWpP9C ze{mW++v~BtxfaJ7uXDWOit>~@oDL7!5hjmxwqKlOl_ZmtmIlmK_aZ7vX2okk>GAjf z_}`1a^+$g@2FIpiV~a(}t=Ky_ioL@##Zn_O#&H@?jcGhMJ2@H)(_=9vnYOpq3JW&$NfNidq;76bn1l!7F;}*l$noGw-kqyW2NuWL2PcU#me&2INIG* z*&S3KjmH~ry%RtBgTLjSO`BT>zL$+w+2dKIx$lb;zZV*Z9?Fd!YwUy~zbFH4!xcTo z+8m?Cf)G1Ryr`piP_7xDvhc~mCX?%wv8}D0c>3(A7m;q?xDm6{lddDwOV8=J{3}g8 zmI(1URsQA&)r2uE{ugJ*zNc$#btN{|S7Uc)({m{-q_WeIqYRx#*N5ZP*ItirzV};R z=wdEqRBB{m#^rQtV?BQPlfO{a;x4|? zVRreP%HK{rU)z$rFJg+jl_n=t2X^Aw@^de)aHJhqez1VYz1__93@Hs}xCc!2R0Yzz zE%y#M!HBW^pm?j@QOThVVX=$5!!}gUm>XamPN63)n0H|@>Wur}rFdVBk58)J&&Mt9 zHlLYP-C;!hBF2V>+(t1ku(qapcXX&c8<3w<)stPP@9kT+^KLUG+lu1!Y;{|8g&ktb z3zaG2>zz)bWk8Up+~nPJ%x$sQ#GD9umLE6q0sBet0egNVOl>ahFLP9i10Tt9lq>YK zDfOsA@;}?^gHhV$C*~BMK!mj^5=(oLSISzVI#-p;E1f8*ZGc3f~{Mk=_5u4ll4#$gE3K$syWC7nqg~C-*!V6QFpw++j zF&e*(-k}p=wVR&5?Y#3Sp-E?2yA^YRelx$OZzHJgT{_$|3~;SGdFvjO-3U1&+2zr4 zNw6D#`N^?D#-&0x+zMCWfG+;3uz(s~7y85Ohs)t%@5Qw=ZM?67%e=lCIK(gUdsW!jE^|va@y-dPI?3o^Et}WB$HI>PzX!q3jd4Rr`PYn(HuS#U95hvgK^0O2cqwOdY8Vy|ZW*b0di01fQ0XZEG< zbRkW7>gN|A7P(2MgF!qvQu0I{2EO|85gEJ;{LA|0tPu_g&CCe+B!86U10`GHl}GH< zw2@9(@g`tlkdBh`%Yqk&mw@A>a5+9>d{SwuGRdXN)A> zFJ&z|+v<2Iz8oz`r?f6W(rrN&I%A{>NIJiC+TlZI-Cwb(qey&mcUKNDsUr-==+Mwv z%k(8qoWafFE**V3Qt*;4*}&t@0-VDWQ-3k4pF4eYsFW`7BpvB!l8h46bm)Xn8j7_$ zjS!q6uYTklGBD6~$A(A}An|g?Fn6I*k8o!o&TcT`kNi;QVqnG}nW=+gLnH2(4kIIU z1nv;c-H^5fn;?-qmI^tD2zf3%ixd?I2O3Yjn^s7XfyaxzC1J4%%v&H-4Hv&ADfWgD ze|t;6#kKGgfJUxjEC@X_J$TYa!msOI`9N2325U)gwt9eaJ;09aDNuS7I0YaO-r*v9 zB_pKJ2?J<(+sQv+EhBWO>Y6}4cmM`YqB{>=uyMq_N(>&wzt{oc{`|*3 z`-f@yHxJ+W;otj{6s5+gn31hOwKuq4O*;ABOP>b*emL$GdUy%0GB^IZ0IIqxzZ$dj ztIb8(mQdY*m;3AJ{EHjEtnZhnKu9};2RP5$b_!lw(W|bJ@(%j;&;#=Os zHdjB%+kfmBihsLRe6@G{cFn24C^H*5Te>bETRZMw6;}{FDvJ*0)-7qTkU=1u>@}Sr zPj_B-mCl+~p_94NC5^fG=YR2sxvGW-fCaz&3T>BPRb9Nz{-y4J4{dSj;1kzpw|i9u zPyMi8wRgo=*FF7Khs1XwX%m0RPxa(yuX{gTW4B&fzJjZGlycJa)t+*vImeBa%wteXJ@>~!-RK!;h!JxG5%rq5IcI9)MZkB za$NoPVcJAVuCWmJEV1ite0)^=UwGFRi(yROb068gdw0FNX?EdO3=EIQ&i-+%tZm2I z#!hT(?Z%dmWIIwgr&3IYYYhK_`2u#;T@UV3Vz&`G_cw9G-qPZdPmQ^A_g>7-Ed=*X z4GxWZ5oT+T#e!q+p4#>OVH(pNY3#&M=Q=xVrekDsTH}S`I6OU%&7EBMI}!mO!JcYd zb|Uh{&Fmr^BEM0W0gJ9jCC~1 z(9@@n;+H@DpW@l0`*D7J5T{4GvA44p+ndkh(SuLp(dQq>qx&Dn`@j5IJh=a<7lyXB zH@yQ1S-zq0xklj+{_qdu8{d2{re|jrkm`lX>o5yqW5Y2$$^BYmo-}`qbe`AZr_PJckadAJFmozrJIs> z+DC@6fcE(QC-LJy`%}*W{Lc4&5O2Nv?YK5DrgTzxN|(90S=V_^TA>Z_xL4zAvU^wM z?(x&-@%Y)Q;(8bZWpQ>*>Gb&NipwH*nz2aB&O6sL%Dl=A3)`F`Lt60>EDOUmZP^vZ zJOc|xyE{AHLAs~1?t8!GPW!--eUlTa3o`p2xEDEBK`~QKdXa=VCfX3%9_}>f7(905 zkr)1GR_zFJ;7&W{o7iQ ziqh7~PtJ)HceBd!#v(K)#qdEed?@#Ip3kJNSMpotD3}lNyHJezSsv3UNaYP_gTmd5 zQOrpdxjZKzBa3z{Fq8f;NO6!Q+j%DIXhftnTx*4Yft=YJK6n<}NSlF1tLLe_|&h z_doJs1a0f;+Gadme(v3T&(~Qf-f`My{{kT;M3FVqBXO1yTt@+kx1neq{3ZReKkG_3 z^ef#2q!m!@fa&}B73ktHrM;?Rx3TpP^qX5-*H1#yb}1^Z7p}qqT|DNis7%x6@G^cC zF1usz#eEqM;H%KQ3>@NDk@GhXq7QoW@i&40;s5(j|KYWN^q>CcR7Z8ls1UBp0-Ax6 zK|Ffe1S)#!^;t=*tI}ngS3S|$li9e6Ek10ibm)bs18xM>@uE6ZN`r*W37OJl^*CZx z3<@qOO5>Ko%f^>ouz^l)h1mWG&0c7bQYJ?M8p1WE#KDkqq!m1hH-Z4(mZLTNA+NLTlKJ|x|q6B7${7M7nJm{c*Sc@ptL^F8EA1V zz-@IlUQx%9bH~A>XwVHL9FybvnVph?=00Dh`Sk=}uN-l&gvN&a0;e#^Oya?^0pOD0pFaP!q_WdHGW6FYu&zINWgvG=8#f6xeoKa^h zJHnZl$SGqoGdLW$^CvvxpwZL2M+D%D{}#w~G@g}j<}2}SoOpoJ&n%Vpd{yUi=bY7V5kUOh1k#7#_`CU8J-Z)QZYG#712|C|g{3e9FS41|j4fGB?@;q!c4*UkrU#GeuUK(UT6FtJq(Lso1q!?&DN_@DL!LOO5Z!!Clp4j_Tq?fAwGyu4LT=`15Qz;Oa+0g}FQXvs4@s-KK& zO^-xWw`xeS^f0YBfKO&=u)9D3HhyJlW1rCGw_Hox=I}vOJjQfNvkb_G&HPMnAJ(C* z@8p89tAiq~Evzw_9*}hamw)nq{=fEN|INXF_`mw!5u{|X*0ha4#q~qQTZ29g1=nvb z&^31OUuJI7w%RL=G`m%6zq^2UHO-UX*?n}t%gn$_=}MT!WfnKk&!fW2cx6#2F|2xh zCbF1Q2h!Z7$uiW^7i6QSTjdTU3q2%2!>>5k_}QEuGoB6Lhcc2x_KsdX3A*xD=*L|} z1B(`2WxEXEQ>1in==#WC9%irJOGmh=w@_tiake$q4!(z1LeqZqxm}hgp`yQfnqJP2 zG|t{nhssacI=X0BfH@zT=rk#YP#ApG6)BjcTPV&P+7Yz z?}1)>(($M&p%tyR+7*a*F*a}sA)3p$F1*a$`0CWWA6n@3*AU8>Qsz4aI_&C052jMC zmBJ2>TZ?nCxG)=Y^Nbk>WB>3Zc6RnWo}iyTGczUH36E(`jyVy6@${L-EsRCaeBT#s z;<)da8dUYjyTUd$HeyQs_g7!J>v0fc@FA72ndzw*(s+XpOpi47;m)xA;|njiZE{rF z&VKA^?7<=zZ6C+0O;1k5!rV;m@==H84z0`!p4S}?ixViuBpj>8P9xNzWM*8y zySL{%%(!dHc_`sYUlt$fqev`|N%(-4yTsU;0-n2&DFbJcnYn`+4&Uewsgg{N4aef_ zRE#MNs59)8VXSj&-Xf zKlu0m{rLUg`@pNgZC3yu91_v6#pJvj9df`=+A)F9?6NCq!ds2q$cJ}g#_N}knc zkK+IJ|NL*_XFvUkkFFbLClTdA;j;^j`_*pUy6t%w>@1273~}71;y6C)Bhsc-2E4;W zvawLWYw48nt5jWFU}1yBo9%6m#@qK|C1uThKbKLBHBpUA#|OKy{Pd~Qgt9QMa>!9^+>!O_-CJ?z<_(p(b1#yz%L!f_eaWKigZua6 z^ZTF1Gx>k=>}jm6Jjrx6h@k}VWIb(|@)j7I;MmRY#CN{)J8}EgT`zobWajGXv-s2h z@n6KxfBF}``}^PeqrVfczx}N^KD(woP)bT}$_3??qcO=#c7SpOBj88%m-<_Qe)rDP$!EP+#&Z0cKnz(C>9eYzOCQfj* zg7S^>&pe1^UwOXn-9Zy_pHq3CpBnKIiQM(}d~+`zJYJ9I8@q9&cA~!Xa{ho11z12D zR2iG_;wNQ;dhEN!y;#P=lYFTS;SPH0n%g|es#x(^E@g=_GNn9bA&)k~cW)i$-CKMB zPkNE3#2p|#IpKx{$eQ2aDDS=tY?$L0&tu>1!oKs*ZLGqlSkU(R!*kJlp-pMc=`+Y$ z+iDgVYkQ2J9RKJI;kG;HS%`bqA=()}pkS_skDt%dOeFDD^cIMB&h2~R%L(eub?HO+%$9ck#ezcp| zyMAqL!vR{J=owza=L)*kjW98{0Hr`$zqI5jwK3hC1DANTwzPK$UHGD~ zD)fg5TorB?E{BP|7uV8cysv`Ge7-t3#4quGRos4a=q)F|3HYePfApXJ6O{u01z8zj zOWn*YvcYzRXoD+mF*hKizs?6mNi$?cH>Xm`3^F2oHWq{}`X&rNpb{|QOl6U76h!#7 zqoMJWhSZbHT+j_-P^AH|<&*fLtHrs<_!DBrkAL+AJ{zYtE}}QW4`UK!uXuEndCI89 zo&ufWCKQp=OT*?W-ua>{3>#=ET0adNp!yMW$ELBThMx54Ud_&b@v04V%AGH1-1(Yh zX=y3$-nkod3-j){L(7Dx`y(>vVusRAcI9Hat3$y=Kf6j81h6QIN_@s z>3o^Tq5=z8-fcq1O=$=nUp1ZIPqpsh?x#RJ=Kn6P}fZs z;z*e(`Bfp=8dxBD^PRV1Vs<(X&yL;MA@4Yo{#@n9ccO_8i%M+ChbJ9F%99sJ)$t*0 z23(XUI#(WeDhw~!C|nj}Ng48p$dK*uVh~q5;FL?B`7bNwlU-5_LWbC)uMX(2I%;H_ z2QP|`2Wcw%XDaV>ZoskVMJJAdkk9Dn7!bbLl$~>qtmFe#GPdfkXiJi zp5;*j`Q?~*p3(UbAL2}jU~$SFWbqA@{Eon2}Qm+?xo)Rks_`Yetiw;9Rue z0ghkgmu!++2HGK;i+cu+kEF2)OTnaFeoFmI%EAwzn%g5`LQq_iSqr!c=~{#gqO-W> ziLR&YL>;t4E;N)ij={+fE~@-8l{yY2cPT$WWO`*7NR0s}hh`IC7aQe*lLaXBMJB(C z@h3vNRNfUQO~u8uJgAodflFv_;Q@U=fP_HB1*H(NktuR+&eFa0$snDODg*bG$!a;bjsARSLlt)WrB3KsptvGz8`m4UITJoW_>BV ztHV!RH>|7uy(FzVq}XeEWxW8Gc7EWncGP;y*#Xh%D)TdF2(qybxX3VXnWy{!+W{A@ztrmJUYyfy`q12&Jv}uZqZ$+P zVJIKB(bdYMe~(2gCgI04-u9^#Qs>tO0)}1;PE%-oZ<@wq^vjvp zW>*SvV^;&|!T1Mte9RmI@zVHCiAq?E8M*6+u@{mtS$}+ZAU@nbrF>QBqe^#<8{{q^ zcE9i;@9VF>7B?1WV{UrPALQPDa6dlz^i$u}y}GskeNI#jsC${uRu?DE zmsekTCEokyH{zXlzTurnbMrT1V0bK!PBku->@0jC9}5TE>9n`S5qc`4l6_-yHMVy) zV`poc^d!ifBXNAKmC_~ z8gsML@elsNKZx&r|3@mj!%BbEL-C@lI_p%PUtAlAqw{M{ht>7%*xldv)d*bsz>$j_ zJIYag)W40*9hbpD;xjqzHiKQ1ESRwvcs^UX^+TY)e-Mwv1WIitGH^$w#k zH$y!gaGm4i8;&hyx9FDIE47jC;~ue=LM ze6X{~%z`Q(xr@Ye9sBa@t4r{swvF=4yoT@lVm?Ck16TSiEPPE%)|sg(=Osr$?kg_L zc~FPN()2EK0(2I>#zx20zUBfgZ7GZSb@2;I!lT@?3Hg9uqF@cT;cC9(oExu z&5In0h$xdzzYFH0h2-d4fHwNN!ebGY#m7507UR8l-;{bi##O&KdiU|uwb)RZ+EIPp z+2NkJy*N|Zo1Pd76$^2v#Op`;ma$Z(byb<>tzO-WoxgOubnt0zY15o@0;Hqy*1@IO zZi;_3w|-l5!&lFL6ANGHX)3fyS-l%-Ji1W*SNJk}g>HBiOnU|SRpEBwav0cqaV<^8 z`zm;utX~Bj;+Ob;S^R!8ARqs7%yQxD|L~vZyn`6JI%4kdwNW@;?HOJv7->{xlwJ8l z9nML!IU@`P9bQ9uqRa(SqmafO_q!_Q|Y4% zm9w$tlkSO2>D?&khkW4EwSdS?cU1=14Y??^3g3ZM8G$AQ8Rb}bfTiIBM|*xY;yp1|%JHPIPzCqFRT4?kIRg3ky)z@-tXNmDxTd^x2Tm|kA@?!6K> z)$wMRj2A7;L-cx({!RY!mvZM{iXA2OJYZga$9`eu3zrVPJEk5uC@sw^UqUpL@Wkvp zl(-CaaM+z@UVOZu`C^5yYVtTc2W`GYJL5vUc!@Ibu+`vXNdo!HbV*w+LHR5s)}3CI zGdndo>oQ);D7Y*uHhK3LW;gl*{L7O~NC~htpH;_DVc(5z2V#Vv#YQ z6|f}_vnyt^QaYNJm$wjvUCT8xLBy`5fq~p*$59`$T@4T%J)_FX5`Z$h!u`UZU`9%*MF5=+D90q#~B3Lz2M?A&Mv|;d?#~gA# zeDbHP0q`TmSrn^zMERtXiB}C$e4%r}QCSSwBlhmYrb=7r(>mJaeBJa*$r6r3bqj$k8?9zOm_vnYhCd6LsNB za*(c0WSQv0Vag*A<$^`2=kg*H)rs(!Aa~XaC{Lt2G=6tLB#$|PFTEj@f=?R2(iN=TFe zfwzAZNDGE;?3nAG@1_f9$09+@PY7^?H{AeNoq{G&z%q)+bSCIR8(~-Ttjy3s(q3t? zLn(jj2q%0^%s+G{g8&O*9i+uUhREi$kS19fObO?3f);P+qhCD9@6g~7)^x$}T%`?2 zobV98P6m^7v_O|n0>r5#)!qUG-{@?&HCVR~LQwRL(d`fZ{{OX)>bjU~n;J7&v<7A}4O zldXQ6weiu9JO*#FKB(JcY;WOPSmPo?(Ae?34Ur48BFv=ns9>Ai=2e+C zJyq)5Taac!mO(li&zL4$Tv(U0BNXV88jV!ytu5~0WF?Bh8`Ceeo0??6wQwi$kW_| zaMkE|8sDw~one$mqZ>gP!flkchwM@xg>gMkg76!r3!Lwr{0+wA?%X5jIPQ`Yh+q6C z$1x0ho6oy=1HJz!-R*F=@8U%spcf?6#d9>Jz5-VL4)u$zdj9JprqWN!7Lp#%?M4_+YigfA3ZKl9&UN@i?)hBBi|Cf(m3HvV+@WzWQP{VqOq{^ zV1r$0Ti(&Z(R0sV?E3pYj4hUzG)|tKDn2%l?+{;bqJwILE{{DGKR70gtrN*fI#$}z2nFWG3Q>qjQmcrZp2C1@{7NW-_%*M z9yOkvl@3{aqAp#@@09WCg>-o#Q+mH(;YN8t-ZDqR!a>S^t1rAzoN|qq7Z!A3hk*GV z=vZu+dduSMbvZpglKWoy=)(`Zi;@Mj`B@DFug=SV@&EdNmjB`({=;&5c2Yk7{3oPf z0MmXU^O5xb-S2$6JbwI0_~ctY9urwv zY+-I`=f(5#kN?phmw)t+|Ja{D`0xJv|9<&z{pN3)j?GfkMf&-#DT5kEqc4v8d$o5` zp6wo}4ylYtpX{L8Twg8^x7NzW8lO*~Tv1Lb+i%OI%GBZUS=l>er`)yb=4CnI8(1nQ z?6~2(;_T3RqdaBj5TCi2on3I;lt0=N%ADsCln0oM{VDG(aB&18bc+iMGP6s{FN&)S zx6dT-X@Mn;xjCM6b!9>Il^sq~N*l+tQl3}b`W>naqZ{&PL3N6`81mv=a=+L=F9#== zE_=)uAQQSocIvq2?v%OYHGX^>4n3TmUdWFHJIYAXz&wQK_jJ*w_+@wrFs-t`w!%@F zEU4d;zND*j=}qbM9Ega9?L6@@=fDdHw2k=Ph#zTNkUqf8s*C_E!qEO!N3FEak0o|Ui{>dFwECLNDjsi1bO~wYoq-2U;bA4>%a1S=l_dWd*!9d?(X4< zo((5{MqEn2v-kP#8@t%3+oa1JyLbaV4m&hN&wPyW`16-Px-rIHJ&zVPcF8TbF>WA& zBYxwd14v#dZ3CWl5`sD z#F%}!HCr=vxzZ+#*{Z?oC*0&GuReS(1|+IV@u;4z+<*c&oj5U}uJLAJK=$fKyp97h z>}n_~7eU9d@*_aQ={^uFR&f)d(=dRJhddk`VFc!cr)P62($F*L!$wL+r#KSrP!&t2HakB{{aT>=xTF2giemhb(MOWd0<;li5;L z$|d@&UZFBnrxDR%c=$mDy#f>agf6ys*||d1bV}V-XZ&N0v9n`(%{DjnPsDQ z(J`=x?470h#g0Lv=LfLD<@u&tqiHf$H|epiq#W{WqHoP8n|~ zUaI2(3p&OOCRWtpU83`^4i5`e3-b%gI~Hng{BZu_^UwVOT*A{)@M4n~C?=;V<%dkc zBE|wrEDKA&@V#FsfBkR#H_P_J?Xs)E$e;b_hh=B)m4Y#d6lYiIZh5jCX(r-xwFUsQap&8fg$Ix1I%I537b-9$Hx{*AuJYChq6O1 zZ$q(I>~c?@!bLbbV_rm?s|$`w54#IdAOmpxqEdA-%I=$~vb?Zdo<4d~R+m=Gj5=`?opjrjP8D3<3Pf|r1r{8Uw|WE86Q#0d!izRZ z96-np8KxIbWH%2`xUtKD+o_ksCAbnrBe5F?gkgnBDAV`mG!WX{TpyY|&Oh0Vue4q` z%D;wa(0C*rU0Xp!`a|FDfO(3SO^SZCo2vzgiy+Nqo`4;_)kV!j5R(`9v@kNO+Y%bt zAsQRwyR;jhoCR7qrw)H;t7#2k#{s47f{wl-;+=FlB2&jpZpR-2<4kX8xXK5f%~^Sc zj}bP}q~#i5eec5Q-{LX!VG*PYgT)}8!dLa$jlGYh;lXu80uxntcayJ(LM0cbtacbhpK!u(+;HHJOx7^MI^{ zmEG3O+8T}X3cV8<@s~cruX+z_I6)#3G5xBm# zTpm8y7VW)q#15H*gK~Ppj)m-!SyX?YF%FA6#NkCRjgy$*^$TShXRv6*t}nls2~KWa zPUEdGUIwHO?nN|>AJ#dNOmS|ktd!;DC5;JYyxWGOtO!HgdwcukuM}>kY;CTV z`GrL!MXyj!w zo)amczpwEV+GO__J42Ak6T765G0kg@17(u-w%|t^SRiDl4&yhUVu2hgS0Z)%OrBp| zU1Y&P`lHM-=i-+DRSw=V-m;V`w;CU0j)1t)snWn?z4YOi38gRd5S|c}8=5Z4o+tfe zdKpjnj67slI#?8V{ODo%&bK}(-}vUomX(Fh-Q69JPuDj#M0&3rpBzd5hu#^)dd}OM zQydK{8;1kpM3h4E+dpR77*dg zBsq0}BPaQu+{aI!s!VUWTs(XJtnBaZmT!IY8|B~qn}4%B`rxS~$}yJAOYto?7N!5} z&;E7!XaD?Pl*6O*vi0CedHTsG<;jz$WmA0C*EdxDmaRL=?Ee0-u0!Qh7O~k0M_+zU zx?Y%_Dr+lCWNO*mSoe3pSfG|Vq@TCtNcHd4?m^i*JT51v7phzAv^n;i7G;*5T9+E@ zv$#T8R1r`fvRf%H#j>!xthT~qYW*(GnZHu~Iz3Sx<+#ps*Ez~J^0N3v`6sVy}{ zR%qg(&XFI~TYq{&?FjL>jz~r?>bZQQw%Qgbe$y+RES%AX(Wd0(0OV4|qB3AM5MF=9 zr%Sr2EX^k}fZ!RBXB$Ua(q_3$5Fd8wrH$yHTiC(zgmM_SW1*RuzE>V^ua;l_{&&hR ze(yWp`N!h_p~@gT7GJ!4)h*1=O!3r`P8i#Tbr)BI-k!AEhAhqp5*2rQ`MS~HHWSuu zEPT{Xg7TcfkXHW|PlKVq<}&1`zbC;?cgSF{e+GrZibcq#Vh64`c`@of%Z>ES%rpe{1GWYyKg`SKFGOETQxf>_zP?x$m z4#v?Abo!ot@PXe%^0&RZbV90-YM`NQTY;G%r{l{*i#JNz1U;R2I=5`UW-+3rk!}ET z(IMcWpY8dQMvVavPcKfm!DK;W&Vthkpp(xagtLqf4v+khKrc+VyRjx6y5Nn-NbN=w zOVt6sl$W5ATfMF;scxtn6z+<(0j`o7YHYFv%fxPryM@Q3ox@IA@Xr##fD>g$VW}I* z6BkZF9#WQ6=?%Z+UcwlWFrZ|D3PmC{&Q@d%np;OlR3utDgs!~}LY~qwV#n6A7ca`* z&W?`jO|FrzefAy#3vrj)&RLU=OK)kY( zCf>%0pa`i4zpT8)$A^f2_1Ax`eDC|;ce(sR9pgX$@ej+hS1%H30NeZNMDZbM2E#eSo3{qf%DFneEO61uMHce>K1W8Vb9Zk_ zolX5XVvyrhc(c?4R=FwbEG%c&7im&jYZ0MyIIqD6JUK=IzEmH@oWT_3O7vb3Qy6%; zyr3sK-MScTQ6D+Fg7}<2u2Z7Nt#GUA(0};&!?L!-N4M{LfJ7$^kaWpc#bw@>ExC;8 z4xl>f>HNvfV9TXJ;VFnvRhdTXUM=I`?S{rq;Zu&{&mZkU6}5HgtY8JL0~@61ruli0s9H$Y=cwt5tEKz zb(6+wR61ByK7@x7r+GF@^_SJh87tpNm-PW!DAx~%5mcn}h%nG$Hm^#Eop2VpL2Gv% zHaTTNLraT5H_PD2bq&&BfozY?&Bru$5sKg@H&H;6MBM?fCj1 z{xAObQu$D}9vU9qjMH>}4UZwaRU@-eQ*Y6E>hCC|Pt?QYIJo-3`y@zw@gMRS#%YCC zzea=6?8**9ADrjLsC>YXKQy_<@qvcR;=%xg9;Y9=vAcbL2MsXp23lN`^bMG|1aPU8 zeVl3%Pr#GDc)5byE)PK0M&I&NeY9M+(*%I)B^fRHcgX|X@`KL+H|~Gi-SQ>)R(9j= z<>(hndbkz0;4WOBw!maM;uyuF>WE)i&mjJ?>lK>@|uD%@|#U z+wq3>HhvQA0OU2|uS8o%6ZwqhkIQNWPf*O>}Wo1?>+AomUpb+Soub~OpcfV|>Tyc>-R%Ltk}FBe~>omU*13@b?&3O|ei2pIPgiu@z$( zjxs#h-Stiz#$jG?klcO|QgLJ~sq#*`nOo51qbL*sOJD%c(a3+#MPs;VhQQ2HwDvuv-JI=#{Jui^HV0^5wo^+QUUdq19 zae3z&$9bXTx_tAKPs(rq*559__UnJ6yq3b*b>yQn<&R#_v3KBHG5M`>@|y2Kvk-Z# zd^s)qyD!U+e)OZVulP_IFMpFR76~{K^CP8!mmmG2@cFsQ!KKUI!-tQ{U;k@=qkQX= zZ+lUZBmB-TZp!gFCJPtRiF89*q~Fg!|I#PQ zY;A9sU;N(p$}j%HC*HC2=YRQW`SD-;rOM*D$L{ABugmjSyXEDpeZ@Xi*0!FMrPZx+ ze{Mnf%?_s}@z^XIEKaLVNdSM-jPKM@j+gm9*2;=^cugrk_Fp~s@utY)BT>bN<008K z$Z-=7)NvNi*y%+LrmVt~BmXFaltnKpOOEB`)v~>{?VXg2&6%eF*mcQV z%I?mtk2LhWMBmw#nlhKbyaIKN1u1k+-QY-3WMAPMTncxiGS4^Um*i&A4m~0VJ47k> zE6cnH%VOANIXpQlJBJrC^PN8AUQrvu@u{>MeCv$w0xC(aUz9<&8@z<8`bfI`%`2yq zx|Vv3jJToa<#y(T$OCr%Q6^~@IOdSWbjmns0S7-H{QUB4nfG)0q9Ewu$HCde#BVn-j zuF7wS5Hx;681ewd-9va+e526h9MGemcfeiozDu4-5PIj#JD~SBcf!;<@>O7(uO@p> zKu>=)W?A_9-9MD{N))98sP;BlmITYJ1{N2lbkTYmhtEUSxX$gWR;dz_%8TOg32mtI z7C$$IlS#PNYGe|xGQt~sy~o6(+E5JPDmWz0O6Hg`jjkSqQNw2m{h*0-_U<5lMm4;n z6)lCpvUW((#NE>9o2>B-e`Ja0z#OJkf<_ZfX6eb{ghNNhVLF7hzTZk|mBzbW)G+WC1s}AeW7KvA`8!!Muk|p2*V*ZLIXXJ@ zF#_kZ^YDd<`fL%f%9yyKLy)M&nzus8&$y!#P$mq{w&1Nd*Dzs1v2ROlnH zvq3}k^+k60MNPqT3B2QolEDLfz{g=6K5mDFM~48&W73%iP0E*`>Y+wqXl1F1%m9{$ z4ht^m{^F8BmLBH%kvGus7TJP2nLPN-QZjI?9{I`fgLF7{HBkBg{>y(^{^>vcr|MjA z3S(FM zKu8u^VKyT@@rF;CN~e&H%^S5hJ_1oO@-42pc@~B46~1dmXL3#*zZs4~5ifMfLZ8n# z_i-Cn4$B~ua!C2kfKh1^Zk~==?Udcu0IlsFd#gG@=f~wjN#gBBcF&z29hKAL6UW6H zpS*3!x3^f3$|9Hss0!<2KGaF({CNgOEXI)!bZR-aA>}*yih~Z??4kw}OB%GR&N4`x zU*bd3l9{vc^`nk?kV@{8x#(UzSma;3o$8MLO(>4%R$E~`r` zWrnwB-%@WyNIJ<(E&?DM9Q;pt1C1qb6X6B{)cWI}Nm5>AnnE%VMZ#s3Spm~KKxJ&F+^{jB zEGnaEukq`t9k)zeCPhGeg)|K}+4zWVWJKbgEP<;&VvRlsgUQWwA%-gX#)2>QE~EgO zgy-gGrBP!v{DtVTLewywzJN}T+#JCE<_)?+Yu}PS2M}}!nGPt3pXC#D-nxPt(v3(b zyY9}X&;vEvnwCJMulEG3AbvuCsw9S%-jFupc;XIk+f;_(VXuJv8YQiz<5Q+MU4)a_ z%4;}40FQ(sJSfUN_V)cPmq+|e3yEZu+kU3E4+O#4#5VK~kUICLK$@nnFZRV0b31{i zRNaEBKA0l8v6A-eIM|RU;GK9 zr;wkAJ#G>Y;466xM)K2jVvxoteZU9%kS}Jlw_FO`Rfg`8HN54=-!!_!uHl9-8h;?7 zjuIwqV>mm9w1moob2;ash(DNOI;2ZbbH1QAK_KrjrDQdi3X=%Q-2vzZ;)Rm`T&}tjN_q>(< zbo>krKd!$vvDEOR5>QTW>k4Qx+=d=MN;8yYoM-a`&+~~1SKL!&c7D06ZagX*4?ijo zo_y%z>iiO!#tAIA(649Q!DK5tJ&uo$y|A*Rem0ZPybNa=;owOhoA3Pc%`6s&m~>_F z>|Fh44RO4agmD2Up0EJL+xyp-7iCuTi*s{c_+p`jaK|Sn8hdEWGQ%-xt*@_VfW|lI zp0Nx&$k0Q3k&Q(MFEDt*T4N!FX%oThnxOB^7>3DRE-!A09}6zD`6Rde2z-M%Y>P$U?QIv z39r4-#SxV37HW%UyvRAFIz=A6(Ku>K`kz)`eQAECJbm)8eD}NGDi0Z(YAosrew7pS z$9Kwh4o=GFFLugjUpz0zryM_d=EaG>{@2*?^?fgJa$Mrc(Ls6f{CPPz*z@i_#<=VT zqWxmgi!`(23K^X*$`AB?3n+WachZgi{cShrLn-r%%jMTKmj3ttJO5sJ^!SO(#?70l za(aGK&NRm5RFfN}@85JdxxrH8jmimmaT`6Rc}^&8qA!=s4R#++*&V-Dg*4Y zLw650H_GcT>kP$|GIqs#g`t>atz|k++z9c*>3sqr(cwdD~(lWm&$9UG{_>Ud&5NUa14?yJN%l9yRrYwn(`6k^payyRd)ulbQ=(m8-z-}j$T3Ip zmzL1o8}Ah3Xv4j|U9~4i2`@Zz4a_s-1=jZB>XgU(%tz3svGB*70pFLS9cb6le5zZ>Lz_rD;Gg{b{XSi^Z7f##yMxpnrGYeaJR#*4{SelR=cL^A zj6*N8Fv@~H<-=`^=&0AsNoH4GXF02TU>};TKVh9HQcTjFFyT8MrkMbC=5EGu<8lxCEkjvIC%v%X zh&g%M0DJGM{DufY<2QsM4`AFqgm=X^3Qf)d{hzA7+iBHRs!NymIOOi^P>afB71;;@d(^l{So6Z^uz>{S z7TT6ZV;Y$qLmCIV1LQ}%M32+aJEitD!ccjHt^OoBRPAo4{sB4E0qc3=wuPJQ(I>Hy zu5bxWaL5IX{M0EREi{I_q4N0AV;?KWE*IXK0LXV_fe#N5+w`ZS=?_inA;sdwjqGfH zZVxwhy!b)lj@xTRo_N^J!=NE=n$hXaM_Fn3`34hj26^F&2SR6d@GeE9T3FO;GOjyU{_pZ-LHgXiWcA#`#6^Mz&S z?L8J;86eW(BV2Zkk{&*qT0eqHuTSYgkXmjzJFYvFGnR3s`}^oN8%)y>WI0la?p!mj~gZ2E2)I|AY0-N-ZPU+F4OM{NSSu{|wh zoxh#BTQD3>i8-}rjcKc&N#*MCp>{kj2Lz-Zh@cXgUU#QZG_hlqDH`(@m>)r^qxrP_ zApH&tkpOX;Ob#e;SV5DkL372w>Z2jKkXvR@_;s<@#Wk7ov|mVd3(i==+Mio^SCOhm zb;#}@K*im9zGJDpJ1OiSq}-K3T;QRBFLK5P&LLaen2nc+hKr4uF8B5gbiv~Czmvs5 zgM%n?+9z`20)f>5aS+;w1Tz5;eb^^JMGpM8WUj@H+RyLysl zV|54B=o{H?$y}kMQyw%sW+Mr% zrw4jmk8fcc4Bg{?z)+un?PFx`;t71Edn^v~mpcOl799yeth zF~QS!>bxhwq{S7W<0+%FE7Q}j8)ewXA877jr5i7ch9U0(1lO+HG9?{3-#o#evb z&I8kqkc)0Y+c4xwUt~zr$H4Polr~dXqc|Y(>T=*wKVaCFLEGB%2EB{^E3yoE+~x<2 z%kWh&LNDvY@OA7=p}99bUl!LNl@CAph4QU$f8RS-829FwEhbc@4-I7KhwmTk`Lq#^ zBWJ903lqXDtawZyMUiH{my_>giI>J2e%Y~(xA{glJ52z}OzNn{4vgV- zF_uqXg!&u3x5;LTLB<&>Yr3YTKXmI;D!d57k&9W#qmIFs@eMm(IChb-6Q{kLpPq`> zTQ4XO6>|!dX(s1cD9e#@jBQf(*g<32@K^e>6NJUgdZeSqckCYF$TmX>Yjdr9?|a`V-}%-z$|4IDl4oIF=}@`h<;9)7 z!}617FUn88cv)WU?w8Zk6EB*qtS*)9jScVIVWH{MAOCsz^7EfcjZ$5C-_2v8^7)IGKG_Am@e(#=3vK#XPvxQ8f2xs`;W90~dvRF!1&;dD z*q-@AXlVy{L6-Fl7E$@$)z0p&ckNM+sYfi7Qg4|zV19xHVahBgzO;oVzQYZkdZG+a zy;M0-IRp1_d%Jw}!GkhCGgWr?kG;bSKI~-N+*nb*-6%f3TX$0SkIvK{otf|4+>96T zsl&8k%sCN`g?BznLCIn6gG^_>fO!lrm{UGg2HH!k$VZz6PxDaSpSvt*_$@=WIiW7;&* zlzENBL43>;Hn;OmG!Cnac^ld)(!mSQEROTpoo<}%TkL7)($>I>;(!-r5q`)^+4Rc| z;ze504&Lt9kuJB5$jgGA!lFawKmCkArz$sma%Nj)mECW1v-iuR2YOCXrk{Q8jR0Br zLSA^1FOe18&;(Ch)fziO$sdZ)WnR`KHIK*nATuyr_>yOEnEV^9{Lm8s&X<2ZO*4ma z16@2-4gi1BiT-=qwD|z{&W_ng#$d>^LC-HR?jFL>5BobPYg_~R`mDSQ?uz$a@=SvF zqbF}_{&0PbI86KXM0y7d^Ydqe!BK}nxI)O@OiOD7xR^w0|FkD2Mh8|>4ExzIz@a~m2=E#c=M1@7*$f!N;f=QoHoTv z2am>?4iR{}(J2kKIx%#jy*-)Kl?ZTx_tWSr+!1lZzC#eV9mMayqN_f&cy!smuD}ZmE&XHY?5pmj4(JuhNY!B>5_#nzURe&hc}k;wjpU`v6XYA z{jetu)F0_5Tkr|S(FK%e-eO|M6(3W6>od$52+<+o_z@OrNuTS8ctcNz4qdU+j5p30 zL{jE+bOmoKs?+K7`j6c?U*nBYb;ze@pqEUl19U#U!;9lFq)$3dIp$FLq6k@J_Kq)^ zyjjRXBVGVnC(TQ%8oX_+`FwHoLGDaVX8^#09*QEZ3~mD|r{ZCM<-?75w~h+>a3@tV zP)}I!V&Q8|gNC{Lq%phX%%d(a(vmxl%Dc0h&KCWU7B^+7);uaiON(?1RSN=j+OUA* z2-f+KMHAUEAmCQZC6^a+Av9E?c*qo;4AN&*y#u7j(L$y+r7Z~8z`Dnu_Ry`2|MI# z(VkJzv>1)DO`rfNdk&qzGCBf+R(jCwDPo>HUtHd+tSt;cxKJ7rzDi(uWXDm3by4--{s}NLY;*oz;A2Y!TN4pHxUcJoFgu*zWMlYOirnd=HrWh&9Ae-F!*RYNwsCpBC zs76CU-#O%i4xC0YadKFY%^?3lJ@sq~`w-rPk5AH7hlj7IMQAV#IWqS4C@*%pTOzgWKgy+IN_($M^>bMd6Gpvjq{^VCd*j}%6P}~2O3{-B%v1v6sO0h3QRtL zXQ9IUiCTJRlALcV;U+&h%9111SPVEhJ}w8G9CLmy|LiWAo#j-J151*EY+gs9@#!V_s4<9@zPaZueOAGhQ{sD_$yBe?V`CCzp zS=oKV%aANYa_SA^LQYb7{rbu~ZG8Oa>&tR-xL3~4j+FlFHq*^{V?`<5F1;?ix{+@r zketI098TH0ml~xD0x(iRM@-U7n;v&VN_pj&Iu?caKGgNqMUMD9m)==Kb>3VkJm3C$ z>vH(fhaZ-2fAXF3gJ1g9^5DUfGPkhg;}iFf&&%cODKE~l@Nr50d13gq>JBf45-+Eq z9F+^{cz1WNyyQ4VzMrKr_Xm$3mf!e|-zeYx{x7MoI9I;-@>Ti#`Kz*baHKrBRFRSt z5_(p=*wyrKbEQ0a{6O|)=Yp!C)RY&jy`xa+r>>FDT!+f{)3X4{KsLWCkLA}C25tKD z1UFY2znAP%(m0&OV|G@0?#W|q)faRr{bC2wrr73hyFt$hEqgn=Svoo{Uq0V;JF~RBR5mu2m0xeXsEMqzb4yMS>4Puzmg5ll4jAR9eb#|C$?XPn z9Kw6SiA68wMe2N>UpS{cQvAf*IPql1Cgq8_78bO?a}k#E;1i+96UwQ=dErO-g)H7N zw!CbTcrCzsok8;5C3jHFl+g{kq_S8D!ubeVHY2}6lu#?IhxE6@0>g!`F3usHopCq40pNV`vl(c#!?;@qxc7ZyHdzs|+nfRW($R759K84+=sy4)Gr_9n(cwCO+sr9W(7MG4WvrFT z=?~u?2+acqoWi14rG*CoZ(MC{ZkLZfdRjKNw%jQqJ-oGG^4hUV{_qfh1)bQqTPK+g z9gR8G>aSRTOExzo;ro`HoP-hSw-vu@oDN;Bn(dgf^1Ne2VQ@~d`C z!jP?y`wbSwPe&vT54t8iw9QPIR^}a~^2d+-c4tC<&L@18mwxk6NIGh4@&EL*Ps?Xt zJX3xhDc>`2xn!Y7>0H);)qzBg)P$tvMezq5-D@A7hiU%(Ncr|j@j2lPhqq7Mdtghfs|PAn|nywN~K16+5SFXXTIcq0@#^gOdLUA8oM z-r8LE;Ed{YujxV#*Hxt*GjFP1E0{XG>TtVLsSdOCAa;2%K&JSsXq3g-h4S>_2W5MG zyDX{$?XvCW5M8SNi&~t86W%J1T<99NP3wJFPvS=JSyXBDy-~;?s+xyJ>V~`H5&}E| zk_UNBM`+hWoQ+1I2vp+>UC;)C$cP**7I0vyyRj0)nm}eL|2!Y#1Il3)XQ~h3b;YAI z2@4%{JZ*U+(53vcJb(#>YhkNlr@~E1X6w2^qmvn#c)kF+H+FI8vTmx=_$qg9ogbE@ zDF}F5X2Li_W#Ggr%U$}gPYY9hD^~a#&TR3+TQ=pdb=0M^h7GCR=4~4Mj53vJLTcXd zrH-|Gd{wIe2uj9<%A%X{+Ru!rjFy&**V~acyqr zKZQQdaXv#gc28=!oedC{JQ=4;xebi_4NU<1z$uUexzbq}frL{D7@-G14ANEMRy-}C z19+c&8Rs(&4d*iMdOAuoDGcyFbhl`@jO+C?kFxAPEi86AVrB}ZEbaKuHKY%qzRLsUGRC&$TsRL8WheaY@&7{0e-re8D(LN_Vg zZ5S`3UHzCKOw;|)>o)J^es{hCx8fG`vXA-&PkY<95zv5d?SCJ~xO*}T;~x*(n}Kov z{+ZLm1HTKVwf@04$R`xnZp`nXHWD`i2~wEDeF-1D6; zcBd$z-tD!#vZOHulf?9+Ih`X5J3b!$es)>0D8)-|z(e`>-nwu*}$0y~p&tH_iqm%UUStzO#s@HNeK4+}R0?N|jg2#ea)i!FYr+&BU>fI~4zEg|)V6`}FhpUve@gpV1hB1vq~nS$-MsS#6&5_6Zp3r!dhx zr?J_67MV1HVhqQ4g@recXUs<{{Y4M|h9FG^SGql{b=!V<{Ocx!j;TRb9rfENX0SY?Rd%j%Z^+Yqos!!K3os zPo8*@?dJ&;B0nu7B-WYiE^q|W&AZ6(1))o2YI}RTeDcY+$~Qj#hR5A2 z8k?RRAC^D=(T~cX{pcs<8m=;XYdUsDg2 zH03w#3gwA%P5I!PX3ux_%E94j$q|Emue-QBJbJWQK4jOJ>I!5lSCxuv{OC$peJ&E#Ync0S=(%IfM;`Tn;)EFXXHP`s|n7tddn zS9{0hQu#m|w6ri&jt*ZHj;#Fn!;k#!{wt;>R4$mSJ2*U+Jo^f(vA^m-7J--_s>gi_ z$4N_+0qD8NS1*JM{DQH{A@bgMzAF7n%d55rH;Yb$NjazOQPpx8RvSh+tYN6ngk#|h z9CWUil@Dzmb<^KJmyVEya4dXns2(EI!Ty0?96)c(CwdM@fSWdo7oB-2AKv&=E^@pr zJ4Caiwk>v1=13EDi5df7C%-(GLJ1RJbeT2}eN6jej)?StHVff6f) zD4**>zGQb;$w3)lrzFQ)hUrC_DHr9w+MT>`4zK=s-uQy+?E{lPCcI>3p{ef^^yVN; z1!%L_(dcCtE;w-+cNwDlb9g2{c*Y@A*69hW-OPSI19g?`4SJ7_!2U z4>0Z?0)FN+fyTHFEsMt0n9izsh+;At5KSxUo3fsKB^nxN3A^WFoU{P*`?*$<@))IO1EwJFGngqHu$S9sLL_ zw-EeU2&rjK`hp|1p#AoH<%ihd-6;``^(uRNfGQf{(2Lm!5=Y__Z4DC$&t`OVvb5AD zI~*gP)f>6!pi4#}cwl_^(Z}WC!v}uQ!3X)=pw}=?DmdbYRc*li)&?x)_Ct{en;L04 zJNUakR9;xwfkQ|Az8>Io9CCafZ#krKrULPEr20pW{tB=9HkTgMJ9~TO)yo%t6ORWg z4`6heg&}m>${Vp;19G8X_{h&?8H)V)BZu=l9u){rI49kF0EfXYp{%F4pzQ9whi()V z`{?k>^|?uzuAkLstwaEU*0YK!&Cc8embGMt{vrhrneVq)ozOP1?N( z1}DlSZj}`lPr&gICXNJ8z5~g7dQ`|m%*dDrnBS(+1AI@Nl9#Vuc=rsaO!k1Fuu}&fleL#*xf~> z)DvXV-?H-dqX$msl2IMGZs7~rl>SW(p0^)tm3eh|mCa?!$0?HEyuBr|H`1$g&f9Mc zyy>LT!D1ns<14)o>V%NT(vSG_-Lkpqx$x1ipJZ6Ve#Q-q>Xqse>kN5gCcU6#+Yiz8Cflb z(E!xVW~)e=+y?CCC9n=Evs(ULSO)3vA`CS41B+Yty0{j0n319j$<20IlCbI#yq#fD z@i4L$W%m5=ObT1zxGj&v2M4pzCq-R+aSh_Cyk&P@xUmQDtak9tUikzQIpS0KVq+(j z%4gF+M?;zfamx-L^S%Q@UXALga(DVw_;9G{#NT%5&bq)!M5343FQ6%0M?L`-d;n_!cg6GylwTGX0@tlLUv9t#bL}D2RHJGl+Q1xp0amlR! z#s*aZE)5~O49g;fLvI(A?wZIPh$a zY`y=e&fs0Gf}YP0`0;DzcpO8(Z&Drx?h4!UwiNH+-vcyv%kot`?BAX@HGcYs z?qAEvgyZtcn)=XB$^%_%8xPCM#-lRLi(XUHg+(qFssQ@zj0-#wtA4ab9_rK26plOO z*fLIXppQ@A+7r2LETxDvMDawoy5{Be)n#5}ySWzKblF&2E{`@>HD)*}|KeZ$>vDE} zRn|2|=X*(IYOe6A+U3>ja>Zhs;)N%>LHJG>{gm^It8#X6Q7$|=oXKyFP+ZnHg9QTe ziHUv2%Z#BZzuxswW#-5}cBafsYs@48J^6ZhRgMmh%IWD@nVDNCOY58E-pqVCIlU~0 zN5^IF@TeRfa%A4I7l|_d*H}V&;wVOc??^7jWY>OyFE2ErJC0D}h%!%P>mrXNk}jFb zD|SOMX-{1u=ji)nf?jfpx4*CKlVkWc7`xdtmJtu0Pu@YHA0>?ZWsJsx*V590ci=G2 zWPy;=FyIY6#h9Zh8NYEfBK<+WbIh2KiEzfhIdy|?dvV$f3oBC^e@2G2l|_F8>>D3F zDG#^TT&7suI8i=cTql266k#!CUphNc-t*lm?;=tfXO;M+h1s&QqH*V&i*mI4MLF1c zUQVUgoxOvyUnlliC{s;voKGG<_IIT&7}H6wOxz!^sHbtKkF)eZPO~E<(K8zvoFhE{NyJ^S}QXP zt18=D<)e?jS)P3Gp^r{v%&t+m$|rL?H`3i3>FwGtJF{Rhr*gNpLjEn3)#WVs?n~BB zzkJ~%{U{&ICvXht(%gNQdybZ50cZE{q`cUrte&~No}Qg}A(e01b5hFk{B&8Aym_Hk z`Nf!Ab&N${UT&QxZx)yQNdfqi=afs1!emb4i!YveXDH>l?JnZE!Q$`s)^_>egQpso z^Bq5SBWfHkx)WXOGGiwX^^}Ebj!w+NR~DBDj~*E-!xx#DFCd?Jf%cmpJ}lq;#s@x4 zW=G}Y^DlRl)>GFl@_K%DO1hdaPakcShYz+@YO+vA3&>Hd&tB}6-MvHa&f|q;<^U|u z(vla3Sg2-^I(0KIWFup%W0WJ;W$FXvPZxBqf0R3gqb+j#OFJl&x(M)+Fy#h%F4EW* za@(%bq@8w}`6d?7)pn?U-Y8D$0d-(&bE~YZt}3rieVioU-Gd+HBa2^Z_oOq|cfzS1 z;%P@*@aMt~q;Jdg26G~!ReZxfI{v)ukakAtqR|j|zD)8#OBr%Hm^*@*FOn)+{*@o5 zFWIdFV{-~m7QbdZU*ngQq7GC*;=+*Teg!>)p`u^k;`| z;md_ZS3hw>1tY`a<6;N&6Myv#}07S z@Z>MQG*+49545z^Kuu;F3E%iRwVfRclOIe>XQ3}|2s(sWbQ47h0NVOOFW}sKn@|@} zX##RMd?Vl@waEWQ9l(|H!IQ`8czjeAm$U8r+7F`SwdEwOxbm-V3^njPJi<;70d^v> zpq7UOspeso_K|L{Ko0>r4|%W(@q$&}Oj6LRdlxgh);(UOdI82O}yfCbT%Ce*7C48=K;D(CQwA@T`A1+YcepxsxFGjXDT)rr-^pBP-zJjtm0`ndBKCvOVUA z2X)eUBae;&=X9@auIoXsj;zAN4}(P?%7_Ac;p^q@tMa)z&Idip3qgCECY%*@VPj--j>HnJt3 zbW_TlcaoPk0O{m$tO8r^>C8G`R7cKFPQ5dcV>j4g$y;SC)X@o^;iyA8W)h5rEWb^4 zl{~f{^yAnFY#g2h77Tu38Y!0jzO%6+8yljrU5}1%Xb^&De3$Dd$ zI_o@E1Wq4CX2rKOv?Ox$Dc{P&j)%$O2;k;Qb?U(kcos$OrbCm630O07M(FY%oGA<) zO{%SZtY?1kFajP;AMrP>+j==%wD{4M6F_cgAcCTnJ^NH1aR^KkG=c-{<>=^w`qVAi56qI3M6P&XP}z^DgN9Fk`=qegrS8+d(ejn-9-}V8`eML-(C= zyhl9&f*aS_`-Xl0G7Qfl{p~!89Jk?JJX^RSjJokRMp1Y5U(ZI$r59R+V>0=k`nof7 zi{AOQvHeu$gR-%??L{#bT1Xlb=}c~3-tbKvzGMB?J5e|;Zf%WYshE^k%9KvV4IH7x zg!PR~<_;L=tcqr3VbP0IjGO&^8jU{ImuAc1-cI=k|M!1TKKtqC<>`kXm5)F9c6spl zBQJn4>3V+kx*W4$cExTcjs(k#ed&w$^%psr7@nWcqMW=vR`le%#sQ3byfZ=`EPQ#v z&Wm?UTvHz3`g_C2hsPSbDV>UoMXyT@JJ{jE_pH3gqA`!Zv7_+|JHMDP_AV&_FEIj~ zkinROmj}_i7n-DR7LS}a%&EBCV3(va+&bdM2=$+-EW8^i=7%zVb;J?55+p;}jQ9KFh)) zA)j%KG}c(mU;iFTNdwY|#2UTPJ7b@QCl2 zan#{kjZ;}DoG#0Y(`9>op*&bs`d(j_!;_=(+2>!DpZ@fD`SSToAQG2i84k(T2uvwM#h zq$me`6K_U1pYC#BX;K={;q#q?@=E29JZ4dV?;&lis}3$^$CJOir8K?RKPu054wYxe z8jl})SK9nyj=!YLo*wSIZ1A$HB6q#=Vl4|`iksyV$_vL_vdGOMDBo{8P&gKS&sA$HKk|LRCAAIAA-pX|sza0?AB(uO=rWD&{HX)xHUxb4%5xDa zceEeuZlf(>;f0-=`Q;I3a0CR%0HEjWmmx&)g zer)-ulSitX=#X%fE9Rh(i8}7ZFX@k_hB(l9TS)g|9gX zUY>bfW>|Moa z3txZmM^bkh3fJMm%!Bg*m+?t@4}?fzgWTCGB6nonITVG%!6?+Ow))!>z*#GOkA~6= zZ4<-zKw#hcgSnv5HanaUp>HJOXQ(*9VpX=D+`(p6v73^A=NBInF~G4sE+B5Xhy&&l z+nq`pt$`4!pP@@=F4;T&fKq`Dg-$wpolx0HU&3=u0CLpiH64VGVQ5JTj|$cL76FBC z<$yOio~q;bL>-g0wRJcC@N5ly#1KYiCc0#IJA<7+`4NA|FX4Frcya+ zpugI4+etSaP9DBA^0>`Q;B*j!Oi=!?sPv5-ltV9g=pn%337zg;b@28N_Vqx!QO78Y z8n#u>GDT@1TaQE4UjK5{8Iiy*ZeR|uN&TN@Bs-nhp$)gGP?+( zllVZRJ38g(&Vl^Z!0;eO9}Zf>!mpJ{rxPojpz*EOMe1=EP`VerE@Eea!y$#|;f)`` zIiA9uIOLF>g&OB8-twn&Uj#dCj@SFxoWs53+7k~hT`)hVBurGpfCNiQ8O50KR1 z_kcqt(=&1xeG&sO$uBgr=7m!G8DW_>C_XzN*#vI0Qc{?|??z>VjQ* z=2)>6e;3?}XW+(mJFME{in8C(PW#u{Z^H<0*;BWx-G!&oMocI%HGn%oH$9ff{Em@#O$q2Hvkga2s#p9BLQ zm1bP0fyweU!0)yUa@UIHu#&!v-dd5VVZUUjayI0;)L-`R%$#szpzv` zx3<);{-A6<`mn5TKJe}o`tMU3yD%Zin1cQ_$Ca@ggoP#+d_10!ACuJwC+Fo*{dSIS zV*++oiXA!EWm#jGn~T%(&;Qx~r~I>j{?9$$SzcW)Pe1yG=(iPz z;+>f*ucuh_Vc|f1AmmqkJbT$Svbeb59Z)ywoL{Q{&dYO*=e(Osa`HU(G3{5^p2Vep zp9x3Cgt}Kl|VbKe03|&1j zE%_NQbBrP9Z;O?g2%@L2tgMn-ST{LFpReem>Y+1`FA8Rwk7HqoB(*gfefJLfp6 z5|xlg%L{X5Yi+(f-k2+^3%r1MQ}`Cs-r+_0^5uTn=R4Qp{$k z>6=q7*x^UR%_8pQ<(bC7S7m8&&hk8Z{K(&+V!`Iwb3S$OOuTQ(>G_q9L&PMHJa?e7 z$b1lEYj&OSGAuie7UrkR`s#dHnpJt_duS?8EIuEeU6q}~6Yp5!+h3FgzE6gXD+;r$ zarLxhWMOD+bF0iPt(Ak*3m*f>QHOlW;H}CKi=`}9@#&0{qeJIC3oTh}QU2621pj%B zkvYPWvAYyn_ILNn&d!eVPjX3q<_^42OPN(ZurNm3fFEU)?}abwnp0V2@oQmzQS@&L zM?NakTpp|Z7eU82OBG8ZF$M{n0DsNm%Cn= z=2RWzSWsEs+E^Z?oVk}9wGW4)eYtl~PEJ(MS#(oclw|853uG+*(8f^~ zIC}7nU+zUd7Us|oyTJScvEuX5hcZ2`mz>mHE^veaC~KbAlR2d_NIhd0W{Xn=kH6bf z%22+S#nGAB-H9*lE^)D#&ykWWO5R9*c72_xUQw=CJYum3eX)~|op!XxSxnD!5Pm*p zQTaq-UcaVI%bW%?2yH%#x{bWbC_g9AQ%hfH+#(c=Y!ld zu9%K9{3C<#{Kvu#O@6(-_X8R~po^=f%ls8@^c4BsC<{9N13O@Q?=-}J3@HFV4BP7= zFtj%?r%8Bl9Xk3MAnt@oyoT^q{te!jE|Bs@h_4r}hgKf`YA~w*p9NU>y8pNS)_?dr z6fG7!kjn|vFC7f*Dm>o0(F&P;e*`$A#7<)@*> zg|4a}dgI~;UtO}qElS%#*`>R~S3C6XZK@)NSQq?+GLP7~A{h`)cFE%A0p-`Q2Fsd@ z{KHCxrenCZwdt+b8=IT%fWe8-BivzyUC53#oFa(b_$3O`p~hVgMjnnd^fcToFeJ;- z31Q?<0O8ZwX7U_)tw;#XI0N%MMD$#-+z7$LhfZlaOuPxi8+Yg4WkUxg<(v2=CoG7W zd_@S`+|H4$7Elh_@}66OO^m(t2OlfE)Jn(I7V~L~Dw@}tghXv8okU3R! zdxVW{HGMY0TNU=Kv>|Ks#$i@Fcc)w7s;}HBYoRl$0*)vRy*6p{Y>-ctg~vHyEDXA< zVf9lTunhHTG(8SyaH*%VN-WxL`GyZNSGP%Yvs}%NsWKIjsXM`^Z8nQ)#vN3Uc4Im% zN@K@2ZvIaFuzVnoEy4L2&F(LP7;jO;M|Z;2cwz^iutCBh(E1hVyOj^~@zv}JXB=kZ zAthn$-Oymi)n7p8=RbN%U3GboY2A0>b03zQRt_3XleYDlkW+?&*k*@AR{#D7N;L88 zOMBJy$K0%A?pDO|ICn zYsFpN6+z9P#rrweqNR!*G4r zaj3jHnsFJ%VKSeDAJ$=T4Ns3@fL9!EH5Ph(eO}Iv_shZlZaF$SC}*b{gIt{HnRip> zH4b3HoyCBqMf&vY4$4vDUPMt}n(;Q1#q{A>U||Oh-$UXULyo@Vh%vs~bFMK0iy$0h z$Rftp#+G;UJbwI0jmJXE%V%Gd-B&METHciPwI#p2cEz`jHP&G4Mk@G@Fk^t5 z*Y~`0hn+Eu&%F4>*hpg##vzPPcrlN7+3Cc$hELBf%fZp9kB-~jKQ6C!_RI4ZJLSdB zPTAW(@;Ahw<=a1u^U!q0SGvTTF;?nK$}@2~-#yMiI_Z||(}RJq9?$wAQ7_rskG>GP zW5H==Cf`+Nk{W%m=$LN+u{bqfW|Urbv$RQZWMkau1ucyo{o*EZN(Q21lHNPKIBrmR z!C2PgBahu~%H{c)^7`1PV;mhFmSbHkj+~vHh~~BOo9~6Kcw$|GWGtu@`Pr%Q5er9$ z$0yR?p0C~g122?t6H#xP(+u~vgqFW`%x@jo$9){WWpTTve2`*xaSioN7j+@ z|MW~@RVG+G;HbM3ne0wGI6Cupzjj4?cBy=uo-gx@t7Tz%wJa{LmF2aKvLL?T?#qww zNwGWe^0mgpk-nlrhsf4>DiC+yY~F zmuBDm7vwp?SfBVLjKf09@siXV_<2r+xd4Yy0#%1RCn32pQ>RqV-1cyk<5F4S_&bmH zvp~Y46zvN05E-lIJAe2v@+72QBb9(sq^G+-hF>AxxU*>k0Q}WOB zsqe^a7V?8n7LCFOpnpIZ^B^x3SY+{2TjIP>TS`8$h`+eNXIS{Y8H-1$;v@@2#CN5-LR$QtK`!)1+n_XMuBXN*S&$onsk`VH*=aAbFqU=<3PM22 zLY;BC{6e)Zw{y_)gNOj8uNG45DC5T3(%c|EHLN__+zck;s2M$6STNmx@<_d(G}sL z?KRi&7}_yo9fA1Y_5k0)HW<3c{Qz^Cga_B58{gY><1mTW5WdR4!TZvU=#cBZ!;Qkv z8g3MB>;LP*|KlJ0-~R6X-}W5m<*(G=Ha%wvRocNdR)H+w16jb>Ef!JS>y+MV;v7n;=khjTp!a7ee8{aA2W%!}WLsz{79*$m6aO2N{$7?Uvu&8pT z&LVHYkPaU7@OSzhC#GVqyq!nZCuvN)rV{_W#gCo?;SmbL@RLOsHq6-kuXNTIvc_V3 zj>fdF4c|$Z(-)kXaN#9-ztumu+G0xAiNGzpI}`Xfo(`Wyucj{^;&gJ@9feyr%Wxz8 zgw`Tz;=J$yh1;eVcss{D1s~kMK*wrlaJJ(^GPR{_|)-$6AQf1ljkhNF#v7HbFdT4 zTk_>b78c_c)R~**%{e+Qq!}5iuJUnI25`I`srsTY{N!alpdT+vYCuZ|&YepG3wz?f zFrzEG)u>O%#UdVLESMo<^0Vq0eTjySJ9=rI9_Ub$xl1*((kUNw=FPL|sl4^)z*ePi z*1fSEF8blt>PPN^iVH>KRp}FJbxTJzQ1b^m!B0JNs~%&IFwwc2B}r9XPBnXpJzwlLa%B_Om}>J3oPW zB~o}*q|@xm0Lpyh*QKe`M%9O)QS@xEG&=Cuo3^+h3H`8~ggf`Rxm91&+s_DyoOv68S?w-lvA1x<`POBm#eo@`zSB_3AODk|-@@0g{>Fd5Tli|=^fW*` zr zH9kGB_rnd%*mK2guYq50ANm7B8sIKB7k!BiH$i@`A+EtKKg>?nTyP$`o6<*d0j$BL z!nvPo`yh^bg$q>>no<1F-L3?;ELmB+{Au;cF5cNpRVn7M|2HP#Uvm$9`R^yL9uqe=Nl zc!7fCnVPFgVOqD}#?{!Wo2$WB;VeVtSADA)7}B<96fnf+svZuXYv^y>@PQ|py%5s* z$-u;ETdfCD#|WQJF#_D<*BHLHwzwK#pL`ADv7rKepHq>9+tU#}=z zR(1~98FS`|Z>1`W3$ypV%Z#J47~`?{!;T|%`}q4c>hF7Ot#J%5mlXz*jvjPVtd;Ed-yPMjAX zjmvOTE4*Vz&C9Ixw5#tR2G&bllUryo(LzcEG97Tf*#pr z!U7Asu=Wp*R9^Vj)JZu#)i_%EVkZha>O7{ty!K)jdA56STK104RhBfCyg%bf{Dt}Z zJ`QtriOKJ&vNShU7FCqib$htJQl36};DrLxh@L6enR8Lc&HXYK6E&7o`C^yM^3uF_ zDDr|R<7M=ni!pRt1X8(?>7(;CmSoY$3yv}wYZC`MU|4Km;g&K)+HZ8RyX)}esvI4& zlj+9e+EvB*@BzEeHp)YGJ#KH5jg8f^wmheDsj@lywoJbf{n>swIov6SyDya&7xG_J zK5EQ9{N-Q#W%=^ii*j#zp)9U#m-E-tW%r0hL>4$z zW~*#0G#{Ph+uO>JELTLYeg3iSmqc!%N&t%G=e|W$(h{DAIWez_-I#Xu+Rw3oLr0 zJIYqQd_<=7!j3P--n6%#qtNe0{Ml7RJLsbw{c^7IiTD+YddJwl)dSaC>HWTFnC~Gk zz4)Q9tCEjz%dr54n>hf=DQRR%g*^0vyt1CMOZoDSve#;JT-Gjg>W%9jFFmRJOJMw& zE8_DOnM-;t7H@qt>#XV#^Eb>5vD3>hJwu}iEi-i*xi#Rx&GXg*s66D^m-46>9S0Y6 zl^2jRpTT0N(x`gLZnu?{Wu@!B+aeZ+i8IH|PPyzZvH(avseCLf^6j;^%4^9aUajqM zn?o4qF?oWlk++U{C)ZEae zeX*PWUEwNyv)fhufN}q%N%_>!9c?cgFkL6}Q_@4a7;b#pu3b*zDb%BMidw=ks{C$@hN)DD=`2j^A>qz0;pEBBaf*a=;6-FCNbq(Kc7I2RIQ5XG zGf4-Wi#Md6J$qJOzS@-^Thck^frmtUDsaK0mIrKjpt+|g;?SVAwNhcBHdbf$ze$jU-l{9*3S7#(qS3>>$4 zMrQ^dWavrsJmgtqY1^&QGvVm)5e|{PphCw(VQ!?$Zm|j3WrufUp%X}MljbTbX?cq* zieLWDFCMI5twrkf8&1p~2UT26OJbs&hE4jsYEc@Agu^+yfcwR9s1$dTIB3@(w2oSm3IwD>14V?s{!hT_@5l}CS#69L{${D`Gx7S zzP;iPVoysS_c-E_0gHGg9u_lSmrKb==iccTf8HLPSK3-x#AHBBT3epaYmoP3i{mRE zYM?bQ`KD8*b!*QCD^oz3hqvWQQIHocxboU`gpmh+T+}P9t!_bwH^>m%FbEkw&;^~k zn7nK<2pHb7*b{5q4qef? z1(I$D4B)gOoxxl2w1vo!T1w#v8=Un4Zvqn9ju>WUnVUYi(LyGzHPsMRPYk&U4=yM< zqXS5~Gy)xOnaI{;j_)X~pyw?RovdYZ(*cL9hYFY=?VS>(LutxdA+g{OApwiWJ z+FK~oRjMjokfc-AE{R+rE5G+2{}HaA3;a+1*Z;>FE3$M}!?@cZl-omu$60BNvu!jS zZL43#kU0+H{NLrq-dxzDE-<>AF243_vejp5ui(HqU%+Li^(88d^BsptIH2K&zFj=F zkB4n(2*f`0AE(FNWQ`_(Ax+mWY9O!MJSMwGwIzI~N3*e~ag9jUQQd{U=O4n!@%7*G!i|I>I>|G{P2w4uC(}%fM{qZv9-v9RucEYTV%Xq1RStQ{&;GqN3-|1PKmi=^yEF5 zEPNfd(zMV+7{)gVI(@@tNL%B$9X{?ZUek@!2y-i+0^|Jh6zXyDpB%QqZJESpP$x0z zZ?mI^i8;P8#o`B(lXHtJWpQambXEX?$is+LVlC0_v|gAGw(LW|CUzWQgzFZl2UmVey!SG1!|M78Sw+@M4(KgRE}4HFn9kNHpTb zA_WU$mP6yPoK|wJvE8L)e(l9dF|&+9c_)P3biGocapQ7X(Ae@!dAfgeR-V7wEqi-Mk|m2EjQeLbE?k_SEvqZ@UNBi);N%gF zW0f?HuzdZRyw{lXic?y$8;vyZ+N$Ldk1XIyXEIp;a(+-RBx@D{@-irSjvh!8xx~&r zRLMBqFQwK65Ejt@#8-)FJC-!zC7IC_II%;1B;9EJ{pvTm$!`7r>8Uy zJ}p1|@sG+s`xpPJ>}WhZy|7m9&n<~o=Ip%c0`nj@3ePvdd1;fKkn@srDhrN`gQaui zVXk0CGJEj_wJUxfd&q7oRnFH}oZ7W6)Oehiu-Tc!A`^?@ z94E;FICDOPL1(VXiiddy(ntC6P9ynTDI<>gX5PgGS+BC6<2JpkiTqYL1{HI1FD);Y zwZ*xzwlwG6pS+k#Ie(#i|LGSm%l`hE#{ixuDI5!!lXqCmTvk}>67wG98?sRjSoER1 zunUx(qUecwK|O$GWofDK?K|cYSe#|2Dhpq!xA#1!NPVS(@S^`iveOmYfX??ErCj?8)UaIPaH@=Trs=|3>ACqdZsUUY9vN zPN@ceTp9TDluRr)t{!dC>66lU{V`_&j{&jAdP~;APY`6;4 zSUXgh9WFkdKRnbRS2ScD46FhghZ;X@;1!F!z*Tp5ui*IQ-&U053m=MAH|ZuX8Uj8R z36;b925(u+JMqB5H#JNq(cR5c9Jio`G$iJ*i%pF_9+n@AZq|A4cJdU!PQWrNq~%hw zuvgkJ_g~iB0c>qRVGIZ>0LM6xPpNbiDmv&7^uYe$$zylO*>Pg9ObkRsNg?9cyTZ^(R}-&1Naq(G0HQE?=WXru^3l(mbdE@iV(cQojV%vMJ(%!C z7RkjT1`A?5yx4I>=jG+Amt}Wn-*36hvGB!Wi5RrXMEZ~_&foyzuuGQFG7YujGfosn zH^1ClISGlWD~<;pdZ2>>0e*@fJ_0%}H+s+$7v7#6LpelaJ3$l%y&#Vp7SXD6!P_@} z&2E_~cCJ`@E?lesq*bX9h#j4FgDcnqJDoZ%V{|z)OBQ>U73P6vu+> z9PF3<)1z|1padH6;Vm)-J5wCrAzI2-I;?YLfrYPGYfF)2;DzkS>W&u?D<1E9Q`+hH zaC8J6vzb{9j3kfCpu(m@l$}(_#~V1j0f(;95uG}A!ZFC9)9UYNX%Ln2pGA7&LcaUz zu(9|{9Qbh_KHuJ=Q#Qvr;Of*O3vs`>so(ihCzORTI@<8Q&|vlAjGbgk8(E<=%`Hxs z^{r)h6p6zN0pz9ll4j}}vT`&EgBq$9+F8&*oo^XHYlKDBP2mYsR9uxa9LV~boj$5q1{ zHNxAH#jlacZeQK-4r)#h--oH&~atqp@7!Icgp zJkn1QrV_ee=b-SGzcayq*(Md(ao`QDb_`-A_iXYy|uh6`T} zlHWayyAksi4jAC@Pr7=uK|lEy80R&Kcf;94|J6>vBKV%?Eq?Y=m~lCp9Ygjk67yV7 zo&c1`5cDw4zri@({k3ZEGIT(L^|m~{yTLf$+wOPEh!i7XWW9@LUp@olbnbhh$La=# zG_E)G8p7Rf%-(ODuE8X{Lr$U>&iGn)t)DTn(fEh%QF{aT1t!34J}HORpHP_4)FLBcXE+>Trf^Kq# zW|X$#q{pV(W`1>kjq|E*quv#EvLAqdi+>c9hmx_2&qTB{ck}8YG{drT7mV{uE$wmm zhh{YIC&By3W*wVMe2vkAR1Y~X2F%QOA&QB1zB{$5@%GBvMwwq)E(=TQo6jtidwicu z{cGQDR@XchJ3G55r|cfOep@bhAy4C*bK#iCKD)T|n2*J_jTOnZvLbosmF6jr zsR`=|a%eQBT3u#=MSdE89ULC}_&y)W$il$|yLi|^l9%#^&kH7*S>S0e7y_vismsXl z)-O=9D8%G?#%8S##QcHvqp`e?^PA?SM0RK8#a6~<9zTkXqx!FuuIuZZK!Th8TaH5% zo#OSxyY!0L7QQlRM?Gd{LVg+>F(^`UEd#Q+?5QpF*jePBC>O9mzzd3tOMF{srL3(k zdvcm|v5V&DSYxz0v2H#}Gja3$CpNy_MA|rpjU7XziFjOBq$8(a^7-XQh4t7~dg4e+ z#*L4*H_9hZAA0xElsfn9wmLdt2i~>Ey^Q}@z&MZ`99`%+GV${QsK%hP8oROpwxBUB zx)2lllTH?1Sp;I5hT{m?k@)(}J(nZ;$>_nSoH$>Z>rj4Lx6}#de(0k}X40;U^1}{8 z7V5~4H_BIuCi$Y9*%{HlzAT^p#h;gd`X~RmeEI5CdHBIc<$M2)UnvitJe5CbQ90kI2_c>Vo7bS^1bK%joCtgZPQeJmuA zKKLRRyM|_^2dP{2hBB!#JVSr0)Loi{0|YGsz4sa~Z1d?Dk^U;kES6H|)r7 z76xE0|lw?A77Ry(bvjd9-J%2OnJQwAgX3%w37Y>(W*_h8^ zCmVq5p5M@q`odg(fmr!$xcah#N~S?4j|8*^PgJ5}0P z{7PB%LY8QUPdn;o>k9yW*^Qs@(4!WByns(y$ixRtv-^_W^&Olp>Lz7lS?%HMhj=(ri;4a)SEr2;qplx8k&b#Hu z-SiEf9!>?2F*$a)PyS%qM>?a(gJ@f zDgt1S9}p)lx#b@$_G%g`H&_XU%UvA2d6)}R*$QYBfF9Q-xlA663tV#n-CzaT5z*GDxeMm=&POt5}`K1fF=yVg_ zWmvjKkKXyH^pWqp8ODw-(mTJX0hHf3;z$I^>r49A#qoxG4EJ1}&CB!aa(-F|oXHA> zn=Y%{=_t<3v7?Ogq4fG_Lh6$`ZQ^&M&bp7Vl-@|ooCdzUkxD1ac?U!3(ruQ)6Ze!H z+nZbEgNIMb+VZLf3F7J8LO+nTGC>)ZhGos7KH9dSTP=6;k6V`j+0bK~V5iJ?1o7l= z0NY%|Z!!Tg5Dp*L1N(-ul7x5lGnl|J+ext`KXBPg_uki12?o5~UI`CM39eOEAYT)V z^0suMPguN%yu&xHdLuk>;C4b=CA6n5netD1ZH59nJ=H3|q^)6a3-~P9Fb3e9a_q|+5wo+2Dnp?Of_7`n8pJxX4Y`TtvZ7>m{{t5y{7ZZO6=x>xKb@T829Cv*EPyaW+t7eNF8-^Avf@h@L;To)0kO+aP_z9vq*{#t#^V zYw?Z4czok=_3qH!?H@p@AP3}bA5Jo|?<)gRmdJ){|>4~*l+b=Y87_MoyvEiP1Qe8mj`r*O~@0lHQ~U|)P!mA*i<}W)3ER2J;|@HQ{#|6|0wiyz2B&Af!lfDCVU)M z&G9yFNH2@{k;LOQ;ps!L0Kto{Koon`Q(#t_)`T;=<}_pgM*`TtnmZO5R5aJaA&cEBjGRAZ|4X@CcBT1 z>+Tf!F`>~&eZr5Iu>bIB%`n6Xk;f2PWvH~coyfy#S0AzuN61n z8De1|`3Mo?Sbx7vt{W!k6^=zK#*FA@d1b*15lc%;3ODVAD0ZkI4{2heKRStC+6gb_ zJ1cplAL3K56Y9r+sebmvb(!q zUcTJ%A_SkYSXx=}ceajC&g;UIbnb;T^*J@ZW1((dWzM?=6)$pro2=+6hDqT^f&vIX4(z#KK4_xL+@{bp+{ZJ53vA8dqw#|HuQCP zc<7yu$i*BTdF3NTRgS5Sm4&pg@xN~xo`LYDJs}>-U#r8+)iI~DpmMsgx#<@O z;6=Tn9YWr`bo^R+f8#~qCyzGDw?Fx~Y;A6ogTo^)e!bc~avoh?W)6yWgj&t1JXdb7 zGT%g;=$Y?^u~V1&adCN}^c`ewNAZ!z*NRV~b)Y2p=6)}ZT2@_VWq~z%%_6qyxlHQ1 z!$BcBQ_8HY46ci`70M?T+1FG?+1)nt_PWd!+Nw+EA;5TxD{W?r8%woYth6^qSO1u4 zms;NR`0#c8uF(4vPvS!t!*D}BxMyn*?<*s;FKlEUHaKo^D zv8nX-!^thsFIpr_{>>j7VS0B`6u>6QI{%@MV;2HklgXFeq3QE5m6plu)nz^K>!KGA zwe}!#=Ug;gfbX)WQKnOfpX~h9*)d(E=Sp9-Hu&oF>v0f&d8E5oY3X1Jnv4;U0g;?s zvNQR{&m;h>JU|i_Ir&Kz7BKR*#_aO-Y-1*wRVO;v3PW`0A$&CXR>> zSHy`98wA(g^b-aectOza_O3j16T9%lg8JkS-ks;_=cgce!h)6(c<|Hl21gq5;HPuQ zqK6*JGW{lz(oXm+)QF}o3KE{TaxlHPBVKJm3wL+sIkNH4#b1097h&kgOE$zaUHr)) zWU~Gpmmb8TLm#a}j=$>+rY_2UE0;-f;`M{g%rXdo3*n&wZIHq&M&+HdoNz3{(n&ef z0OwqtTej%?4LVUed@W4q9Q`3bi)pj!$bi2=N2F8!lvh4>OL*!BogF$ue0$5gy6!Uw zWRN7DV$M+mlqsY|Hr^WYAc(hz#E^VpR~Fy);*C6XNCzD-t-{k`w4%h%yB?J`;&0#o zB9GA-i)p-RX};tI>5!{+5ZgD`cx#Je5dg|LKxcAJonbnq@PJ?9lfKcbbYv~5u9|O6 ziwBjalZ?)Gl?@ou22_)Jlp`VLHR#G)VaSzoP=WXaX+3d+;%0RG{cmP2+g({|S;F4H zVaNwN^h=)f5W7(o4HZ@-qf9n4&{<;D)#M3lm+rXnk-MbcF9Yd~+C!x(KllOTTnRaL;N(HSAL z$=4Ve9b-suy;28o29Mo-_1E!{ zm|4g*B0u4qn(+DKfAS|k*Kd3^nSscKEHTHSqZ^u7Yne%21e&cgKQa4Vr($ z4b5h^#v0x??h$5$4tpobs9$gI^Kgi7Zi3s*&o~NePgAK34Oi9D)6{DmH*^mneK+x` zm9ndoA{)}jZEJ@E8cj!6W$$QYq+il#ZS80}I)UvKhcxj=p6b`(WQO4Y7dz109c}dr zua>^iu)|AOU*q(>f8*KH1i_W^($P8#Wv^`-FycSvo`h=w(PN7Xd~_7rh656=$t`!2 zVQ^JKZgCI%jJ9`;4;p^8tndSuu%dDH)<6|T!dAZ4jr|5VU1065W}xE6u0VJPhud5$ zuHk!}ZXFF*>nHd8aK=3vw#SEv%Se2Cyr84YzoT=l!cX}hYv`)?7%rC^YvcR07$0md zaQr$y$25RO57aOfhCCB?6vqAAHR`8lX=7_I-6~BG$@|eO09oTV35N0YVS9QOTSzVW z=)BbUM}sj>$e*8`c#{A0c(0ru?v&$$S7m?aS=oL5d3o{0XXW`9KP_K;{*&_AXP=hc zmwZR;W!c-`FUP0n<(LJmbB!scX8b*$)ul|@vonR=IM=$`cfI(o(eB|%dAWN~p1s^H zJ3D*j==i9do#$I!*BUc(v^oo19L>h0JjaJI5zpcnV@bwWj4#-!!qI(M3}gJnu84eh zh6NLjb!1YOog!Q;lK6#33C9?`^-oxIp&ienGku-7)3i4orcAY+V(2dmU^QQBM}hGb zivqj=dvzgsH6~=ri4&=Xgcv_BBHZR!8qV#ek;G)K$voq+M#XSEd!&JFcTCc=J z*`cxXv=?({?kPUigD*b&%kt{g^Rl$CSibw+@0V|U>pNwAeM9_8nHA0a)Ej^Mi(P8y zcK_(Syx2V{FZNH%35yx``K-ZQS(;<~K9jL8dR07p18!w`rEG1km&Xq`%hN|2<>L>w z%14jZ%HwtUEl#VSepQwiXMJoQVw3kS6RNk=1!ZuV6E7AZn0q>xj+lF*e6e$iXT-V2 z<M!Np-wRZ^IaB-`MM}Q1@H#)si>YM5Thp*8#%|Q`WFc%yG?Igzr}}w8QE8<;;dwwA zRm>inP!{c`Xev(6yNEAyCX`utdgrI>jp~ao=rV7l_}u5Gu9N?ymBqBo-Q-1vTp6Ru zs*Bipcze!|vZH#I-K7c-Zzd`rReeED;$w#+WtsUbcE_>+$Syg`Om=-Kyl5g{(%?BB zzy|G1+HQ7au5t{i$^@Q-A)b)Q=JqWY<-&DZJTrHyv_hww+X4AON4d|AGliEM$(x;a z(m2st2rfs(!kOAn&)dDtxYvGn%%_s{xfPQn3gJQMejccaIw zc>W{wF=LMz+ikk$-|TW!qv76R=aPHew53Amd&Dq&gLmPEe%L0_Hn3mk-O_b8eS@#$ z`4#X!G?RdEKTAl*_p?Pg0fzbivjN}uy8l~$>+k#y4UJ`kAC1F6P?GB8x{~#n1Zag? zwYCW(GvPzWv$=V>hGVyh2meX{eYFA}M2IenSkUJ(PY6t0(G_n;i=*1{vkYS`-HS)!h(!+ba-&45LlEAgfvg7d z1eU|$7NYXCu8cR4O&VT2{c|M3Gy4U|$ptz$oP0b}9j1--vbnkG4|V2YOltMufGrI* z#IULlg0}Ew@79o`WdG|AT=nnXUI0hqFQ14IIujyyr(13g;2#iEco`ju067zve&XF0 zYk0`gDRC#Aw|rO-P-hPv@o>p*BQzk;%{r_0X4Fz=usW+>lcDCEJwhw_orL)MBLAw@ zdazoN10;TuTSz^=Y*!NGlW-0sJjX)<@NtI$KH$|k;31wjwdjCnQH5guF(Wvw~-(ZI%@|TBQJPcbS1r2t}c^lwZ zJ2J4fvV?;U9}s<*D=ty1o-l&L<<1Cr@v1VIuP*Z4XESS{#^M*e>1Yr?Z&)Q9q~Uda zbLBz6lDFln6DS#Zi)nstQTB9F+!;|h;ls#uMmcVRWKzE9TmkILVv9ZBz@h_5d~}*P zznTG2KJrW_luj*gWohuDcrA})bXk$-Ey6UM@BYK8>+sd~qmQjg%`Y-`VR3gRR@rO4PF%M54mz0d zNcQFVWEylH#s+i7U4xh$fUj|(ZG4+-#_4AqPSeU={etL7P1p1U(&WZs_Hi8qzdtex_bAQeh$VD-mziu7mZzpHYiTG_z~D5VHeg~@4|3z;j3CBTa}?pXO(yK(j9rL*pvac7q#pFrfa-p_C9epKVZaN?Y-|P+!YQZc5q~H zqpSRIt8wVV)V#1ADsH;#vaBGQ9jLU89{=VZ;)iyi>Be}uZ_()@j?O)>PrBq=O`xX_ z4CyG3?ds`r**S1m|HixFgRJ)ON<{z}zAY>`tSy`umcdpU(=~tl#ogL@%US7xp*g%J z;VN2S4kNfm6FYg{($R2n+i6j%zoGH!FJolrFJx>1B^kXazV#hml zxa-w$x80Sta}Q{owo2n?PsKx9>9IBXMhh-u2!3|<{`{)FLFeZSOkdC16&Q67{f+aV zu=X7F8_)-a{_%62;_C1_C@0EC7AROy=;g`yi^YwzGxD6H*0P`| zwD}Vk;g61vyy&^R%i`x=xzIS19YHH=t7UCt!@E+JHMV6ZQ+8&}mW|b=vbMbFon9Q} zH>>n5FU)z-Y-Mq-EYHt+=OBwt96!iH(##Amhw^eKW4qwF=4a&A#RNMGa0~KhVT%_v z`Igz)iN@h72VM|-eJ$DEmPNvdCkrKhk;{ofckJl95uY4Un2Gzh8pEEIomVfE#$D;@ zwZ^Nn($TaRFgV3$cW1Bc@9mZ2!~Mc?GT)Y>bz?!61x9up@r^VVC^pttoc(FUmLZqHos;xjFie#XxpSv53X-hGfo^%L9v3>{4UQ zpM@AFk@BE2#4(HhHkK|Hl-Z3$?eJoaXwe5_XpYfa)J0j#+!=E$EL2{5@rk@nUCf+M z7JRr8w-@7(No9(KTaIdEcN&Y99FfR(z$uWK6M5^g`uyCqk7o3of^<*Z%vJb^Mdme> zcK6X$_c&V7{>mu6sm9ToGcF6M%bp*gO_3WKmwn_DuFV~Qqpq}egsY{KIs#o=ybgV8 zS4@SY9uC3+=$LQ-b5ih<$N@!$6&cVUy9?J>mEWo_%t-!t72Hp zV!o8J`AbTZ}4thAj0V;(1D?8it(LWb>qN~kl;)U0UZt8*o}7}(@_zLHBkMr2~|T>z%L2# z@a&J4YFIAX zyU=2W#xT@}Aacm%tLhrOuX?Y{hSi$R9#%K9Se-x3Uv}pq54UvKc++ToZM{6$eo)p{ zSKT=U{6Ng}!{wtj`r#vYeJJ<`Y4x|M7P#5d;Tz(J7Y6*puh(H@6rt0GuW5zHg-qEP zW|w)g7?U?0=v-n~2SN`mIt7^iUXePEJm~1)^EL;aW75e33EnkHHU2!9n$9c(Hr>F- zEt~XgndLSHCGj^4@>!HtoCyp{x&6r^WG6uM!K0FZAx~;!$A(`zKcVw+j=CUVfr~T` z7r8jLkOw~aEL`E{5;yc?doKL^W}VAJ;w5ZkB40!2BNWM#nlIdveo>JgaJqx@pc%hr z+7Ad0w^f5bVepYXJOb9AAP;KU`3u*|6VU2Q;{}=y%enIVQXN3zM$O>q*iqIANyotX zXEuso<-o@rikOZbi(EOzBK4SZ!hne51z8|-XG9$k29hw8M3!F++}ZW_#3VOIKhWWE zER{y&$@ur;HPI}=-5m3Ic)9+dXs2imn@S9m2 z^&q_S5%c5lwqQla8a`R#d%c;4*`3iUa+-V=0qzg8rR{2x)R%4Z1zJr#3{^M=2imm3I1CQU%VpZ|=OS(bbw1T26ftAh z-KgNB1)Q+WBYETC--7K`EX{de!djo8}Ym^RXZeKxkamCsD z_kcTQv&SDh`fs!~Y&CJW=PclK=rTsumUeLM>Zm8-fB_z8<+8~;G&_3`=F@10SA(HD z#?T*oXnJ>l8PmD#v^m+o;&eq9v9~MbyW(Yw4rA}Ybk$wMg}!(9{?xbBIpi{&uL2E?02TWhalXxJ_bI4bwQ)2BYVN zGk!fT*Er5@es1^&yveWyH|WJ02&O!HJ|>+KM)_=x_IpH6(jx) z$L02;I^)-0j=>(iS+&{WKzDq{ApWD*C>~y118Dqo<*56}=c^j2%E&Gr&BJDY4ckm$ z#4QryFs|}yGV!8sM=AI4YI2#DOrbyS%wYh)xQ~f$CehEz)w!;V3r}FP>uX_wqZ65^ zo>t#KWg90Z-Qk3hcFsHpkE@C9!N8ba7;2geXegzxa*RPjJMe7!~&kbW#sW!7Vw%H z-(r`1*x6y?Nn^%2vNMijOyWs$@~6%pFqTCZe%Vv*S{+>1ySN&i9cOlgZ1U|aAUcwFVB1T)Y_89aZ9shZDqbZdaz!eKH4k~AFP%~n@i=< z#!}f{o%gk|JgYEsWpj1Wi&iXZDdlLp_`tZEON}Kj72iGaTC{#i2V+KFJmouFyRTlA zqr-hK@SdL>mlw~!C_nkhr{#+;pOt4Xcgi674a+_=^}5U`)7hOhrSa>z z^nH49Q!Z}qm5Xc2XkECST_~rQH)VHUx>vmHh@-yUqb}%TrxKqU@Hep-hqL=jc}m`q z=j5Y?)*j2VFh_Y~=MeJ?EW9vYM|*rHYeTYgJSBC{FC9y#175PH!~;XLQ2 z`U{=Md%Bp%$$SwDzU;JIQn_AIo60;AGNM-6%Y7pPrJOYM;8c4k{M7gtMM% z9K^?IL45z7dSY6|Wqnl|x79MqE1wP{yKdGqaxKlPooAuUap6^ID&RIh(Z(;2*0Y z_#V;dh5*j#k=d?>PuN`kjp2sZEqdwUeW1lR3Et(`;N3Je13EL%#{ORipy#57%SICa zD~GQu6Oe_k-~JD?@YRItK!p*bOK|*br6EBv_<^*Ja965IZ!&Nug%56JF7?u6gYdRs z5P*w66#{2ufTViGzq`1FNhTvhZ$gC7Kb_bxu%XMhL181l%FyA_K*z_o76&|V$Io^< z@rxB!c4G%;kLqtW_7OmcfgscZEPt}Ac@7P#_l+(-tdf%3obkW{L*O3 zS4hqSURhl)4<0=5`MA7gf@db_TPV7~iPHtytY!11MqZ69rrn;5=fRW*lpg{LBeXgN z32z$x22ynfm@McdeikC22HYudrw@$oJe+ud@<7xBinpzp@b?=rdZ6>x3mpKqKhv4y z_y)G`v%86hb6db@<)rB>^2Bsn?Z&P+DZ>pDPb|8L9=*kuv{D}J=&&--pXhb*eIxsz zJDD9nxa*(6D7s8oFJ4KXe#i)g?>+guQ@{h7PP+U#4$qx=?C2kTLt{JiEQVB_k#{mX zATFYV*0NSymEUfcpXkN|3?7>Nj7xcg%pC>l7;f0258+)-%nU~@kETsj<|7AGj!r-5 zktbon>nBf4EEbV;N@pC|z%hsCbm}Ao^=<@!Zf6zP!@KnfJ*D z!dTa$;f)^TvP<-&pBpkGCuJUo%L;lEo;-i8_~4zYlX^jik=>11#DtMRGP)zG0Wclb zIdxoVhIpg2l`Z6<)BIK)J6Ww~w;^&67Xe5UolWly*H`$nC$b;9I%C-}QwXv_YC56x>ZC(~C0xnF7MtYA}}}{mia;8{%+0<^u*?jiJ$o zz+tgj518Qas6d-QJqFCnbXag#32YL!*%MblHe2P_MIHzqAOh&P!efND=%7#*gf2!x zRUW|#V`Qw2u7S}NNw^w=ArnQm*l6Vo&0J7N%zlIAK zZ{DHDoh!VlH6XfBmf4gT@v~=e#^aLW>>cu4g4WVkr$FW2{z#l>Vmka>7R)jyT#b9+ z1(}^y4$O*%GGyQ+2=0`7P_c(<0N@i%wacM@qwUH=XSOSuB-?;SIN2Q%8vpF*@wy^& z%Dm%2fNCa0EdbI(>yPnI-V2~5NCXWIG&Z@dyAZlSqhGgj$Y<8ViS8f$92dTR?Kl4e zFMK(@W8gY1z>73Qzdha1-LT^{Ku0ry9+(tHh~PWtsQ;+D(ssCUcj!B}47p-84n*(n zQ2bgLLE~{3ZW2B!Z2rL;uo($!Ym}ZVIP}x_P4w730gKVyOvd7jOWA$k9SDre z>ts9=-`MRIp0SF@tt3yWpu8qtCViPSMkbB9G}dZ)?TKUc4KgNCiY$9%g)aWkHhNgX zSM(YTDM;oJ^dp=nmLZY^&>@eHc|7M^MFP%IE6IE6kD1acMi*$RR3mbUcxVzx6=#d?frR; zIp@pkdvoRL?R2?*GhM{E%q_0yTJpE@=H~ep7Q3eAvTIE$Us8Us$h9H)x7JtyTPmCD z8mCG%XoqiSb0p%8l#RYv;32MxW|qv;-O5RoO47d z3tyRkp{z5%;CU(8z1Zxs!~!%6P79W`eKU?i#vBCS+~3~b@Hd-MzFE}GE=O6qvgG+J z@uAP+MH$)w<_ZLD(TcIY>lF1!m+2%cX@Q1slC3JA`6d_(SX6X&Mp1sU03;PF|0w$$ zUAnxySQZy~K^Q&Vx1N`j2GZkW{UjfGPx*4aRNTyIwfc^9)FszX=^+bh%)3Mf%zvhh z@uY_3g&%UctgGLPq8}Md)x2D;nFUX^Rz)^vH|T zEP5pmBWq}-e{=&2^1Zch=t`#Nu7vYXIH^i9Qi3BldYw~&U!KnnOx*U7#qD5)w22jO z3S&p;VuyDREiPn|BbQ`Jn3P}tWTJ25O@{xtnG3tGiVww*#*WS(T(G)#-qj*#_RbvI zF=Oo@em%0$P6GT!{l~&`eMR^_%s8*R;j4MR8@`%`+!}@Vm92s4YmlM+zgl>IoeiNb zeEpr@A)Ts9un`&|vDd`owBSS%lqWDiVRvmyrwdHOW46U6_$DkiL9IX7d)_hOMP;s@ z@vFqHXf}}nF}q_iNR@FT=F2%|&Xgws_UCtjo=);BdQ z4J}8!Z9jORhwFAd;xHXy8f_YVM=E}n2qz$XI-D$~WI@GtJwSMi#}6xok3Y0=n}Nc4 zQB1Ucs2I&df(`<7xg6HE0AR z`g$%m9S^jSZQ2Y3)SY|2*qQB^}g3;jP>5Ez3oY(J4cp1 z^5zz~S|^9UT}J zwkQz1-9x9T$w?l1*IeaH$AwNZ3qKjupw4vM=;%@|uX!7bfy%|X@q}|ZL1x8G*=`-4 z)^TlVC7NNmp~K5@Az8Q$p1Msrpp%{YqH=R38Eah&h@a~C0%w&|-_F**6*c<8S3BA*b6^+_tyy!4WikkYDu{KNAuleh{%x{YID5rVAZm z$FG%zW>5GUx$oe3Hpx^#^lXyc_($gs5AX1^+YGARZvCVymlo@f@G<|tu0kKC#{uJb_g4kM*^=^RbjqLW4|W%q$`4allX9FdCeQ2mHvhyGh+pvWH@3PP z#GPx@ts2zXTlk)axJPl^NI*~y$Il+sU9We!@3J>N3gas{tUaBd)71^Mu)W>34qv?n z?g4G>y8)elwU6Mcok{I2gNgOL_&1Gb zD2P*I0o@$P<5BwCcq>fW8(q>-D=QgC!ZrLo7J`p>Fus6}a2_|b^kWyxJd%1ncmi1C z5BwPu@f{lpc25%+4_3ov|D7G5*R6vvsH1<)wqc*K-<@ z*+;`M(eJS$^9hWNG_G1+_DjU;8yo)4F_Zb3%&szO{6w74lN=TUy(psi*e&G65l#cS z%A%nASy6=ZjJ)JHyY>Pr<44b%AfOWHai8$sX?J>APR|$%UwGl>ki|7!DI-ngBiOx?d;iy^{?w6oMn-`24}?(Wzw3t{F*ME^pqJlT*bdK4+J_ zbgVd7s9~aiZmGPPnknbk8lPX>6b((w(aB|b_G-U;`RbtTpDON~d*$f-bvZh{_Ttvm z?2^pIGPAf=rWe-A&D4B(JF`&k%`BChy6D9>>)3&Hb|t>z%}%Wg#=TO9zp*5}O-pW$ zZ(QUkKjq=v{kL8eSYDV>nXcp4={fa#XUk2QR-R3l)s;mb7s?TbuU_qyFTZ?IUcTC~ zZkNR8EqSGK0Y7%ktu8Nm(TCka=NDIAgk*usC66(_!uiu1@+XhTtIQ{GvGCItsQ5M; za}LFeU)!6jWov_PwxyiSP*#-}El-$tU@?wkE&0}z`yGmtdPSU+S^W8SoXfWc8`CO- zEJ7+;$st*!BNmBPlm-^EIP#EVK4}v;Qqp;P#xbk;TnJ^4U0y86vDinyhTVi&43nJF zAG)BrNepsAai`9a_BQ|Gs4c=9*W-L5A>Rf^rj*b8vcQc#2@$b{c6}tR(B?Un`7!i~ z{?MoE^o`0Kb0g+SQ1M64w1dJ?Fa6y)$w|B5cFxat(w8=gwuL&}>N2u0=fqqIdS6*u zENiRFUIg@REv1(^Aus4LZz3JTn|6YQaTdz6*vE0Ix+JUH3&)L=y1NV^LfSy*FALc! zKT4Kx`Z*(UL^r^!(y=l(rTl4hcw_Hr(ymmzDU9uCNT&(7R~&ki2Z&s_3198jmtgpe zAI8(UJ2Q5`F5#NlpwTrv8tM248GD6c*l}on<~AT}aWr@rkLYCxV_~_zQicKjJ7|aS z)jZz~?;Fn$ex@*_?du2o8bCSw`Vn~H>$iXV@BEG{5e#(YCunX=l`ycWda?8G7QJXh zOdi_SFo|tPYa3?8$(K@VTP1M#xT#k9$xXq|q!*PeG+0{WMq^|Qa^MW3${ROG-CG*L zfNH*BD|)6@Y)hlUk8u7aJr39S+5rx~#zbz{1wud5qJ zMvrG=U9@ztg>$^(dwIhy8s4bMxymelvCE6Mj_4$^0Cu5{A8)VlFy|pdN4MoE5VhhC z#`^1g(W!i_KWmp~rNB>h*=s!*=10rS%A)z>Hp+RE#SzjEKlAaT1$+}89B-*nZs=?y zGaS&5J2rCpEjIChC3$VW3T&RTBRdY8a`SM)j!fxXBt2Z@7in(i+ z7jOPhHZvHZ<3-2lt?H=tN0jJOWi|sT$tD@!GBA+5=A@1qTjiZ!q+NeL!0W{~`L{(& z$}c)#Aj(3X(~bu^t~6X%>il170OIe1K_Yp%as0)?QjWbKeUv8;M&;-wty@?%e?dpW-6h60izG)iLZh2aK|~?` z0M42W0r51431y%U`vhfMAD{0P?`NSr8og!a)Q*VH*o zrBU1=Ycw{-+;+t+NzDfjTd&BlVmDVO^!6&DoY8xG!h z$pv0N!nb~d(@LJG9z|W?sDr`_2MzS5;}Sm40EivHez}kaFEC{JJ;=_N%nbN<7^l%YQ{qSY7Sdoc1ymw}14<|K#Vo@Kvpbq%Gjo zS**w!@#1gyfEKt5H#CRP=-=g69Wg76(@)|t42x|@)7|;oKXz`Rqd>Mgk;^ck?{I=4 z-8epcad64sD{-}7dv5wro9Bs z-RRpD0F|ryyZV5rxDndWnC=dDGkwt(ROoP2>L7X?xD2CI=8G7X!@)3gA7;mb9)kO{Plyr5_WXx?-s7oR&bMK z=cwP17St$S<;1QY513AcA~nkxUC{%Vai(whKrs2)?Kot|ST1K;>IMDqvJ<9oUu-(SW%J5AWIvQ}C3 z_cI(k{=V$8-s2;{V!swY7n~Z@a7M(^(R3cM+gaVg>F%p5d(aU}F3XmI59aXYe z;JVQ`c>iFpyxQRyxr4$^E%>w3;rJvA6pYK^&GCVr%oWRw&FP0Se$m)deDTY7j2C>& zUnX#wsAW<;6Sp}fBYYSmF)8nFdCBcbdlr4>X39KA?}-nS(oFPnL>)&mGU?4xYl}5m;+@9sbz!b_G+9?y8}2+&uc&CfHz$&*eP!|9S-$e82WB!}c@SCbb7 zM2bFmLD4TC-moJ|bKv!~-4q(_SWQi-p9?ya`9tafIF_$5|?Vhm)Khvx~-I#G{o8j+$c*#5>C* z8*?J;RN{MCdwU1v`0T1&Xw1iTsPgc9XRmzue7C&V*)Mzhd^3(6N;m$d)yerqIXpfq z`-dlGk7EW8bRC|R-J{F0b97c-?w^&t&-#k5?PH*dTU#y7F{5808X zaC^t)`HTJXYVW9=UnyoGyJ#&&>NMLUyrT@v^V< z!s#o#K*=|=c6JZStKB{EKPU%^=TI_n^rJ|#*mj(6(V;M2p1rzZvFvR*ljp^i#y!$K zi#b#3<6NAbmzOVg$`{XGlou~vN@x2n8%v8SpBg{&03fe9CU0|nrLg0T*#z%u%mjk? zFkiu92|lV(9-^mxOSyULMNY~cb0(A*Oukjl$uP6i_sh!4N?GK{LzNfm>9o@Cg)7R5 zbi$4;b{s8pw5eqC!bvRzEC6NEg@s-gl=3|<;$fj#B}Z|;w$AYE$Y!1Bu9!aMv7iWC8?b-{?)Vs71Z){H;O}(Cx-ED#5Lk1QU5v;we4rH_|v1&a+ zHt5kAWk0;3qiv%ud|{9_G~YAh`9xUa zBH!|SP#&pHdl6IdLFf6GYJ#L5vZ%?%fo0{>+UkmTNwP4=F{3O7F3huNnKm#BU&4u& z7m&$Y+C;uj$I+H;*O;P9dMyv-mFG^)*dc&NRs;HB;p<*mp5r@w_*rz*z^{_ojw}7S zikInl@EhP;xag$$1t!zQBp>jaL_Z7%bf*IeM)}nGQgIH`{NX=6m zKVY0s1MuU1k-Ep(bw_w$Jid3)4&keLz8l^*o*{hQFsA?d(R@v~od@p&EPUPjPygsY zcbnr(^FUUn3_A0+H0jka5DD!=U+HQXBZH%}5n0l3gtrVxL02A>Q@1sPI84{^1{eUO zH~~H71dyj?4$}c7RCvdoMsAdAkBJ0?=#(l%QX@;xr~+6J+!aPvds`>^ODOw09C4e} zG_beR-q?EZWZN5I34TWi)y0FGBLp}~01@Zr zc{7IHC~P0s!`A#!V1wkFV|5+^Xb0IlF%5KxTlwI*2mwaZcb`wBSr!q6J9dY%?&xd~ zFW*#Zx=9!;Y&mC3dL{wsSUV5gq0JF>egh1eng`&x8o&oPrX_aVCUib|p#`_{B4tK$ z%A}kmkMV~OKKLOHowk~<@^ikCIuYUT0Wk7XW|T)jD_4Z|VvEeSh>0Bdv#5pH-o$YS z2iav3ns9!rPw7AxDQ7J1kTN>j*X2+HgWcmpb$Cxb$Wu2+k@8lNc(~B1vnhR{1?*SK z0}T_z4>{j@%lh)#N?BcBD;w+Ug~echw@c|+(0~P*DPsh8UdSKWNHd+SEcQ$}9PzL~ zjGj0ro}GsrLE-b_YZ%f)r;q^{W!5_rl`b!CDNY71bf#Iv;y6clzTEK=nd0}iywq`J zw-&nK0SNODpXt4ze8`^Y$TinZa8IaXvDWJmEs`8YoQb zB9B<8b4QV%f>UnpX>dXrUR_u&A3S~8z-oHkln*VeX|Z?yF(8R0nC2ek z9lDXE$__3iGVV!nH0b<*Mr7X7iwv?c!K$9|u6`|Et3qz_tpW6~Gsh-;^RG?^hl%3_ zQ9VqSGT?pF5BXPmuZ<;cYmTHP2VvwMZ(lL$a8Z_0766`jYKz0 zkTxI^m|RM0EC&pt2NPEuF`!^scnQe zy7IL=YGW&&7$M9{5)GiVkG$&LyaUY!|LWc0IuLzi;8)2i5AF$;`)#-j9|)I9(MWZX z9zS=m$5;NuLOZJTD(w|(_>cbHA2e3~*5QBlzx};o)E%UrRItuQ$?QMCjnG$UxR%Bt zOri(CkNY%Q-?0zEPU3S5CwIdPW#MkyEq+`ncg@S$*TOZN?V~uL(Kf$|h+Po8a4G{` z-=qHcyM$LB0OeIqyGP`|!`&b+*TfGFAxl5W4-FYDY#*l#^EA5p%eS%}#?{O|${I+} z`pf2t#m?Rz>o9JozPd*M=EB>ri)V=Ikj9~_X17t}w4Ao}aXHOF*-d{h(KY`H#szPC zLqJU5t&$l`N7+ee?upON5&jLrCVeabpP_%EYi>Dk(}|HKcg#qhF0Gz;;QlFn>-dKcW-CY3H4uK3 zRzDEw5e;?I^AD3|x{Ox60bWoJL3oJJ6)flut=MVM*|QP~NwwQ?os=qp%( zgo(4GtBA&@4-*S+CXa_O!gnI{^ob|#q)#%-N$q>BjAYU3gQp*tZ-4uH<>8}`y<3Jw zfs0FxLo}A)csNc$VeG*-iq6l@J;q_Nh4R4!_B<1{Ow4MWg4ixM(l=v+oC2bJQ`|n< zO_v>#!Se&oOX@(5oX-n{S*YSAIwpIWi1$l_>>?3w7Im0#W=!OT0VRyFPhM)RV_(KQ zEC?a1cNwwMMq@qEx_)Uq^IBs<$79|(e%=$;)t|P4bQ1@r=MJj8Tp9n|*VrfN>t1lI zI`OxoC9hv-yt($`-1^!^S!1V;{J^u|gkDKMF9oixt(IBIa(;1E_74ucXu~3oBOpG- zMOfx$_%@LBEq}&m>_oe~gg)(1q_oQ1N9ETR(aSL6xfZql#F&k zDu>b|b3LT*{`9@Fw2+0M6{TTqnFWXir)zfhUU~Xxt31}lBGKu&^5;zQF}_xLyW+H% zo2&9xXU#>K+URhcw-~IN7<;kOmUU<7vxqGm&S{^;zR5^KD4i1mY z%l+f>V)w`kgeT(bJXJ+t(UR|d-Q1`iC~fRCoROU5BaP*pE6z|Ci_4G`7eB(uyMaeen1-at-dn$kC4_J6<#}ML4{!rIA zoy7~Hyfm)*I;{qNb9KIa`x}qTcR%^ai*8>&+bRF%FQ1j4eECYcI4q~4rE2hz3|6)pB-tWnW+cTd#QTqhCuq^B%VX*=;-LwI}tsvq4ZN%DYFZzJ1l^+ zJBr1%GrpImyv{rsb5SaPPDRQO?$*ZA9-(Q<3oqR+D*scy7v!h%eVk)NeJYM)KozM;|e%cSx=x_U551I3! zZaL-B9phzQDkfd%WMTSEdAv4LRu`vv580)@$46;_+hGGOyzQ91m)()WF5`wU60SnR zq)$cK2|t7(ZD1JIciVxcqpyP7JbQSTUxRnkkbtp72wFbAFF1~`7vyJvzD#}{_`CnR z|M|W9zx~_)gWpl;Dx_{T=U|v$^Qv}t=wxeQ=oL2{_ZY^T2X08XnKy+S)yBhYd{LP& z=~O_CfACmCqww~#NAOtfh9msA@b<0RtC$Yvy9ychR*`Ch(1pj}F8cu;-%5j{$2Gjn zh-g1Nnq7u0t+8lV>6mt%F!EY{Z|D@L1H<=@FnMTY zS5`V*97jk;lZPAM7~fL2(@Cn0W54(EUK||-!-|)KNJ6^hY zD@t+sJS~eV@$`M4!4hNkRF^@))9?%bk)jQ^^jGMI_o0-nRt&k*v7#C9q9+m zkG!jaZ9s1i+w+i0<4Gsad0gWr{lRB&kZ^Q9qZ>t}zw!rN*ZgSuZ!)-?C|HXJJa#z} zPBK_RP{idZh@T7k%0n)f4_)ZPVQZd)#~*qirIo^Li-3g_rGfPEvrNQAhdFlSahkxp z{a}GhCSjl#Z-1QfdUigG zY+N)=lmkm8-d==sJOs)Bj5OMxzhx3V7xAf%l0OW5Xj`ZoGt$@M{GvOtK1xLth)jrD z3esLyoYT-`sF#0O8#sUvl#lB6E)c8^iwX2~40?jO&NiGOZZDuoCw>l89~0^Cqp5?h1SUv(Q(WwL*6cAIwsRX?oxIsZVwq2rB7Ju%i7GIOUs;~`tm zx56;a{PEL0XuJKhe&W|b3uoQLFZ_D9|J8|~vCYdWZDC}!+qX&!5{D6SRTP#+gXta6 zm>B+58j38Y{iP3?sr!`*vt9)DulhB-d8r+;9$g*cACKx^>4v*>r3Kb14rG1*)BY%rvUXOnRV;n82MeH#ML z{}xtMRhFJtA2!h3?HZ=fIQ`(+AUNU~^5Di*>1+?bcm@}DbyR412sCxqf*^M4e1wePVJF>@>_=a(e>JAVJLbwD0 z$n8=ql;t&1ML-G4yyNZxTpM4dt_}S|59fsK;~dh#KUa@$e&G>6V1Tb_3slpF;({NJ zfj6WM(;>mhWf|@A&gD?r`rp zAZPT!f($QzGFeWO%&rkHcGMj(Ow6)~q%&xUp%R5%rD6cwEeJu&BWJhYQ_#@kjB~mmv+StIN{U zs`a$AB)w^@$pR(vXI`Z)+R^usEbLriQGi_}jE|Ws@psb{Pma}NyvAuD(%pi_UyI9S zd0BBNPgtNsxBae?S#<-CugENEc*xh<>>Ip3u<2cJ3TMw%mXoTFIv=heUpX3lcOUqevt=Kw91O9t7voz~=zw^=kSRT|*n6V{9V@;A$-KLNP<9TE%Gssz zM}90iP{!D~#p2VP^f@=n81|kQofrbMbB7&>bpAaa*N^=7X*C+}G6!(X(UH;tX=f)G zvaYK9udc3I&vOebNGX5WjU`^Ri!A!Vi!lDSm&$^Bw<@#DRWK(o&8{bu;_TM z`anCt{267Nw6MsBJhT%R7gt`WqD)+hKHtq!*}Enec>$PHX4sJ^IV2PG9E-?{$IOpV zUy#gEf9Nw*`%G92#t)Al=dDhB~kISp#p=V}V{z7=}E5znUJv4u%jRNL4lxKcn zS9aQ*{~vRI)@|96<@rI&o74Bln|mWNGPAN$8YR()rlbc%=?kFBroMrAf@gSP=mDbO zNemb;h6YX50Hkk%vZ)e$02l)hmC7bEZp6Lre*E;EyYv73|2EgMz4kuG-J>canS0wZ zvuV?&O`Fy%Yu2)b;nOT^A|VfJ7rQDu%yaksZB@kmeEKdYsS9lxx0p#k&s6twDiH04 z%`y5?+6C(q-gw^RD9Y4dvV+e22^MtO)@uClvY68LDJR-Ee0|SS9LkfjbH6um(ofnB zkiIE-K-U0udUsRh&pKLEXga`l^Mi>$VFZMqLxO2xMOS{H=&(n+!t*a&vw^s~IM~Jn zR?$xNL9i4a=-oj1xh~Olr1%rwAq5k@#aRU{UeWe(3YNo`!@mR`qx%vbUz$!2UmM5t zU!TlZ!m^IP1aj2j@BP6~6ziv(+KB{9@NA4$m-05e)myL%EVtIqb zn^?XX(wVFCSEtTRl>wZ;zonb__03fVg&v4P&jLNK?B~fV($&T3aMS?2ywN3IyeY%r z5jXsJg6h0INd=!v4GtKzTxzhxfQ^9{PXTc==5^xzgTrBKV>{n7lAcmt(IRD@oa4uZ z-Z}`Giw#|yqPYPNh{Tf{Y^y0_95|y^dn*EQv6NpwU1q)aGGNJ81*X&Yri)PAj(s!K z&znx9C!WOM=36&JUxNmfYX(LdD1ujbOa}av zEp*nO{?4PqNn1He=9DDC48Q>BaU(N%@J(8>xOFKH46Os1LF}6wE-i;Q>0gsk;V-dc1986phQ1`mAMvEdy zdWh@$tNe~@(ngHSb=O4lg9-;|U2pM#s$lAIqM8On@JOPI-4HdJAap5z3y-Vug9zS< ztiRfl@w&7;a&6HKxScm_E_GD^)XIR}{M6&RJe-D1N*aGcBUke`99pX~?CXkuQLNp> z%UB5;KQZl1c*T=l^#KycbXaU-_;~UGDcNzZq|Ly<&>pSZ3zw_`nzARsbb^f9% zoGw8K`ZzuOs(1`lrU$6UIL)5(DE}M}fE&Y`UzagoU?-Z%WI zAH8G}HnziyAnDpKGrAj8T74c1H>cA@iN*Fk#BTB&I!oKa3kQTx{N5;NruvcMO?>(6 zC&aA45iVUA-}F;}d+Zkkrjd85BXRd}!Zc2x!W>t>st>pWUAWAotN0UVqAmR!M>uvX z$}w)EC$4Eac`L4YH#$>FuEYn|hb4~7B0ignU#yL7xImi^G{0Py!*Wx+P1hI?M}#Jc zMsA3%D*rJfKiPK6q-=9R9>ox^DKD6jzTx}&Kg!k721M8J;9Txww4w=&;qf(l%BP_V zc3m~S%$Qyjv8ql*K08Mn9#!UJ*(XG%35vHO31Bm_b{O|l(raPu=YOSHVY)2H^#wp# zz@K#7{o+>sES-3fSLPcRmu!BWYo0<|Kg$#1C zVRG{Ry>a+4J}#bx{wp4Oz4imH%<-A~)VP>=59!@09p1`et%3CfuQ%MXfPX3b%9~&u zUC5hM)K%tY%z-KA%*E*A1g-C4;hB89coaaGH$td?(lL4l2M^LG4h#P48*B;{@%XdEIQcVAC3+WhQous_#2MRo86sVr^|Pv zm_zRG?GCSBy%>Jrj4L$>(^^LC`&uuwck++JN z^Ixj&v9ZRRL@86{Rpm%KLB~F_Pw|)svjM^bqH20>6O=pO*5ZL#_^ojaDCNe6oaW}_ zlleVwv++hCZ*b8rs2@D!%|;WOCtgeV$eUZNdz}xL-psvnduE*sKsU(aBS~BR_4=Lb zAL|RO17*YW_BL&SZ+)Rp-jZZJf{iTl>$MJw6XW(m?PKjgbzX*t%+Jm*Z7wfw6i<2) zUy(Wg=$4II(js2!rUdf8vjxb3KD}8*y2wnLtm8Bp2*alDHZSm^6Onl!AGnkq%wwc} zl||OGV6Y**xUOxp;ivLeyJp>pvY{O7C|7vYn@_a&dT@F8^vrL%o~a)@Ic5Fv)W>7e zx3L^oYe(0tWnSJ5=kDvyy|GOHc6F(~3Z00SI>#nlHow$nCGrOAP)f%#h{$~hKj$lX z^Sw&M9C0{qd`Zq^8CSELKVeERK?32xo3`xGnrI9w9Cmb3{_!4)t{YSsP`pN*>|g>D z--#|14Yv?JLGNF1W9DJa8~ha3!$bTE3TNq7gcm%P2Jl$i9zLJOhOQ}PyR3J3dDd;K|HYP7V3@zbYo7ZGG@e{fICdbQAg0wUI4+5$CF<= zR$s$UgdK(aG`e(9U=e6M=E&qtCV`*u_g`^A77OupvOo(j+N1|R{B-aka~M4$ZC2J2 zZ|K}`WlClx;&92#4I{EbK}1vFGWZ7W4k2;r@a%@Z#RFoa1JWT;IH1>XBDRk{tPCoG zZw8V#nD~jF)Ez@{bc3)@zzskIZ2r7{{d)NJ+i!=%!$S{nVYL`mhyX{9piy416>A?8PwV^z*HDF77^=)C?4&`g}mr5PcU%wfJ@B!Vo=H1 z!EBBoJx_%Z&x0t*0Hhk_cmiGtCOvTXN^g4Vgu%hJZ#Lxh#nG{!fb#c=bdx|^eiKCE zA)@tePr3OctLV^61vMZK!H7`64Hp>z%DTc+R-tz;&5BF#=mFc8v5etC+9@~x6i)uU zQKc{pe#Oq9LW3jHM;9NZD?AKVCp|}i4>!y#)lqZS9#{(Mqxry%Rv( z4iG%L0w;;AD|9Z~H*N+MlIzp`aHTxI)8OOX={rvvo@x-l_qmuP@und%!iIWF+HCN! zDV8?PU`TCO+_yE*Kl=6?PXf02@T&$xH@BCrSI9>DVGs!*KW*ca+lh1|SsZdFqOMQZ@`0nH(Szb>C&|4d>_rSvd~CPm3uJJoWYAM(yzC zUIQ-;kWV$4xR73zM|T9u5QDe%?dQYpfhH6CyFT`iKF;mh@_cgrVe*PxOr*y;U>#Ep zBmjUMlF#RMr>Sa?rM9de_OaUBH!oig`#Zcbm-a^8bE(3@uu} z;{!q{-1y=lzHoNGYFZxSNIgwd@Q}-s;JWx)v~HKU@D!cw(TfAO(^aOMjM*G)5wIL1 z;S)|5ydB`Jti)5%aUgT!4YG)cU|y|I@d7P=g@s)4MPHj2)pqDt#&*ONo{f(usN~Q8 zgd2*4wu2?Pu%R9Ek6SL|1ygLth|?fHY4&Kjr_#$681o;G(aKG$b5Pg z3J#Bnr_s6uO?>In@_=ah(VzYdJ=G)&B=-|QtwpTOK-Ew26-U0XfRese9wcGWhju|y zNSxz7`N^mFE@|;cmO4JylO)m;a|t(3Ngx>@+7m7gX}nlXq^W95#2IT{t4%A z7DOjlhWI0dM3A(7q#pZ2PlFy0IBs(r;@(4%a!D;qs8`EqTjo{kpQlX4#d zN;d^|3+JlM{iRDM{DN5Wmm$7PP1da|LGA?(%BAC*hz-#}pLRhncOnKt5nuGm%XodX1lS=Q0>tl*)^(mWSwdf`xc1pbt+< zrETF`Sdp-J%8w#obiBE>KO7vsmU*eU(T?U#Pc^&aZJ{-9ny>)R`~yEMuCCd{(p*A$ zVr;^O3Y$61KS=vta~8fyEijR<{spLcEs^}Y*cu| zP4hwO9p%9~0!Onk7IS@&@zL(``+-}{ft*)g@&KO~{%>-09%VC@rraS_y0kaNA&kXr z=BIgcf=xZfyKlR!J z^K7r5NY4O%zQ4V-PQ75Q!}=??=8>aS9$vr=Z^;d<;IH#%g#h44ncGk$jnCNu$OiPVY-2{z@>_&98wR zb@+RK@Y665rty%^KW`-I$DgbuA5=R1>`9pZ%`SRXfO6YU?e^dCu!)<6)C9!B-x{TT z!8_a+Dn9XAop&T06-UtU{MlSPuX9`>^xW*v{6xg5OrG}Qi5H$)x8Q3q3(xF~)bM)q+jLSu3!l1wdc*WtSPNI~T zpJZ_vW#9n#2m`+rlnpe_$!3Cb=Z~whu_(XX`LJr9-19lm3{Zv3ncZv_A;Y}~+4YKc zB5eh zH?J-^0#kJoU0FA(-8>Cbo1bPQEE5`+tq_u2Z6dn&YwVf;@{v}=U~|_4HSx}-El=LS zK|Cyyc*;#X61n*>>2kSg@PbbLM30DQ^Zt=1At+1YGLhq(V@#}26YW!h)-gYG7Crj% z+g2n@`Kyi*pS)6Lq{Cp535y%GfIK|k;4F5Yf@3hq(`czz0CJEXbpwE33Kfric6xxS zAL@4bLW5|8N)Gzc4VB3rZ?b7X>~fYa!a+d1au`|~x?mNhHxA?k3;QNQz#ierH#9BG zZo4P}0fk{E;oSm_^ICk1m~@(=fT9!Nbbo9b5EYpAS+wR+dH^T7>c_{0dqIm8uhE?! zFrI+)1<=5jIukh?4+04wQFIJm1ccj-OMl9>!r^O*5%0e*rjJ7w{AIOhK;r4zgm8EX zBpKp{D!<$d6LYj22_DESH)$0Wez~#8s~rw75f1;bn~cj{7X-%WLO5xQHxbMv zX%uT5Rslf`kF3t0+$K@3Xm_SDG8wkhbRlGMM?TX9U(TZCANquW3?6CBr)^?6JVY|i z>;%TevMjir?YJ@YRd$kjKzuXyqE95CWSVSb_-Ft5ukVeo|JJ|z-}A```ICNtvO<2K zbZfvp^Y`@%zjbS8hi_m^(agdh!xg^w7iEuIMTOXm(9 z29SRYx6k}W_egIO*eKXJaJ=i7B67z zKO2;P0oVK<`v_g~*qCplG5=0lqo3vE#jy{@;5w9yz*^Y-3Z)k;npv80k3FK z27Z$lPi%0|$!!|)5&vi`>kQWnu+q(6cJXrj`ZazFIMV>ZSACoCE>`(5O%ILM*O4Ad z5aL0Y>3crRS5QI=10%ih0}(z`oQj7Hzk*7y$~@y=0v7W;!IY;tEaLlk6(??B;w`Yv zVxpXVJ!trfQviAjpFxkpJ^JIAu4P(&AAm{+Q{z+P`E_A^xc#DG-gc$A_0{E><|P*z z(`RFX%@*Dg!T9@L%=J7U;w=r$Puc=C^FQRnojH6Se8mv2;`7iS3(IVLIG%XXp1k0% zIY{0b)7ZuHLZu@U8a7|Rw>hKIPr8|(uwd;uj^tqB+;d{{XHJY9qnlFF+l#Nr$lQ*e+B;fU(*8r%uv?uBbb1#m6e0Op& zygfM|PNBV!ey^GL=Tsxs4_F)Hp>65}ZHF}-<3*o0xl+E&N9l|FnDPHQ9H-L3Ma`VT+aY92~Yetoni?L;~u zALJ7Q&_-~QNBShc8L2qVGjsInC$Jr(0X&cgLtA${2v4_%il=lvc6Sq#2IWRil*`Gf z+M(ZS`{>WKux3Ll{QR9RwHemEyjdqcSwG`pW{$gjKJ2TGb4;Ymi*l9xY?AR77#p+J zoBN)~mOhvMOS%w-O*ZNT<;276+p60~Y71Mc+q6l))u{Hqze}4^TVgX0Udp@sBgy&f z$w$R|=I?wxmAl3?buSQ!fc`6WH~kp6xP9+$?j?H(w@3@Dj5pfww|5cG-~ROV5b-O2 z(N1*Bc0upQwJI(U_v9~_^8=RSO@KeLu7=0baoEFA7hs-l55H(iCpbs-tMl2VDz2*<|;2ghPjX?=wTYi&F%<+!A z@kJop#l=)61aO4DWHX)J?z&~Q06GrmOVH9PUUbOG2c11G_z~Kuf{v(mLr)3Pv4}+aOF>&MKri_fp#B1)aUcDM#zIf$Vm+3&!3Hl*Yy8P5!t5ZrZ_e`b1O|HWKv#Z0EoYXZlmFu<`K@CO5~OD~qsT9P2$xSEC|~%>D}4}^ z0gDH{l#3AL(+-Eqz?Z?U2F@H^;lUO1h!4CeH)LT@;6b+rTJZGXMaK1#o4NQBCxaQK z^DzSt&M0P(L*_FHOui{E4?;Cj@CSJ{*aeWCy5@C>dnP0d7RY8M81QG{OBfqn3`DRctv@9C-J4$y@7}%f;LDRN2F?omsDTKndf)|b z6|mnXL^t}~sIJ~>u(hUv#o?=$!~WsHz=vB&5AilNz+vN$^#illk)nc z^sY6L@j25M8l;_G4mXz?r1999;voCBCINegJl(ghiOAN#X(#YyGf)oK3!cPsTckW( zZW(-|0Lp{`AyWB?&-G2wkZA=Ym&$nK*@h-q2g6Uk{ju$5pX#oXvL-(T+{N*x>(73iWmVwAH(vW8332*8KKaVspO zR%Eg*CNv-tDLCki!x*8zu+&@rPOI?}(7#d_9c~bHi&~2?w3ReGai)(o-2`bjArpbK zL)-8h&;rY)izj=?L%4;Btfp$ThN4lpRYW|{P1oeHDx^6`OjFdxA90Ltj9MDzBZj!4 zGz*6V<|>@@0nTVB9a9##xGjU-6O85Mh_o+L+8ugxF&3O{{!TwK;Y6;HvmF1?uk($s z|M7o3CT);!%u@?NQtP%aFG2ZxVdpfZ`&^-g?~F#U6i=`U2lRNmS{gl!G|gU!BX`xW z9_BQ2SO_n>;joJ1NY^1(@l(wcKDA~Q%;T)|cQ|VSzuQo3z}2>+bCY#kIabIAs+Xw3 zI+78Pe~Q}^ghS7_cNZ+;a8LRe(_P>j7{g?z%>|4nsG%152bOU7m8`o8yj|R-w1x9S z4J-1O@-zpTK78^6;X6U^BBy6GwdUrw6Ta7OuyxM%|LDEiQH*W)l zkDd{kaPrbbgl6o=6KHpVvpwQ^o<$#s2$3ne$HBa!xr-ErCW;r&#Ab8|3g6>^9>1DC z>9g@g*$AUF8H?oB!2LkAKr}7e9Y5&wlhb(_@#UAh|d2FCGHLrTUra2o& z8cz6#qB4xuWr&~}zc#sGF8k{>m3+G-WX1qlf$d2XF)%=-9M;3Tw&P_c? zJ0o4@OFn^u1dz*fUB!ipi^gbtvx+0mm?zi#+#5ooT7SlgGO1-9&WxMeevO;%9k&WhgZjkGW&j0 ziieltf0?@!O14>psjtF#g71aUnb zQGDu_kC7Ue_8GHf@5kAT8E6S*zgz zZ#K|rTWmJ*&^&L;@unIt3sC3Yym{}p9=$23zJa{4W{Q5psy7%G!de~L=cc1eP@16S(>IL&zmjND?rQN89xuV>FaVo#^1AUkuob3F% zcJA25;ty(x9xLr-!p8~k%vTcvL>{|h87eN&yMd8!=QhYWhS~1I8q9eCJ#J;VYSZ~w0!4j1jepfZo%s6nc;oBI|Nfu;C*;_Ar*Fs;S==66 zBMF)+XB?(vX}AJ8>M)9fhDL$A`3s0D3qB&Tn@$anS;8Bv;*z=tzS!m!D3X%HGIDJs z3o<9R-3F5eYcgA-tHjsQ6mi$xR{w zvK=5@k2t_F+>yg4i4!w=v@>2C7R*_Y=0mZsUb6x8a@f}mof`r-$P7jm!JS^XbLYSJ z#urccFrXp5yb;1p!B1~7sA9mN8>DYa>Z}>W7^fR9H)Nhj;faw9zLE}c*&IVWI(&rW z$s9g%%1zKa&g$9f?He-WffYA9^Wf&m0{oiYqz#_3_F#>Vf$9biZ$995H_UP{Ho3#Ji4YV@&pGPVGQ!&(b}OHp?jWOVNgkU0eNTR zk#rdt@RnYk1C8#vIg+j?4@!snLmTvFlj!{(f^wKYz!IjB%w7ptpM&=}F0nj!jX?pnSmxVB-kc z{WP5TG4Q^ZxlmpE?)zU1Z{EJ~lV5}ChX)JF6S{u-i6^v@FUpBLF=%3fa;xyO>&xM( zc)$Mfx5LiCo+RN3rW@%XudXvV$`gF#)v8xh(jXJ*B`bXWmY3rA+jbhX)<&q?jBu3k zh6eQHQAVEy~E)r-~7lM?Yu{4y;$%7>{Hf=mUfudRyeYZ&~jiv*aj!Z#7cg7{1*>` zL}T8~4KisbUUSU=ECwiv7JU^89$fg!9j9$V765M|*e?2_!k>T%X{*VMyMjV1FcV+w zHB{h8+hR04Z5K@G)C*KfBQl4q#jrinGz=P`44qMM3bF|H^?XEYWhAD_1#Db)S+v^( ziU^<6L~7n$Puh;A~ku8<3dD0ww*+4+yWhM)3>7otz)#(3{<4J! z$1%LAZ^60EH!!E%uneY`f$lLdAMq`^S=DKH%#>~q%YL=z#$z541A-HM(Ki2-KP3jPrH2z4y5ze!Ks&!S}}`$5zH%pJdO7v zn7_=bc5V7av|$V@Sa8Z?fASSF=yA`=4>P7~Lc_>=LN#1W;>tNj?Fb8mTd2dNZMrE# z3wh`OJU@Ee9wz!8-|}W$tq!mln{+gKcZ!(sU8-_|#0`zY%rEo?Tb_j(xDQ7@L1VO> zm-tu9Jg1-BK`(|Cj&!Fww+IuzN$cPqypb*VJnO`CgiTfBp#WNzU`CE0(9!{tSK*SBtYY` zl?=@BJ$E!GHq4k?YEHJlJN(_h`XdTvbj@$g+)Iu%*F*f#84ood zAM6gthug!!p3-@y5|n&ws;+Ns4>yW_a&|HN?B~B2e)iq>!}mYD9WKsz%kkRBD@K>m zw=dEoZ>8;SZw|lxqnE?K`|tcWhu{41E0r;{AN@wy|Lgzz*FN@;`7awC92>|6#s}%2 zHbH%04Tj_VRFSNYedX_9f7|88_n+Rdxpa2!HHD9=JJzrC?|LF#ZcA4@u+AFR?(UBA zlZ_%yJfh6rpP!o-ZNT+ja*W8m5wMP(pa_e<@H0w^~Tr6y5z~H zTznCK(#QkL!LyO%euDN5Pu^NpeLz0eg0{DIhAriLeSK{>JlywM24zIqy*)XTT&*2Q zF486r-@$wR^2PAGzw;ZaL)$(!^Zh9&Qk@THmzQ4SLk`w4_e9HEkSOEw{95(lVz`zJ z^i^!Qd2@SfV|a0}GrTz3b^GyAq3R#eQNFXdHrx~c`qpn6zI*p>IDLPjHgG+x%RGO= zI$2Y;`z-1V`fYu*fIh3-*wtqPRc?U$BlVdD(DmT}`UkRp7k<4hm)un(Q&^m&D`RXR zG)7<#>w_nODaJ`m}m5{^4j#@Q{4KuNp?_W4?Oh zOXTFauRDKpQ1zqWS4+=F9sc{j_lG~l9`GKaM@Hl|SyXz6Yerv_3M3^$Gz zzoL{IekABdClpDyfW&QHTe2euRG}Fa>~w+-#Nh=Rg?R(6+!jt(DtaSu5IDSz zcfx|N$dSL{^&2_Zsx)Lbk)0Hd7Vb&{S{IWz0=WFzf4pG1T!L^!c-Yw*>b#Qz+zizL zF(`eZ8}sW|uYF!JH@*yzOlD}D!<8EghP{B64mSigXgI2X%@Q9)$U?ps^DjL>;>{u6 zXkpXKZ(M!A<`rL#K7>x;ip!0L8wYZ-5yk+^XZ13$VxZgPVv{IOd*rRI+{iUJ5Dp^C zB-*v-Y^-oDH6LbeA7wp0R-RuD`*Qo3HFebKN}E2%PLz~nxt^4+jdCYYI`U$t(o3M+ z`WKy}Hh_b@Eq`E~AN#qvmRkdY54?WP0ACXY-8|6&gI`{6X7iAnW8R+Qm;^p-8$HzK zV!}&5DGPMOdDeb{L<1K-m(LVms- z<^hlmahYr|DdXsg=oZ@>c8ce+;KpuWp3*~aH@7@dm$$AEkwxunb_tevtDB2Va^$sPLk z8zkgSdcrs%#r4~3)DL78AL?!Dm5g*HM%FExhCCg_cio&%DT4FA{kr^R28_fbKF73e zZfiir1Vr&E2hw+ar%ibvH*G2kqYFnqCVxzd4H7{jM-)#P(ZO@I#Vz5}-WVwF?eU~o zUi+WAF)qf$>)3Kt*hnV}T@(~CLrVlCJ)#4I&3&10(q!28nDX-M}^{(}b>zlm(c-+VS90~suJ!aw9jexbcN zB5#ou?^v>->+C9>Y&|R6rR1 zxEE;jBVYk91Fp)`?hcQIytc`M#S*^BoB+W>{^0R+_|t#>pa0s9I{a_{cmMsLj`cOR!kE5C7H;HMrLU@;4`?He4PS-681X&1sfc!*}g zPhs)T!f`(ZnB`7T^6s z$|u27xc|*R;#L{@4fiXJjxJHwV%$Z4Z~8F1yB~k!I{J|gH$U0wy85t|uMr=&9HViI zvorCEpV6w5aZTYtG&-5wOF8yPi(A>2m4g213(i zK6Lz=+h{^@qqcTm##FTOkGLsPGf5(-@a_#T_XF{lod<{-m&w?wbQ_qSunyn+6R!OB zjMdgvcMNOBsE7TNb5Z^tCOm}xJI)AxaFco8t>yzP%3o=|bD_D&waitF@O+<&9+E?cWh@suuM24I$s+i=WcM6La~6M_srlI$ z8+Dn#$1|kCJkSqh3Rg!bW}YQ^n48g79hb%U%w+-YJAOD+GBf95PRV==o+364OyN}< zA=aG?`taK+o`>>)F>^@fe4>GuWP%rR`QclP+`O^HJP>-H1S4JMh(z9o+Vlny4@mE9 zZ+nx)3-Vj}Mim>MsM(-4(5I2hX*M6-qqHyq4+yHd&4nnPOo1LuU@{C`^Y@m z4E5MjdE(*Goy~Q>arEuW{b7Im*>L*iyWy|?{Lh9<&8@%r@ox=V`!9x*i<{y7`Soye z&WS?G=QF;CwPE>BPtOK_0^{`5M=QQNc`y6SZ{wU_UJn;nx87j-`7eGL{^BoxHvHAk zem=Z=doo4P`Ou5NBbC)t&j z*FW5bS(ic%@lm?id7$B`%fRb-v;m=bn3;H_pMKzj`v7lNAw!d|jMs#yx6&hPGSq+a z!o$S0N#{Xy)pwu^XGAyy@v-7FBq;m|sdmYlk^2dZ__CJa7XaGa3MN>jIc@AvcF0Lt zvl+}=fu9^VZ@GT-8(QR(brY|p-StOS-ns2?v?!aXl-=tW2gA|9uItQm*Sn9Z6I;X4 zA?ud=!=CCF8`9J<-pb@?Qt-Q~H+=JLn+--8>Hz7p3C4ys@~{p{yaUBse=fcGnAaO_ zmCmD$`y|yB6v>}VH#;W!z%H1=khj^LALYf3H#&}Ul|AFr0C&6-4up9*K;hO`U>>)J z@;g=^Cg&JtdkR~`FG7!76%HiNtHXeKdIiQm9Bl;XD(z}Zb6ABdcr2{oOK28AIVG>L{>@J)D#dzbU z-CX>a*Nbi=EmTt?zUq>04Ifek@AUY|lLe9%pFn|SBCJuXwU|a-Dxtwb-@+ywm*Oqc zl1?5QG=KC#IzotrIaFnop%K6-5y#jQSiq!3c#;AqX6D@)@9ltmp4h|V)?fRzn{Ao5ws`j+(N;Q;wX^C>Q z8b=%hhU&;H5pv@z8tg>2#~snghfBgz9=rk6o>W7x`Y{0YW|Z}Hn`8CRFFIv|khij= zyL-`~SI!k?0D`VKhno+~`rK|N43vrJuh{&$$rDC|UtL_v7B4mo;jeht9t^fYpZNKv zud?7~PFZ;aOY-~3KY_nxBN}glD31&nJlLab7_>_VLLgf$1|aVRA#7p~a8v@P~#VmqSui-Wc@fDH}hf zCt+yAyq(0E);r$t+8qGP#3TIGJgC{sMDPzFM=B)?vO4li>zPkQv zP)PfMg$Hb+NqbBDX)wnkGZP^uV0ks)n_mLTKbwwuipFQkJGOv)C|=&UqMq}lUN*_7 z@ucg?C+BG^|D>%b9*C`P(S~GiYM`pg4YD(N@&>Q|H8DlT)P2%=qI49GiICf;2BqL( zie4r2`UYpLZ(Fy-+mH@qqL_SVI`C39E_X+7Cvf5@=y8n4l3 zOOt=2vDZQ2>$oOqbiRPI%l^2?oBZfZ26+OO%=$1m9_cojNk+ITwuGl&+yKGgrDN~N4g-?@~VbVD|!9bU3PRL0E! zFKL9*hypvIN!n>I6%Gaq1}FiiD9C%Gl_U-(y^8g>x$!lJ!Y|OsvfqxNTndEubOkfq z=qmc=EimtnzF-x;$8ojm5gLbe^tN00NYh{y{!4Ja&Tt^*Tf_w!*9v+EgX1^GnP>}E z`O97m!(HJxmTBY~`u8N@ zevjW~xZVJB+$wzUZyu*>8`JJtp;4OFh5EG?K83aT#C81m40vr4W_Lp_#C1U2h3~_; zF5x==gs-qUJ$8>rhpkK;Ryr-3n085+amBBNbtZMKH{$O!;_u^*Zqvy<;z}+M6&zaA zcd*J2Dt5=m_o<1;WD<;x-|h?+^q=SodcW^<(Aji!SY?3Tzo4N0I^mYxy2`Q{-MErJ z+-~!p+cEcJgMbYx9>CO`=lWu}m;3Ja(u=E4o_x^!h_@HmJkeNR^8+ttGbfXLY`l1r zs58t{m@BdF;JGoIKboU52Vsos6C@-NYZ0Ez0E{h=Q&z?W(Ghb*AJM0ICTk0$-UPUd zCi6EQE^Kqp*5-MOg)j_nPr%EYUz)#o{s}v!oy|bzSIEGFiJ8CQuFVsO?J{rbYINyE z{Aaj%Dkts#hJ|cz^OL*ZZ?~7tYdsses28+ z+xI`541e|4zZiZd!&_dgqo7X803PVua%+CNv$yB8k$q=-S2AvT^NaNkj{IXIgE!WA zqwIKp$K{vu=WVAAZ&FZycJZw`x6#?aWsU4cX|jQ_>Gdq;^~mJ6msnd- z4A1o?;RoR}2WK;E@S8t}2YX8U`M?IT-^dd`MRR_rgJb)ZyUIW9D{DBkCC1m}<451T z91iz(Ef*VK$WDEr0&#R9>o%m1%!GaTC?Qx=lU~>yqWw@;p~0|`OZ#W7gmif*+M7aD zIwW-cMz+@O8qRAb%0$}6^I^TU58Q-9Xqr#b1s;^q@+MK8EfIznS(G6fZ6_3XbX7dJ zL#1DBFzKv041>ScU(#mtFf&|uklzoCD^KK~@+KkVNHXLpa*$=-hU1}s*7#_vY-(+* zpX80Z*DsINU+%iya>~!a;jYSd+gW@2=6lucQ@`Q2x3@jKI6fG5)mHe99Y-J1jyP(S z%~Fm%Rf`|yJ0ILqL;Ni7IN_?1}CYbwyRk(u3!V12GW&uQ=eE$k@zZy!9|8n4suYdUa|LCXUhSb5zc1HZ?CT(O3 zPnccMnI^#)HvuA)yYWoaxDzQAI+2NDg8b#Ci*YApf~4a?1zue&lj-bDn(?*xqj!-v zF6@yWIn-O3cjB2of8&hDmcTUUG2f#NZQNY2z_kB(NjQe>H{~!914^HcD4mYb#y5v> z?zmY{a>pv8PL?1BGKAa0=)wRh3uk!+evifcm#>E7<73~9$RB-ldg;c{v(fnIt;HcX z3=y*M&jL6%KAr~Q=@-sVK39i&b0z;ZXCCvm7awEgrf}=c8{R+tZfnWN$G=x8`TI=10_<=vg#VQX6h z6%EXMvlLI?x=;%J<)`SWm7>tjt?j+=@a*eOnJB=R9y^y}jc(YFUw z(!I)vrNsK2ba(l4D z&E7XY)m!o4O&f4b7T9QEkVTwlPdUmG4M{UhgkYxnif)awJ~QaUoyiNET`6-WF~sv^ zg@K4@EemN=P_$baXcYhxmw|(-jl)+KlLYcenQp9Y`c-!ZcE^Xj8OZtIFVs$6$bX~( z`IdO*ttRu*poq7lq_DAWx=gWnBThO$S9x5jJV5ib6dOLgt;Xbyd~?>f+mXu2b)OAi z>E2JwiKpu;d6S!ZkvhhpmsjY?COVW(jF0XLXZ^@c`AQ(yX^u5yAWgY@QgEvQqejul zhi*1B_~P~YO-*Px;?N;t?Xr=R2`F+SR~_XD4U6$mK9CfSyNB%8M z9%!3P07lt$O<7?>Ye)Q@tNfKlL3%gAM9|u8X!1}4(ISV*?2La5m$$_TjqrYJ%z+?c zn_l?PHhv3`IGD(hIB`t=Brl)sxXYP%;gdKx1kF!)d1(hA<0h<8HyVQ(1(9}U?(uVJ z47oaOjDDkTz>^GaJlJ*%>A<3u#{n_p=9NvuHM;181p@HuTgj*DQOIAei+mF+~W)t4R%!40+aT#xZLB?$wjQq$39$IW!-V|zh7i95ufkE5A zvNpFIZU@9|ZtDPBx+BQ+;AC9NG)O_>;Z{6SF&ZB9skFG>IXD-!41} zC;o_&U6WJ$3T=tf0#k)rj4_&X@4RF)IkLp)m#j2763Mn?z-m=P7sceBT?tDzaQKXq z`O|;)>)rTjPNzT0^#Cl;ATB>}!6YAcEc2?kWk$f?oIMoH06c3NDqknQwxTzk*zf4njIqY_ySbi+}xpXoM>DAi|08tirHRy5W_OI}b zd@-!^;~~6{W4+SXIcUTet@~5CU4uY5tm2fsaa-fE>3Q9euHadGd%x>DxEa16e(aVe zW&z*mTa@yTc;j-hY%=&qx$QC860G6{EaK4rH@P$i;TutW%ZP_AncI+R(se2=9nE)` z<7m#qmS9bd-$o8%sE145!r)=*d{V7}`)JBIZfWYe6V%>{}e^ZAqon;WDFU)E;w zz+>{q2>{QYWi4q#W{ZV)=IG=LwG*y+9_7S(4GZ}%j`xQbhcf$H!}f;qq58nvfzO}b z4+lHz!^^{+VQ2lRk0ZRgI2*qE#m~LY!7+wE`R(5wj$ZwE`1ovNxVYvmxR2f(+TYt9 z4v!Cq9nB@t3lCqPou7JL${Qxq3;L#S@f%8a97&kB4mkmbwGr~fpp~&Q`p-A1HoaNL z!_u!_e={5%9s8{{%Aa|BK07dYV~`{0cp!O4bLV5_k4>I)$-&0P$B)@Sd(K9t%8CsM z>ju3_{~Q;|X-KT^oS&V^edV@6-J_l&7xQT;AGR|V1G}t^QjMx zQp_g_I7*Q3$+Iz3<9OEycz~D5+j+qe$}x(3@9pStSLuEj&aZBVi%Zs*a>@|(!f&Oi z{8_&^yWl~0wRz;$*qkz_{_^G$`l8;^{*2q+b~t|8zt@)p=)@b)GL)GvE|0X67A{^s zqEc;^&t@P;`p;~j!_)LK)*rd0{OyDbSY$+hq@VoLHoP`UJlO?Lp3vU1oLr7RaYd7*PcXAIn{|r%xTlE$xCF=12i;QMJ3Cv-5_ROG-xAy1;doi}8{WL#`2PILM=JWkcHyos&(yx& ztKQs7F6x+bYgy3&ZvX8LlwRjsyg%>CEK{c2dO z1HUS?jjuoasRue@2+vx4f&G*Qh-5EeYB>Dl$>K(6OcBrIc0B#C$8=&$P<~paZDZ~B z0%{8nlwVHlMxFQ#M;v?**^hBxsO>>!!h=otgriX#g|m-OusygZ|M-*JsTaL|k(oYm zif3D`n(qm?!!#v$IwZW%1#5=6fT)W)ycQm>Dd^1W=^!?Mcx#0t4v&tG{83SEHqf`* zZN{*qMU2J@Ex?0;oNu`5;CaHqZ*tw_Eu-3$;prf5xP0W);p(W_@bYWq!ud!&4QLp= zSYGEV20!;gZZNrdYLLWHg_4=`ae2zfZ*J}6qp0NJhz+lU10P?wySp#?U2lkOYCy}t ztaRxdk|6^bOO3@{8(zNenIt&l9h7)u=S_QXfHh+rz>{!}i_Yb8hz2PPX80~v;e5OR zW#WNHd!?O?KXfG>W)tyz)G2S$U0yK=ls-LBx*V>!VX7=B2R`ch{!9}MHXGUS;t3sS zDGLVXHw;|RJx3YbA(iFvtLeHyW1)9$D{LxpBW55&F1cZ&7s|_TXd$+8VNIY11{Vxi zcoR!Ec=(}n1~`6$tG%tnz%OOdo>&qi20sh{T>gs3_qosuI-)UPlOCyg0|i+%n1sG2 z1$HZac)Q-pMs7>k!fFr_TR0iyV^G6WM4Z>WzqjvW3yu#ChnL4Mha>rSh2PYm6{+v< z@`j-|Csk%*GOTMr!iP%X>w%BTg0e=B$juW|v=2YkMH$QXlX#MiNeFqT#(49INr?2B zi6E0GwF4$Qk`+2{V3DPk2j^3M;#gngT478qv5~JPXDVn?Nx8BSt@?0#!$g2I6Pu?F z*EckY*~tfyeN2Y<*MyO>!El5F13t<%zRukzrwo)wSsuL%^BUItn`k>n@o)UFxG zBCC%GBr_>BL0x6Hw&}VSv>UZu6qdc^S8mH~TKIyM$v^cPx^^vaEhk>V=xltOE3suHu-(N^ zwlQQ|BDy9K?29QZi_^f{;#tN<6RHX>oPM~;2Y#p9sGMi;{6iPDHwrAs93OcIhdA|} zU<)g7d^;V%?fMCo34CM3&;MAVWx!7e^ewPq8Xi>mIk@EmuoZ&Pw)Cw#$CXhZYA+c4 zlY&9mZm}aXd7~jYk7-AQ1uwMAAYnv=9jYPEOwItFST+wYT-0WCixY098+kY#u=KO7 zmIxQ}*iO^o@*_u(YOhM%gtBA^SFoXxB*5|cC16V12rdisP$owF#t^Ul;wSI1TkVxR zcnJUWYu)(z`~Tn{jvHSE(IK(~=6=Bbh-*uT(NL@f(Di=6^w5+fHrx59aHUCK5T?QrKQb-SgU9amlv-A_g_q0u3XrFX zCNTgZTYri@#uq`k?T4b=%~bxu;jZwJuE)XOGECu^i6*uvd^hXznsX z*p$9vOlkMrE;IN0_duBY-_GxFe%32)ndZhrSV7{H9enKg%Q(NpYh`5LBjts8uuKZy z$2YEpt;Fj$wmDN7ABa0~#yd%O6^!9A)!qvFunCX7y3PRdb$IbhrH~tbRjns^f;VzB zg$rJ^z86g-3hCnYZK$tXg~K1T;~@a$0?IU)qU+5AFp`*Ck62;Qr>q4?thizT7JEZH zg)+uL+^2l%Li1Zq7WC)slhfhk^klfXWMQ9hWr~e5PLpsg1EL#ec*Nn-kN&jb z7}KzsKtG6E7tb|Zex4IXuRbEq8w6~W2CE1yad0x#MZkpTqNJh=Ep+iQ>#^Wx@487-bUITy+T$HxQYSACG7=q9?Z&Sv`8wag${d?{E1z<3I_SZ3Ye<_8u=R6#=vv^1Gnr!|6Xheo&E|tQTUe9O z9H04V9*SiVpYjpg6pYi$oRsp%uen@%tBFl0j@;uLQM}=|x3e|u%l+c$VEFdc;qar^ z$HO--4>Y&l^EbO#yyvYijtL|VZ<5`zej&r!(GPFm4O_dSJ$^N;ZS4+MJgh1C*pxat zJn%!?2M3%QvSHovU@#9}^S~)(J#AE=r)Qdr^I3yzh_PwNMkn7IqYg|DMzb!EWBIpu zqfLgq^YAJgQ#{DcgW9Y^5tofej_hMS=9y;lyn(Z`voTy=T@3F}c{uq-GF=Xrd{#la zWX*%k59%*(cTqO}EQRV5hIJbrW@eoyn?kfHDVk!W*-&1RKlPLPl(hn%PP4OZ`N3mY zgX0q26Uqk8Ub~Qsc82b#$CgXH+>S+09P&yXqcXGc1WOOPd035@?gmrilA)al(nb;6h8f8Sqob?ql4%*~O+xj?wdXx~??{WKo}2e$~OU!G&Rf z$hpy>$;U!7pknZm8$bDGAiz^Q3^cYh=7MW7C2Sl)N6V zG9X-Kai#&^<@x1sKMrPOwpXo9OF2R$KBTn24uf;#98 zC;j|Jm-Wq!y=`=OV9WqM=VCKZgfBOI;+1@{C6jF04Vw2LP%;z7;xQ?D0waS=mV+?T zcHK>V<+XEUg@yrBBqb{u9FcCd11gH^>^|De{uqE{A3FKvx$T*phq_uSc)I@UNouq(lLWJ!aUJYY9E;pa!jV`n+E07 zJp+8j|M|vKZ+fu_#-x!XU1q8`A0-!Z`2CLKqbS*zJ zG# z=|Ta4Ych?x97VDOrt`fIJtz%FGZRAPH&K#-4!na4C)=^W%UwEwCh`Pt-VRHA$Eq-0 z7I>SM{sbI<@G`<%RwBtDt93w_`IwTdx$V=)Y6HscNCq1C#;-8aG2Shx@xZ0>#ETo| zx~Mxap1zOF_~*ccW6UFnF+BBy`VEQNa;4vJmPa%rFF-g7#TdexPAXk>BgR8O9&tZw z1rlD^#aC|8Bz^o1Cl)=E^7F$lv%sO@3SaU1 zxC_weu$RmX9^}zM(QsWb!q0Qs%f7s0v70IenbcDKBCW~0s4uy z{BwNisrSbeEih_Aczi8ih3H`-HB5Xby3yZobDBQf?3%kw(l0;yj?U8`_D11d-gJRm z3&Sq|MAMsDRwhuG`@7Z`GiG(1gxWoa!WHk(cW#*}+>Z2}Mh5S(F5#^&G+q|^a9zd& z$hMA}y9^lORa!vO3qiS8>D*v4{BbYVZ{m#}`zebGS8+|=`Ik)#o&2CIW8o5B zW-*>HaxVH8X?$;Wfi`Gip4Xa&z$s49y^SO8s#Dd66B|2)|lWOk3dcoy6^VCz# zV=pyqxRuHLgSuf}-ZW#rmpQb5;N^#pHSILp8(h*orID+-m_Ble2Wcw}=0`p*(cxJL zVDrl{)s~pEu__=Y_Rb?tGykcoeE7O|#v-JwM$2 ze2sMn1lByd^vj%deZw1ReiKJ{O0hNwsXu%}{q4IShBt427|zd5z0Q?95B_Y%*7lai zo*Xa8M#bTg^7-;mZHjMzaa82(@b2_tc>Dg$Z-)7Vp4)rPg`fI+OB_+?F}HYTorrHi zWxa+6q1l9Cb%65W0aogtH)EO%6rk5LR3BIeU|o&+!CDx2@z&uX=booSt!f;icNi zmyr1X)IZ%8$*o8Et z!&XP<_{n@dWaH}({_v-&LhcYtcz2Gu$f85TJ%s}}D_$sri?0EGdHZ;74_!LxAcAuH zbdUpZkbO>{3QqF3dgzua5G@w%D|DQX}J04`%zbUwOj)uo_NXY{`YwsNu4qqIJ~l3 z-=?a!nizC(ljEr-Zl1i+b-)um$as7-93Q{1;i;ZI4P4l;BOm^_s0MmGap5PTbOTH$ zoq--&OHQH>-J{$Qrj9htp;+b79kGm6Or8^JT&nz%*d zZ$UM;apLvCH&P8^Wb&jBn_fKab8UTrt0#KyrBA<>uYpJ1c>PqC>>HH_Z_lv_Cic0h z@Mlo0vPCCs8jVlkFhJIg(d8|}#)KC~MZ;jkgJ=2umYjaBM~XuZ%1=BtMkqJxkI$m^ z!26lXqn(QkAI|O;o+o_R41)u2`oJ6QT8-j`jAASdVx+Ed6GuPX$l>eFI05l^(~1o^ z17uZ3#Uwa3&WRPqHv1Bn;V$KA3E1Af!Pm$1Cv07e^nOP&6)Yl@F5y zKM_g)pveBXY{{(wbjgI=@S}>8F7c^D1s=>{d$1q}<>Fs-!P|6vLye;!Ya)i67RQ$s z$y^fG;PS-6AGhD~DZJF0bfAqfDe9iswJtqzl2i*2RGmmzxus{hiC2`^1e>idEyTQm zCPzgmu)q3qk`7%(50FrYkkeEVyt(D5w9G?4aP$SB^b2o(fyhakaT|{t+Yndz9kYdx z;xrx!ZTTP_@U%I+x>UY=k#QSn#^~}(n1-@H_d9+>b40tjv|{$fgI3(SmdozuG?usx z5zAQr;%?B=p#KQSUxBjWk^4s6mN{M1s1G#34?44HebZP5l`koWx=sQah->m=J8sJh zEq>UvaD@n`Xtcc+pM;zSl(Zp-s}HvWAtt~p(#V6ycI%rOg>7BN!KL%2{(#InG6bQ7 z)&_cAk_Wk6o{=fxx~gH~b~}VlKgtp$Y(q(!jlR)HkdZH7t9eXjn&6T7kN@0~XSjyKS-6Qduz+9T2YOtO2YNiCz!9J;W4RjG-)xyae$cD^a?QfZ zp3>~Y%e0V{xSq#|ZqU=mq|fk3cOGV54dh=iMoqMz^FM^cq=*||jM81kVMSI<{Fuq# zL*b{go6^%ofAMPlW!~;>aax{DC#W$r5ZXoeq8~eL4UWMPKR2Bzj=iy)sks0!(Zv|Y zZ}d;@5hpXH+2MVEY5sQmkt;ll#{4GT2Di-1ln;bWxXSP3cDPB3cDYQ-q`Vqk@o7JC zYO$J`#SJX_$MhS%plHf8Z1WS2f4NQcFvrQ4--wHQk!~5c=%4Ch*}W;v0r+#DE#5N# zO_;+cz7Nq?7&>Eo@`M>M^ObwerLHfAyBp@NSDwefuig~%+(nZL=7S!LX@27rJup*= z!lQ*TZ6FQkjc0x+dzz1%K<*YF76ci^nGJjz{98Jj zZ{-0;8HGba`)97p`ULZ}mPG3pEUuE59+=Oq@$eu|waI2hj`u&iz8~J5oDXl`y&v9rLH}g<>tDVZ ze(~o0aB_AvT;EB!r)xfLe|vY=ZwT>r5wc#KUkqpOPbJ62@Lu+tcPGQi`!mUrZ)dRq z2R)loJVfoci=+>}JI~yj9I|eK{?Qu`N|RUCTl_Gw$~_MoCtqi0Cj;LLV`IyoA-LnA zZjSa-y;Yg8c|*F?1>*76)#3iO%k2~IfN9Kob$dTtN{@bHhX;G*rY-DjZ}^QNHo>fS z$wm257XZ(R_0I+or@kN~>u{R4b3%-M6szl+!u`#B>4AF2TS(-cPZuB`b8t>*VI7V7 z$^71J#+5SR@SqNYqwM)!6nt0*U{fe>qLELv8S0|a_QTB5BND?ZAj#A&&^K=!(H@c6 zI+cvxJiO0aYF>j8f9h;D-Ncmi$$JOmd_}yW$$Ag@W=#iO@$fI}VoFjVsF>xG17y}@Qyy}iR6FoO|Kulel@%};QQ}u9Ae&&`<~lu9J-oOY&d#s=W*sLtU8vo~u;HsRG1JJ;(TMvyTdrI5 zA$$*vQ;F88_fM6Vn@h=cJ1W8DPTuwJ`~OKF!QpijZDP z0B>VoqvPM`V+TIx?q!*HEJAP-e)3mZQy8#{2e2ByDDOjHn$M7Z2_N7wx-aEX@Ky98 z{aXIZK>TGBzK@w|Twe~^`1-v+$djxjU`rR(MOfz2Iv6}P&{z0JV>((lW)m6^*gyC6 z!Do;zT-Y?oZI})(Kw#*5!vaej<&Jl>;hSLFA#FHa(hx|iaEmmxaA&`9u?e*DB^GvV z0yd=xxJ2gB%ca>S#|saf4k~vBD=0B;V~xoTfb`&Qj5|`|Gx*_%KaMgye!*K(FZ^Z~ zuY?~R9}W8l90jOadERry5xD?JfoeJYD7E zAvNHD7aN2OmU%Ob%^T8yFLl9BfO+tnkFJsylKZCHD#-KoY*6{8qBwpkO?AL^7hcK- zbm*4zuSt^)MxM?hIpXq)H*eVGtsvc?HHgCPBMoKXZQaSvMq376$l@@i8Cg}X@RfT_ z@zFJT@!$YiGy$qjE;jDG5hgAke8|A>&N{nG9%Z~4seBPe94$)N&p4q@;!hl>%4wzV> z?+lzsk0*kZp3)?M4K0eq!diYLm(vp&Hg(yA!p;U6e9)=umIlDFGf*Thx`3Alhty%= z*z{ro;CiM(8}i*;Gsu?=h#{aluW699sR8+>+F*1@onUaCC*tr>XS~VC6O*btqz@Pe ziQ>^VJg}C{rl2Rc$ffwA8rH>ce{VnOkN|b2{lvbNTl8STpmFX<6Qsguzp2UzlRq2T zG7;6DCU)>4oo9o2(Dn<<>U-C&n%Zbar|#G@)uu+ zIj&JHUT`H_Fb*`Hb_I2?O_z4tVZOS^)IFloQF*}MyrEJ5n+OhboF7^BZ4_FzMYHS%QSE zhAD0Ux5pD5%xQX9g$FZ_vx>(m95Bb1o9h_Xh4)b5BVCu5xgS`fpW)`P3U6H5%~UEq zu8>qQyqF$FT63GgaXT349>MovbNqM*f~4>*%>`OxCR{=9FL(J%y*+*kpLD;75A?X; zL%)nSR&LsAU{2#aigb?WH>dxc{~_EQKPjxEeK0-sAPfG*@PZy+rfJ33z@*nc?Ve=B zb?#OEhjG2%6bpFz&-CF_Sn&3ZZhU_DtfLv}I=^ug;S6W|j8+$Mt9#yRUZ5SO3fkif z=C}oaBg@<_{+>1jaf9m1hdMg);@)9g^N;m6@h5!aAa_BzCz_aQ%M%W_QO*BQ8Zi!; z`Jr=OXSij$<+zi-%lAZXzY#{ZIL2c_JH?y&(S-wL1UtPYuFhQE@cI6 z9qZ@0qUPA!H)|I@{><~?l3n@XtsCaV&v@H~ zqwZMv&zzjRc=Lfa>+w?BuOG&A`)u>aCY$HFPCHQPKn z{N^FpJUoS&HWrwRYo04N^Gs;T8~Es*qw;t-_POVp-+lMp@YjF+b1%~0e0VavJG~ix z`6h3#yg$A0!ak>u@J(^Xdgy`;kzL;EVy$X@UA#XHZ{NNf{>wlA%i+KLv%ehv>Sx~# zzx@84c%6CSpY;LqL0nD`k+5D%U~Pr%Wn`Q!~&k$s@tH4na#3|GwY zF9+V_^MlE9v&Kc3-{?~U?go@+&+~6Z1FhU%6Ozs63V4VUnR$!t=2m6&ROP$2K{Ulp z`|$}d(joPaH>x()r7HzUeWs&G{Kk>!X!q15)>)|M%-g-;3L}*pb&fhhyf$ zOgz}knvvIVC`;v?2U|H_l5a*)r(u)2p>mY|lS#?x_VjUBQ(dJ_i$FT%Qx80(t@82) z9PJKr38H9Ne7l^Z2se4CT0yK``GhFR%$kxnZQ5r${05k4sB38l)K7HT*2}De)N|@R znWlZF-cyf}H*1RMlKM$pw-4g9xXzL2kSDprMV8Ll5vTv_i^sM41_ zv`^`Xc(gSP>sGvNcS9SxWpgoYlg&uVc$cF@x7Yj)z5U&d;o0!PZ{1R_$z1xH)Jtq@ zr{%Nk!c73eKs~?SXmAQIH#F!l_+>tEFUJeSow6t>H#RQ&TX4b_`SsApEm)wHb5-2n z=5b;kreB8D_=n{M2=ltb!z6~sc+BB*>3t0>(^qRL==>u6TK>yG{4x`Kp6^_)&qF)v z@b`b}s;2n0spF*j1m(m_qYThF=-T>E%Flt&(ZcQEFFLNc6`}RDF@W7rG(=fu9(N#~ zkJ2&Q~lWMHP?!iYF$fXc6#{qP;ECUW75yUWYmH2Jo{NF-(i2 zS=fz+4udWl9OTGc3p}MK0DAD@rJJM}(Yew|?(Xgl$1k#>ggHDs@Z$2e1`#|l1C4Jk zZQ}@z+%n7v3zzuO(PjY2U_*= z-U4F~%TqwQ(dq`gyTcjKyTj3oa z(379~VNk*#&^NQ(9DS40V4i^&x?+IsBOs;EJZ;7xiW^>zG~|0|42&2c@R3voSqx0p zH`yS1;*H1T-$DwPn?=RZ#F56O~mPDFHLb1ZGJx`XC-jWYxUGKZ*WP8 zq@Opqrj4$;p=W~&-fX0aAL*GsH+dnD(z5W8S8nDxqJgKt@`RiSrK3EJ#Re{M*f3!; zjtxQdL8g%tBcU@ea#?_{@}cvg+~lY33Qw(|97WG!ZDyj_ms`q`?KNu z@4p{@{@u@q?|$*!@aFqB!`bDzH?tVT`H3*qr4Q2IC!U&;4ygeQhB@|=kJUoU@fdvA z7MZAf6cwW4_kf9kufnAS>(8&g%bS5TS&&DDx`$0U@x}$=u79edCLIuF-Hd#QoI2<}ELep%I(+1jgGZcJ(*Z=E zG(oa$Y-l03ukr$K(SU`&`$bG}<_#S>1muXUxJ_X`q+z-ifNeB>yTOH@L4McbB51hi z3p=RL;cYzCmPyPDEZ`bHnp+5B^FwE)*U^Rsl9?ZkBwouiejtTmn>?7lxy?mZdbvsi zpllLuqdYi6fA^eRlVroAs#(`PBW*UhXZqe!7ADUunv15 z9H_;Eo=5pdyerrQJuR?A-(ZgG!+;9wxfd>^37K#)L3ViObdj!y9{*Ta4-0txEeRy{ z$M7>6e}gejgWe4!e4@kj>h19{%lJhI&0^RhZMl0Ku!OI$IUZD(j{UQ6V2dChTv`}igPF+JTFUcW{+;_dI~M%=P& zM$c&NANl#NC3~4BW4%S5K<_tB*;??2s@=Z0PsESgW^}i3TP?2d54lG;?LMqQ`M(6; zy9;_6f>JJvw2L$qAA1>(?fa|sz@vUdE@H-o;MOSw~=`+BIuY(SfIwwi{awu4KL;x zvZE)3^Ox;B$ga9b+>$2?&TZZ<8@$JV*vv;X2I6E69^TA1pklK??)jzC6ceX0E@sOx zr}0}#8=H>rxy@7NwfVM>=X>y0I<+PPFXoV>?+qNyqp%6j={DI!OP&Lg)Hr1EoUjAu zBT7h~O`ANW4Wu1-9ENQ_^Smt1`?M6{(F5TgvsN7Pqj3D_W@C%Dh&H`8z^30bHhv@~ z$FY6?=45zxdO4h5-VN_BZikceo8j$yj%Q=zNAac4_06qe)1Rx5T|Amj-o1M_{N-Q% z)$nJ3_UE$ydU*Se;|3`&HgWh48V^Tjta@{OHJqHh8{Yiz{qXk952AfLynFlB$28`< zU(BsplW7}Xnx|h~U-~l!)Hyc2{KlUQ^#0s{=$U7`#!$DoSl80I%OAhy;a>O2S{(BO zHY47io)2f2d{->%K=e47J8(20n`^i7XFlu`f37&`hkDFLN9OjV>+jV|C-+Lj8(*wr zAd>=Jk31LG97H%arud{tj-Nu8k?>tgI)OX6F z>UC%qY{Eoen_>6?$2X3)7#a9pI(3H^_xMiT;lb|k>h;TEk9Ak|0epsKQ)R%Bn|#7$ zYlDr<^?_pv(JO$w=#RBN)~4V|c@lR+^lW0{W}Os0v9b7^H68t^EBTh!tv41=FRq67 z@6Wwfi(WQ1(Cwx-St%#l)aB)s!z!5S;f!uqSt>r;6X4g4KouLbgIaiK)i~j!x(eDH z`Kx1c27)w?1;%!oFgyqjVGAYp%<#+LVl6aYq620~usd79e>_>x1=2 zdGL|Xytbds#(Z0iO`s1NI9&Vbu+!5sKk>yARHvsWehZJc?>JiWUIS>3C3wbDZQ{*$ z*4PxQr?G6Rd?dFwjr_zFx@3UHz?M3X&N6`r9vPVcG6^Fq!iz__?GT-E?(+5~m}p%y z2~rqoLS~)Ifw5bGMt@S2==l0&#u)DwOr?x!Ff;9}KUze>+>JIfQ z+sM=pXkACt?=YAnPtaHx3sGdz@8QbZQVN0(zs8e& zL!8Jj3&j|G45h%ERC1f8F7DgSL(szPE?(EKG;PIAz4erwj2?tcjEME6{~9vVKBpBy^-*9a7@U z?|9fIYoa92XvHK(Cf={}jjwvh8^BrKhiF&%{q{qUi>9OVJ++YlzTdWcQQ?ZVcjGlK|K^8+_8dC_xT3%E2iKq? z%9O0(3*mC#(EB}Svpe|kl)vcgYS>0oreN}yM2@{chgJT<6(p>Sy@GBP4k%pR9}Unn zQ~HP@jh4y-G<`al0B-6VBt;)n{!lh#Gf8Rk_k7Dtxt;*L>rff}kelx#@o=b*IsB-3 z@%`=a@$PcCzd6@@S?u9CCAOA9F=gf`CR5O~u|b12Ou zT+adOHuG1{U1j^b;hLi`cg@^3-&W2>2lKdA$0Qdrd9Gz1S;%KD%Ull~`$0tJdzvS) z8G_ttPt0p2i*WbiO9q%rA&ci!N}G9d-rS+AqF)TUW4(q*<{`sc1nGGWuJrs+CGpUm z_<3_n@*xX;_u1f;-^}l_@r6FUjsitXi!|Yx2e27T+w?@ zWnn{%x4o=G85BVIWQ~b>Mm?SS6x=}i(aeEC<)N`B!}%p^V(+~PanAR>u5VqwVkb}x z%3Av4$7T|5?PTLCb9D@KybZ;sAi#QsqKp79>WCjimIv8cv-4*fc(7GGh)+FaJ%o)W z^1rpYJ{;`r`0X#2T58U2p5#?&u%^N$61ikO3Ay}muM8VmtTlM!$7?8TCbE8^G7_)X zua1Y~!`^*@5F~S8Qw;!jV;2w&Lx?sW3(4Gi+FGrxyd_tj2|2a$NWNm7l1;l z3|uy{{b01{;GeoF9<(FTd*ch6_DOwrJ*NG|n3s&(kGadVu#|apl(w$+LHerCq{X@r zZ#5E$_17PL`*L`3lsd{Afd1@^`Vs1`j~{fIs11rI{eT}dr|cv<^$}UnS7eb4&)E#m z8r+Wbbab#c92{_zXFfUNwkPqub|_xw7uP;E^bK!Ss{N_?x!t{gcj5=TsUH9vd*rJi z?)WEs<=svKy0D3EiaUi@zY2uMqCa-(-4w6z@;5tv=;Y?Vf)C(04}|ry%y~@kP<-sg zu!7ZmR^eC2FL2ny!6Q7zV-BCA{Tg1tSJ8{~Yxyq&@ykr`dA{ivz6QMU^?Sen2R~Jl za00q7*{0&q2o1v7MOdRV$bvp`fKG7{@;_M?4g9Z&O7~q3saEk3G)!IfxHV-*>IB#Zgb4E`d z$nwM*gIWw5UJTBBBZ;=WF{QA4ziHhYP=3W;<>ebc0|lOTQ#w4w<{L4C2Jy;UVBCO- zn+ZeGWCLuym5FHK(Vl>VkL!WuplmZhuR%IDWCq1+qGKY$n_-y@l-z94sjgag3>+v2 z`4v)rjzHkeH}uF8SPVS*E*b+uUbVkq^AY{C;iZ89Z$S~4s`gZ}WdrYtX?!fD3~k|7 zX>RUn5TiQHx6E9|q(i+@J$7!_*yzjKOleQ|9%wy#sytIuMMPQg{VdX@KA;9BIWVFg z5ts7wz)X2YCmE;^H}%Z&I$@s30*3}@7eMMVZNZyl3V$j+-!mw5{p91lsm+7+|ldj5+FX zcV|x%I-c?pdq~I^Y0~)d5GPesZVdS5rU9F8yf{HQT9Gs!Xu~w_KXBkCyg3ZA{V&>P zMl1MoS3;A2vbd0Tm4btuFafxOGsxp0VffJ&k=ec$2RTC{+c!H%pa8F{a830&bQxQuYl zWhw)ibVdeH&Y^$)!%O*PQ;kUteFlnBP-v;6#Dz{)aW4xzN2^#q{=}zkDTtb7dEC~* zdz1rC#y2?~gMjp7!KaThZ$aJDY$3DpiC^xN0(?k|2^o2i?fx#jt!t${%58=fM+SEp zaQsBa&waRlPRG2GK5QH=hsQM-{Q?Q^Cw`=fLFwT8_;34`st`7tHu!6#Y&gk$V{$GQ8 zh{wZtU=?1z1$>3|_8i~)3+DJf9Oo3)$D@5Q2BUrT^w5Iq@x`C}|L4kT5!Z(;`l;0F zt;*lk@ewzR^B8`PTkyAhgAQ&U-@zk*o5Lb~Obf|xj-UCt&S`poaGgFD!tI;Ff*AeA z&HNZjYL26=*)D%azadSSCREK}~eQg*~{Ui3!Yc81c6)pY_&gWsP*s z8~zUG%uRm(jGtf(Yi7drd|?;blLU8obx?L0rq+J=ujW&-~kST+?OlU*EopE|Xqw zfPS9tv8u+W)Kc=r1_;Lwo}Kenm*&lyj(+k++nVNjnlocIHZ;e~TTIMf`4&8<1#wc) z$;rv^=FJbo4?nya-oAV12TABMBjli^DK zJI&G28QMYzwXh$RQC7MtAFgtgy8_T7`L+I>?-=4xmL7jXhYnyPD4X)N9%Tq8zHx2+ z1=%mJZoN+CH>Ff}+1TNG=ZfGoNr*W%C(ocqQc3xz49ElJ1Xu>GWWbm6q%oWHS z%LmB|^$BA=Aj=&OPTzWM3Bvu|&Ee=^TlFG?b-w#We$h2m%ctllv82J~$`h|sP{yvS zDm&9P8?n4LrZ&2}Bi=`Qmdi(3as(f14$z|Kwvh!rn~?A$zuP-o{;oe8y~soRaQhY{ z?^OmV6ATcZEF$7o`{XB~LK}dR_(X9(F8z6ogMMT?K;h(>c+g`O$3O~$rmgeXEkoX@ z$9~i9_EtLO$jhu*F@N)S`lUBNaIHGZL)AR|?zOQ)Z)L;10ONIuz2 zJ2==MUcSs{Y*_cr5tck$PJfk$j&JWj4cEM3$NJahmEVRueSd1bQ(wp@`7cO5a*~wgSino78HhKbOC+WCf!Krq3M{BvE*<{t;7D*HU?Of_RT{bI5#dj z*c;uD*o5J`N4ze6c7Ez7X?W|1N<`RHj3oiqag7PDWxcxk!V@Y>ng^%D*mP;rxC za?A~#TvR?~gs2Uz)%39`VSdj0dY85a3TN6OjGLx6QLL8?9I|Nut!~uvXX8=y(8#b!Xd3hlH+aKG^mR-h2EF=C8|kiY_T2c8 zfty~PhwS6@6u)ld=wy5gNcv!)x~>5vn@{M@PlE8~lsB!Wff$31L4z6})1ZMEYT{6AONRN=AbbHn05V7v%#F23=;9fduk$^P~Kb z*JUOeWXl3AnEFGfWD}|9%!NOR?d_;dMBKxUl>%N zM)b+6|Ing$$^{w}03Y=0%?hQ@(|zcI;~O@%G*I8(8IF%$3|l)pj*qNcJT0}qV;vy3 zq1~8Wr^FMTAv<*ixx8>7{R(-I)`6_MMe!sAW9LHy8#SQq~0D~IC&rqC5UL0udHdA7Tqe`pC>T+k+SkX%jX z@hxWnenR_=DC6J&T36-Mn+4EGzGNN0F=mPW&BICoqvR+a38J2dmQ5d!gg8t;Z-P3k@(qEm z#<`S?gHHxtErQ9o1n>Alj`G_G6+#)xNV3QuJ{W09W%rRV+7a?OQfOkMGuiyiC*?+6 zCY-x)c;y%u!jk9Up?5fb=y5Bid5bQ^+T>T5YYXy?e4#EIlJJRKM#L{X8_+3pjH#`U z=5bze<$jYm29q?tqg#?;8vzbFg;%}=RuO^bC8sm*zw_hvj^CF~-ZG7G!kMU=0H<+C zo3a{)KmOyt-Hk6GGOdD^hX=rUeIy)MqUjQv$DPwI#TD4^&MeT=tfX!BJPauO-1Jbm zRr=}UU>0!pEkaLMuoSNgUxgEP#6>2;VwUM=e(Eu}hOcm0BNY7@r$LYJ!ydzz($Z(7 z9|OILc5ZrjD0~rT)aa)lm==MS=?i+?WB7-{;-^38Xk;zWNDsY##6vps19RMx-+IJM zVS%Dw#Fu++R)zJr-d%n<7IAHiuz)jJ%6uyK@;g*^XF9*34{NyIKjFfYU;Gu$eJW#b zK$tE}aWM;NV)yZj|Kx|~GOpqxNBNg&Ox4`b`)|L=$FMTvy%xV?cl7jqtKt<>fWJ9B zUMqJG3vs)!-rt8~s=w)RfjMrOU-0F}w%4#o)Aec{K4AqtE^#V!fodsU091vQXNuTfTvPJv{LSn8sw()kL%($#XkH2He6Sk8E!$F@JA! z^+xD9R@NW#0A@Caa+Dr(Rr3<57p8HDAAMnMlJU?db7;2_f+Z8*OMWhcWLa-u@jB}X zo+ml!v~?cvgdftw9ywX)W?ssA0P6)=AW!@{vL5ibhkhAu&SU0dk&jIgHsW|=EXS^~ zPE>0v~q==Zv=7V+U=d>P;8$_ zq&elwqy6E<;cnhE+E{ZsoFa5`^4{x9=Q5Y)IY}sMFg(P`+<#4T?_FAdk31|K9kOP1CCQ>&>?Fz2m9N@uEI$~DC>@*B)sY#^^W$U80i0){ox5LE+Cj^}j?@rE!i_2TJ0UoNp^^uq0 zUDwafhf_|@QeCI5aN-c{`CffXz41pLQhrX^HnPzE(bM^r+L-v#UN>o9TN}gcW4<%C zt1_jHQOCBt(Y&$AciPb56MssD&(ydbD6i;}{1=S67!Cf;5QD$mMPCqi=nCd^*o)yQ zA0YUoY5$08wh+X@O?up1diOGCf@ni)cKHdGEpa)jQTs{#t2oAs6k5ywYI!^>AMbQ3-B zlQVu|K|rVJMQ}PzI#73<#BF>)*`_n)M#RkklaAMC5A!w`Z@6&0;rWFJBA4{Mci}m6g3-lR43TYlWx`22ebTi6v zbI|#9d2Yzuv_0U|0EPhqX~@lB)ZuMlV?DNk?ftFvDP9Z&;K_!UZ*+3A;pIUHaXpYo zy5L-&bVK9qIY~FHYvAXne!PL00V{9HWYEdrny0lG*lO_Io-)Be>u+f3#>b!>`PqS#}ixHszOr_Y?7r zEZIPT4@BzBBm*=6?0qv<-aV+1L7$KsPg?qUzyZ#@m@KHBhzD)O^#KE&%8!q#0^siC zw{-Mp8j$kV5d%%PF=SD?HNdk@H8}TEW`~EvkAL!$;o#^HL43p^ZIH9gpGbeCuc4s_ zxs(^jD|}G-!Y_HXgrgj8$4bK+licW=KCUk>hxhN^$;k(T8I&s*YMaS>Hms;y)ORsb z{iAMYpu`3s3iQN8I!zwPUv$P%1?wtDIZewzm!lP~H8}HekP`3N^C!dhPR^&_*b1$Z zah{pbAtv%uN8JW#xRQ&-1h+Hs9dA(RM79^T6-K+`$w|VX-(26+#DJp?r9=5iYlNu7 z8y&4SHDn`7CmMqYc6T^|DP7J&;E`>o$kr{QwdDSCyq`Vy)buGTlMh8*pdt^<*qJV#=O=Q8n+ z0dK79r*Zg0nl=+mkT?Z!wT${F*%nvz0w{m#jp~NXgo}wgw8kMbaocs;uu)w2LZie? zF9*1hCW*#B;=#3eGJaz$NTZ;!e6GuwydS60(c{B{#2o{s4- z;jKH|EpKKK8WZ$a!l9MhQF5_uK8<(b2!_@U{H5#m`=kFq*!Th}AFCkwSRDrR;SbT7 zMnC%G9v0%tq|Pt$=xKn_-|?#ORkQ^aHm8}xDw-ZwW-%v=Y00xd+o#s!%ilvER#3PJ zKlzR8@C#x1C8%9R+aU2`k73RfG!t$N>vFt^p8&thFh2V!CdelG@G1XAYh0k#X zjeAVdl|8F7y;+4TJg^#9W;s4%nK=%W`&aB9Kck!D3g+R$Skg$b~ZG zrm>iJOpgnXies-li+oE~Ou^(|)~y+YiCqP$3-D`USoO0XYElanF8IkGz@Ea5Z$S$< zBUkAFSjJ&3(scYx-;fQ)ux5e_o}`Tl!e(sh9nScM?xE+opqH|7$XK843M{O7G$L@k zoyFYV^YnY>%FNT5oAbcno#yg)8ry!kW;K&269d!aNuHEXwoQfLkB8#@Yrr@BW7F zPdo5Af$w>%>n(3}@!hU`Cmv}zJ%)KVrvq`sUw_Qw#rf&*_RaUh#o4Ln*^Htyij}A? zI}GKiylL)>?pWtS&*&1o^TYav?C7T;YYWi}`a_#mqW#QQ{LmR#hhZyy!jvv$?Rl`u zh0TZ;hezIQM3uY|1Z-(ueSEk-9LY!}SqHjLo$M17=QCFy+@FtEQN``5xyOLHMoP@)u2h6J?zG`-9?~a77qp?Q?NElad+?;IK0>nP z;dI_YU2~eOD_&lldjsu*+8y8WIy%@NUcEY2{W=`Bw>G@-mG6Y{AorTu9xpPSn|A^E z4n${|au*by97~~ug6(MGu^11%7Zk4e#9irDc#LUAT(jde1U>O7=>7AsUKU_6yruaF z%{;7!hk_ zF`at7lFp_EA2!_Qn^`Yj4#zKE47<9i5awv^gdNS9s?7oOuC&}iw+>wNCIP2TmW?03 z3e8b&H@u2_JzTg`RcC#{_l?-_x-yOpFTbX%4jlPjy_7u1l4oz%0~KUqAQ_q3&BHFB z=|dN9?jeNSbiVHMbps)s&OQUZ$V(joa$~^Gje(nK28Z0l+D*;*$<0Gd6qZ3EdGy8s zeg=*Vn296)`KV+D(hSV7iRX4m4R?&Z!o(DEzq9CyggE8ptk2F6B~27Xt3B$d~i zud~@D%jxM#o@}vLdgXcZ{4U2bmZMFqqof-geouA?3HX*wE6Tz;4~x zYlDh`2Afw51lVNSXNt8S3Feqo>*f!)$ zL%T@baUE7T)qo56V`GY^*qk?oXG6{7HPh3g7*bImpeG>)Tnrwwu_hd{BD2y3mvIaq z98R0d5so<)!j(?4GLYTi9X)3TJ^+7Y7mEZtGZEx1&(L*n}O70>b!8#BLhLF;v_O4C%+1_PI>Z61M%B@ z=gga{icj-m6K`{eH{58$lzIAPZ)}pj+_W<`dQ%Q5H*|>{gmFYB{W$c2KiQ!s6FH!aJTO!W3oP?Pt{DLqv zpTj6K(>Sfk?Ryq(Ys18@J7(c<)uI%X+Zei{Zdd&9b1un_{qQuJi=d_MvLJ44=1uZK z4^`@JHqIb%g^FZK*TrYXRQJf>Ah{DJNm=$ zJQ{~nKX}-VA0bN~7fXvDU$a_xAaNmaUK(|B8`nhL+;wrHEk2OSI6@zDa)!oX;3|)J zeQ8udjA60EF>xpSAN}zk|JpXb{_THn`o`BPh)7LVXl8Ve#RV$tK{{Bv9!)f(sX7v} z5#Phy?=qKBz(imDSceji-f!HTrulW5Opr2jJ0|fK^VYjp`B&kaNB^`n zOs`W+=#sxN9{0e`@94x6j5N(%(7S=6D^ogL#I<SJS{gsc=$nTmO0@L@h#y=UQ)|?fG_9|Nd?{vNK+vV^w;GKKBD_*&K z93Wr(6H5Nj$6cMv1MwI9D`>EAFBnQ+GCFLciPQqQ9e=cO_GMhg0iz+DIukyNvXs#! zCe)_vVSzpvyPHct=2n`&+-bgkdpUfP%^P8wplHr=qe;?@#)iBJ#9Tge7MG~>=m!IN z%Sm$==D>dAiMg!iJ)Fit-DdpG+$eLTEJ6n~786Z26jaWw9n?IYb%1QNseYI)Yden4 ze2}>k^EQm+@@9Yxa&a7>A2O}BC7u|dbisOu*Dgp$L7q>OALg;jgAMm^f!7%%i#JBv zJQevdIEjx|kiGajJ;(&`Wd6%K!uIa&u%|iOt_&L*e(+ZMvv`i9IU+_sOlu z@81n~H!5o;u}aHhYVoF31GvY0DDUVfiffh=Zsj=$E+R&6*HvW82Edi=$)5WBupq_Qv;YzR&dS>*HZ-^I6u}F8SUP%v27l z2UXARRX=!($unlxwbVD{MyIJ8Wbe~(M?8Lt%iP{?imNtGNP4r=AfHO^Lp(FI2bs6#>U8ww7*Fq->piC*lyy-~YNL!%p zIfl|9e)={(*HCL=dHV@`Ho(}pQ9EVRi}HSwjXc(A+z!c~WFyUz%XOplCO;!8;xesI0#Z6`Q1iJMzK#C!aBn!2%>(Kp_Hl+BEqZl}5Uj5~k**>Zp9EoTk+s~j z_a|y^*Xs6_SGSeirzWFFO#+v@z*PZ8_-#QG+KS)%qeB_RnfOj-g7i6o;sgJQX2dz+ z@;BTHI-qw0{kXYck!CK}GLN~xhlj!@Ja)_~TH}_{BT)YyO~2U%kI@2zm-$-wqBtV? zRd}xk`1~rey48Lac;o9I{=pyoG>Nt=i*TID+#W-hD5_Cu^mGj_oaPS1$IredxG7B1 zDm{FKdn(>J9cqeJVX`RQaBh;e)&-|jj-J{}Ga5B(<9q0HXy zo_F%o>8FFIlc~-gZWh*#fH#D6gZGU|eQI^6ES}%q(K+7^x9X(Xr19pK%+=+k&xO6x zpo8;?u`ktm@;W=|?r^N(@k<%q#J9G5Q%aJ$x{y;ZT7g?O-UPI)8=hxlEi*(l{GjE)+d1i%4jBNNQ-6mruBr@oObX+B& zWk8U@5X?E!51x*za9SbZh4a%zl8d$i6E?dzHgZsOjy>b3LqAO=8pl@|dO{;ZoknW_ zWeX0PY#1R!(qIB+`FN91v^-Tu-fObuJ^_6yE_x%2uA2-F)eg+Fl@%tFCXDEn7G+&+ z$^#{}K{j+RFH}d>mcf(6GnK>6-nKVFNe8}ZZ%mqK8$8vQ4PE5(M(lcyxgZ=K*(6Nz zlv^?u6q7v0bJWM3jjdsyH@;N&kkl6#G;o$>dwfW#kpC_q0E@%>7A(OvquiOsA zPie!OK2xEMckUC-+f0SomZ4{*U?|N<}aFn z{QMTel7k)>`~>r`J{YI_AA4Hd3U7YnnxZBiU0A2Z)!~5${bd>yehhE8hh%t22MG(z zaomFz{ZsfuIE;Jz9@muB<9dG&JqBqPYsIfNqvdfge?B10Abg?nF&R@9D<0v+#P z+#u{WVKb4lO#G!g%)DMeu;6#JxgV4Jid?}HUT!Bglhb&h`PF)c*b<54-aO#SGTe%=-Ro%gKS0;wQ>SPVRVu4 zj2~}y@tETiz6a(xzUDN16AWAC(|!D(*c4-qrFqp;jkljZ{Wv@qBaS5GVKq%@WSH-z zO(Nqxb2-n|ReRdl(DlJIG7)10uR-weuHyR*6U9M(9v-9`Fq3xm6?fJx_&%~fEz#Bn zm|OFPMjkvAm2mJRzqNsZ9N8>m&cMT{l3(*R&;M8tkl`ekIu4rjBbRJlyitQp3a&Yx z*C8wud1cn6^q7NduJ(L=Ef3%B?t0CqzR%^kxaR7}x}kaChHTIGg=e102_tNn@t`b{ zoS)^WH$I)g1H#CUVL{)YRuC*3<;Y&buEKU`g2C@e=B_TYX_3hMjX z98s6`APfSyUz819=E-aXWxdF2FC9Q@de?%K8R=xKZxZwO1D^JT^MfoXX5u^xf4>VGLj{Ap4yZnJfUGDko7N32u+)Mh=HGMiwh$qFOQG)^BSM@$hw>Af-9`z zf0RvIse7N-l_U#tp>y+uA><;!SpH7d7_3Q8Y4^C3|I97ZW=t&boY*w1bE%D*r}#T= z(h7O{59+etdX(+@gD#=NEx9XQp!itdjc@pbXPp8@yJGX};P7DB+dIhHmm6Cu+fT#0 z_vgb8Z{G|j@81vC9I+`K-rRl|E-tQyv-fX@>+>@)$~q%?taJ+|ckc zc4)&9Np1!+i5TNc!|7_D80I@8Mm0Qq`Y5`z&Z!}$K=2L^x&_2CPU$s;wNwO+JMuL- z1C9`fR39tSn4gS42&``WB`P`Y(BBk1Pz;YAK9SNVAq>f8YDPe zGO{V<4Jx^vmiQuDJpp7r5Z7sHu*~4XbPSvcXY(TY;b=o2k*IW_A#eA>vC+i<&2Ni| zmvzbJm;Kq8Fuev7$jHr$4I+-;V-PT&=bN#H%1?uC4QxDk)F5(qZ^z}GVq{>X!KDVp zY>fCAg=cvh3tC=R_mgTWZPRIREJ|-Os1IzM1X5qt7_cL;mM7gGR`0v{?uvWP+!GMhC#J?$c>!j9UzY1BvYM6wi?vH z2eU#5MtLGH<;GKIdD4*b<(Ll6VrJu! zxEa9lZ_GexierNfO`wV?fRK`}~bB>rgzTuO0O< zyj_Sc-9}VbsqYL#8Gv4^j^C&)uCH-+^rm$Y0aSL>U!|8mExL7nEsy#H#aH6Pn(FP& z*6y&sv!j8r`VL1=-T>UFtGdrz=uZ=tKpAWx!3~Wkkl@J=RJ3gF1Os1t?1!WZ+!p+=+k4w4?opIRu@%JSe7a)U! zn;)xr^sjuFPl7|&@C)A>BSA%QaMfdbaF(AO28Z9&wyBD=3;LVJQwHkhtVsGR9qNeP z6`rs$9efUxX*_*bt9}zX%!jb_F@Eb29MLHccqkk?OCqcx*FKUQ+JHnQg+HAIlRuq=2Hz6Ir}S%+IuqqVaM2 z5;8o3Pt4$YnbFReE(x}+x z3;16F=J9*~9H)!@J@j-1MO$I^H<=f39Xx~w=6GC7xaRM11&d*;b(gRLryv~dnl{$L zj86HOzL}Au+~CvhgrAbKztZU41#?{aAEKLwmAlgJjr*S^yvYqcz5r)Ta6QdKxH-Pm zhCR|WRFyXyWF|CIIvNdkwiY@BVN-JYnPOBX5IU z$uDzvF?_nc)O`O+uYIMx?b zRlHHerWA2JCt@wZYYeOfWJ8Mi-zIO$XkI8H@geQZ*O~V+ZwBY}3TIlnVce^^7n@$& zoJg|4=2zyf)}3gaC_*5wO;3XUdnfQ*NOH%1v^_gWk6L`|yk` zDIwM(@^)SL;G0o5 zw^O}+uDE&IkMd;W%vl}k$Vlo%ZKx?x1v0&-{ve8SEt&G*VRYL zT7=XQBV{bI@vWUT<2Odd%LYE+TO8{|;Ce@VTVdoiE73w%ywHmuplv`K_Zrqy*3(!k z;{b_3cE9^->04N@VMB|z$-F*$b>+2AKVW}zGn}1W3_rX(9p0Xt4X5YV!=?1bTIGl9 zv*8JE!UCk%WGow)+*2MXPu%?6*Wh;8+zyocA)MO}xmlo#8F3ig{2LA^+8zgt@n(3J z#|#!}mU#gW@$UiLDttkOQEu{#_7ZeB;!L%m!Kye72?xHxCiOGX2c%d1PrV^N(O($?1Y zu)CX^CH(KXsi`COjm}xALBL1r-QQwDP-IgC-xOtBnW6o_d9^$Z5}JG6JiUO=&7^gb z@It@bVBGoZhGrcozTZyZCaRwoT)`<8Ptp?yJP2;IIJi+}!;KJR5ta)#O6Nf(fgI8i z`2)B?-)Ufs-vbTw=hv|rEJqG>0N+m@m_8LR-snP3(jl+p<*5c3y!~}MzWqjg27x@e zF}`Ud4!rF}e(o6<3&#^&93{t~5P#;+H|JQXTG}sQjO(y{ODRIcoJ$DL7r)3!Ar;Gi}egftP43lVoNS zDo1SaB$evY9TT%mzIakGZy4UWjM&_!4-j|Pb@a=`fTw&akA9m^lL+(^U1}n-hWmpD zd$g&04Y2t(7;kN!zSqF$?WMoE1jqSt%T;*V- zzw$$F<0gL!vLguhIrz|m$&esALC382Lp1N#7W8F_|08ld5D9h`xR-De(@NY zV97=w^mA++ny332k*O{NE}=&6T#>l^WTj+=kJF9A`?G#V>oi_&y zX_@(tvF$H?SaeLt!dhVI^tZmu%t#}gqIkO=gL41?lTX7>|L6aUV)Hi+|AYU@KdHnY zg}%&s0RI>R_o?c)>wdio9^_4b!4GY8G^^-+pBL0bvHZY8{NednzIs?im-2gncLxuq zfmsm-?jhccQCGoZay*pA9KfyO;_=}F@KCv~<`3;-yxeMR9s=&^J*-Nnpbsk-ZPxfz z(Pq3J;=K}2AHBdd?m6wMxM?HH<-O$R*Wv75W@lKHP7zN*2WC__&(0lI0<5f=3YO#TP*(!r{9(iT!r3zq3f_u+bqYq5V? z(S``upL7y82KT&uEVj?(JTK$wzQb6f!sc-TC8z0D^aB&$DQr3Y;8xY~UJu9v%xU89 zO<+|zgirJxfa_4pX*}MqFz-PJ1*_8z5cY8BGI)%qLiJcecJ=X;GddGP;}|EJv+t(_ zYTl*Mu?C=@zqgJ2 z$_ImD>Jj$_wX#q)i%ZspggWv=m4cw&*RLK}#GHd?n2Z%AsQ`Mc=aRZcB-_FRt=fd(= z9Q@>qjW=u_m_~=pQAI?ol)C_ZupR<1cObuhU{~?HmL_>zSH<6TP~om;qW7kaY);)d zIN0~5q36MrqvHR)-}&+I@BBCZ-f*XA|BwIAUku;<@-3-&{?5GOQe{T@UP>>NHOxpG zxepF@{ifEz-kxRQt+5~8z8}snE?ma0=aP%^ARe1mlp$d`p(uG`)9ZJB^GCzK^>6-; zk34+y_H_7b$#JRj;B7Oq&cni9HxWH$e5v}xL$j=R@Xa^ZQR$Fl{W#9=ij$3;?!EN& z#B=?fon6cAH9_hJJjD-PTwI-dO~G|jX_AiLAf%qH=i6QzZF3F%c|A>Fy|*%D{Q*7T zqfDretXZ%wNf|;$d>*E*vP~TckJ_yCyq$_CT-J)<_rdzAwAhGB`)5P3wQT{RQ}O! zM7^f0RSrrHeeSJ48+M=H4(r3M*sxjpX&mdM9-*-N{m(v0YS9aC4g2&Pc z*TCoGDfm)4;2|AOfUHekk$w&DF9Y#Y1*Fb@9kjOi74VP$!~fvPlYjbu{!eL&Nfc}w zRrCvz4sff8pFD#G2y#57@5L8Q=mH910J-XlGh z$rc++035bshpy;lkCet$0I=u|`4qWa1ye{IP3(XPb(vLg0KL!|9v&VKFJ8Qoz3(St zSlmz9D^)tjE=ApT)xip*xaq*z_@c9Ruy4wAzbD2TzoBx?C6^tXq5@WP0EBi zz`!<7zF233h!=w~6T?RivyhX)inxPuT7)O3M@wgCpw2{fArY;n}muYFPWFZbWHCK)X_(3Y3!$4Iq=vb3&htd#nW9cv;IBHn{5nSH@A&ZA$bO;Y0 z!fkR)33Z*P^s1gG0@?{**DYfb5?}nT=gsXf(b^4vA@DmKHy6hUSllRYj1M@5{?V~~ zB7xQ^flI`ZE|FV0afYtKn@#NnJMj=smXontJTM>yxxY8)3rYfoeaZ%uLyeRL4>^e) z-n2(}w!ABxL4VT0lm#Q=sI5|Ok^ z?ElaH@jnjXuL1st|KUHi6dCV44po;{fy=VFAA^i%mf<1ZD8edT!T&LNdhmU;!Gm$& z|3KK6rqjdM@&f-@Dy!nv_-77}$vY2Q$@g=zJWy92DqFzmwBvAbyFa3Eo4>&29p?zE zWGvu5HHJ5ytLVW!#AQ`}9!m2;SwN3rvFEf8$rbu9r45jqmHd~Z1v;h9^Sj8WccWYE zc3)nR-dw8-ycND`;bDLX11aAMDSJnZLw6u0lqGYH*; zUoBg3*tvgC01mBT7RxGn>NPs&J@yIXy=w){=yzc326LS`w9;&3bAEvb%5WuZU>@cN zab_^lpeNj2dv8$s2!1iFaE#5Mt9!vBk8-by8&%@2GM~dDuVu)bd>LpP3?*1QFn`-^ z?Ad6rlXH#QoD4G=9HEF*q0%T$SB;T0PShYXeXJ574aQis;+p$<4Ep5x@N8{c^P#Qb z*~aehWNlNl93{_~Q*$BBjoI+mb!|6G1P;ttP z=8lquy!v6twqXYFU8XwW!w*_M7f*lx?3v#h;+x@o8iD?d%_!bB;RrQ0*LVn%O{^Rl z$>MuXGePfsQ;0XY?yhgd@7b^;K5U{f7iMmGaenEIFXm0C)njSJ^L(E53eSmiijFt# zT6x#K%jG1wV>miE9A3UW)*O7-S$ubLHhllXTg|iij#$=PYO~PgEW-vB zywD?ZvmtVPcrg4Mzx(6izxuELj&!m$eD}kf;g@ethHKRuW!?3DeJyYDQNGl-E6Q8t z#>q9*InrVskj*+azAi|EH}ptbbzpmQTWPUDtWu>vrY$KBs<;-NAHMfmMjj$ZR=>Hp zxi##lzVB>N=bwA6lD6X0l6Zi(l|Q_Q<90@kldk+te(DcpC_iNdUD~ebr6V?end=E< zUeq_z=STY>fUbx3lC>r3T69Yo8+)vgus#F0E;ioim^Id_BhXWKh>JI$$H+!1<&X`} z)a%@{TEC=tl!4c{#Fr4-sq3wDMj??p@c{C)%?5Sj$668XXLtSSaJ>C#*nGx==WKk@ zP9t{#x*6w^f@)Xk{|LiB(X663MH;Z7c$5t+#=+gwzyrQTFE5Z??$tOYm z;V~FDzVNuxSH7I5WDFE8*dr311%FpHMesn$Bc9N%0`n7Ho=S!u+QeI8fOdr3K z!7I;P*A5p<=tkUl7kkTWbkfF4!4VGQ$dm8{;*kZ97B}(mKEYZL=f;7n#=KI$f0#i{{)6@}v+? z5Z!n%#jE7pbnMsQ!^a-#=EBoCyq0}=#m7f^JzImWtu23dY>TH?xY;W`Zg>o+)HPd1 z40SYF;;I{*I%i}ApmVK3eC5X-y)f20G&1n;%>sJiy?C#mZ(K6j2zc&61)Aoj1WN{M z@F9KEl9mPG2FZq%Zus2E(4q9rY;;|spr2t^XP z6`vb916GbA08c)A(^eSzK_+KK=~xGp0SGb90F9@Ikgw6m&ke|N9nVRbA8yigJ{vCQ zHs=kuiYE&FqA%pr)dLT(9G5`*g*O-Tvzx1#+On*2^F!vRy5V_a2Yo4>EO>_;Iou9# z!-c2}P=sT`p$HDEIK+o$(i30dOWS$vf$}oe9VF(=+K(b=Y{-p_(+% z?|I-Ww~s1N8}X5vs&lZ6o*DGy2m&QMJSAQ6@e^olL^BbRTcoZd=~Cv=qd_Y5-u)HgrL9~j&fWEg;rYhX;l=BN;rPX|-$q3TUNBGs)LCdbyPj_$Sr6jn ziHiozAMZX6d)vFiPk!{{;oBE%d~G{#R<#nNyTVy*-r(|3nD_*O_x#)n?w3SPA2-^YWfZP3rw25ZuTMn)GERr3hh z;(Ed!K?oGcT}~X(*fi8ae4Jcl9Nxkjv9nyfO|P0~FRe8{adtG@!01*eaiEFdVXI3* z3vkgsantTn|C1K}MuISAUMZQGgIY*rt@0>(tXu?&OR#M6LCuXqp^VE|lOm~gbssjq46pE&%HP5*Hq3z6dGo^RA7s$oj6blqdhWp?mr^5La^yUNRu zUdm0T!PLf09h`~dGA`)I-PgSalRS-H5UoUpN#@B0BBm&8H*BH>LS{c=7J4z9fR=Lk zC(31Lx(V4ths(MU4)_1`r@#J6J0|;DhrT!&4y3mn_WP7w3)V5nth1>m=}nF=6#U9!&ejl zeDYELs`E{XC4TsWTb0%v*ZXmIK41I34w#qGsx%6wu(Fri)T;QNn+V3Vm8S2b9W3)9 z4mifIbuS1|=ZYSz>)Z zb5&(_ZEb7V-aQyLHuprQIk4sjoZ`ZqiH#)Ez1Mt>wHG!dZf-L-XJhQe(eZF}cp&d5 z&mY-5B0p>h>}>B0d>5O|FCIF+yyD^7yv4P%vppQ_?|9?uNH*&boak|OeleU~kOrsx zX#S|VyWdz-IB%kmE_%&oiS(^G9cgT8KEr1e*uY~R&j}-^=a<9Vx9^8{?@s-IG;2W2 zM^PCI`FsO=lg$e8WzJgu>kUq4P4CnvJ+4j$g_{`(~q}e$TxM&{J6JD2-c7AdriP;y$5H z#GxG!pEZxMe`#|ifO^EHkw0zF=7;d!k}m)5Z~eybZ~fQ)4N-j<{_HRRdU$(sDFtXQ zzrniBbC=nhcW;Mt>5daqvQCu^%e~#*fp7l5INBff_jg@ye|UQ`oV@1`EAePe*Vih!@JWf=ZDDaYfoLb&^vE- zU0$j_vi6{STb3QwGd6ovM(3(yr>CdhXeB+;-C|={`KP63eS|u|8GRX<{H=A$& zDmT9Dwo7hLRD&y6boXiC?&;wJ-yTO@wU5gzY!P}Kt~pJ~7MRlMVS&er@W4FoGF>G_ zsf_CdkEB<2>R;gD^aJ7gdAc6HhIT&wTn6VZPLX~M?=J)KbDuobnJwrXpi$-0u*zWgO*FX2g=)!Q ze(p%Xo5*2QF8{C_uH61L8$8g58CSeuZHgWmhHyI*3)`CDW*e25CxKYW8y*62b8T@Q z6kjkBAia$Bz>@$BO2{f5GB+M>w7$vG`LWQ>#){m$S;Pl4c|F>%jcd@rtI7U$mu^7O`+nIGxNFI_`Z9gbq?MwbCieGknW4edro{?R#x z?{{%yWpnFZ<-zfXe8Y>u2W8IY7=up?jhA}NAcCi?d~5(8jn%+`!7fKFd{RbuT8bxW zp6lktz%V8sfb~-RjFnFR9%Mq~!;gNb`wg$IdL+TV>>Vruep32FfinqUT zXR!29gSBTq%7QivALYcGNz`99Hb;P|>Y67OssolyC^lw!GwSwI1AYx^z$qvCsXp>k zJ>-qeeDpQ-51Dx5il@pb?@!Mi$vX04c^mv7k7c5Km1W*eQ2Ul9en{`ci-ClScqvv&6`W3MR$~v>%S>erjB8UT#_3AN8YBYXF}Vmt#TOS{s=?7Y{WEbWU`Zstfo5; zu564pd~7s8oT8=9+Cv;$ZvXI6Le6@4WKp5~q*46>njVN@NJl&@3u!exKg*;)K!1u%{BiS9+xG{jD?CIFpMW_2fp^~FVfA2*^p;R=>kwNQem)8skTu~Qjf^-Tme8?he8@X64>739GwBFH23C=d9M zjL`D{YF+^puBTarbKff7V;gBaO3o;@aESx0e9bQxV}}-I)6tgE#b(5r;|jVNZt};T z{L8d9qg)sWph_MKA3ttz%Y1E!=s#hFuY40PMw}d`i%tAyhAW!u!ZE>3rf5o@co$`B z9vn_16%iADCHK6n5*T9~Kk$WXe&c3P_zH^~+g?LYQ}x*4#zj8l9LEOG5!T{{e&S)j zLjxnv!s-IqJPuH<5d$5+jfq`2n{T;!xjZdyH6M^2qA3bn($IeHi(6 za0{a@1B!1Xm>c?+Z>K$_O{nFzvCh1Q;B*#tZR;Tut)qunSgnO(-mtHF>QA63$z+@UG7tFrK|V$F`lWR!o-h_|wZ-&J$(rkjWao{u zy`7C=e~%Mwc;isIYw~$5NW|7He!2ZXEDZEdI`J0`3G*WvNV7h~+E<$s3WppR)@`WA z=yqLoJ30`FH`S0K8-OGMZ}f_e(WTeeSldv&QAEdeTEer=MtbgliA=cU30;gq7VB!o zKO56ApVS^)8=lpsEbD#B1Nl=NWJAtp%H$T`<69G*)QiH!E@^kLkglMYA^K<@K|j_2 z9M`V6dmEVCtJ0Y0{Zm>6b}G2yEXSQ-mA}WNT^B6M0hqqwdUpVK6UK2TH^%LLX8Q06 zw+w~v?Z@bQfMVf(_XY4Jd<(vY7Gb`M{)+&9U#5#ipoV`P@Qtr$zyF7Ss0qCiOqa@J6r5l7RbxX<}w{RSB zMmPfj1|B>u#D>=UlT+JlT(PNz8^i0;=jR%%ygM1*zI!vgJ2@Fn-@lJJJ(d66@c#5n zgQI-Y>)ab*=ib~xVixAzuq6mj-`w3Y5aDSBg{cGNBbjufEPUsQ1@gwm1|0$&CQmZt zsS)~1=)H*s&YOEId@C+IgyU83+=!ZPS}|7|+%%x0^Cir5ve6sza-nXJmTyMfHJTFh zM16D*-fzZ%cesqxiOlc0ZZ;0qbTeIlzCJwH4INs{8iN(-hnj=_tRMNwvjL%;N3wE;Gl`Uxuf9cD8pl!N?nc9)hS&krM_p zH)_kb*O%Tfa>^38-X^Plf%=zv$5VSxJZWGv>A5B^)*sS|m!x+&)6PiCZNlZneC>me zJLH(dY|^rE^=#PQ6(7|%o-)h;SLR;fq<5!s5ssI}cr$Fz-}z%8syv7(>ZU(JA5Zw+ zl=Ypu!loA+dz3AkbT1B%JONzuV2v_TWXh(MtLqPf8pw$)0Yt%1!R2Tn&FlLMVfhOx zZps{Ag&2%zX;~0Z$Yyl#jl5Zb1&^SUCm=4$pMOmrU$Et;?NobpR0qWk-p965S4;yW zEVUmuS0FOS-+mGvJ(?0C!c5F1@#_gSF4PmZKN+POUTz1}8`-TLz|(mV56858p(%wW zz9{4cQ*r8^khh-|1`)QeqLItI`1N`T+u+R$KM1)M7T$6@F3`f74dh#yxS_>r?bDcM zS{&QXQ*f5sKV(jfqKByHjJK!!0f#iY&|rg0m~puLM+=41bu4=zaUI`i{FNW@iEW(2 zlt%-B32)9Wo&%Z*zQyo0aqyw&;NUvp?TH0JLkCqJ2ah(^SdY3eoQXGqd5%Pc$4w0e zqAjRC{jF|%0VP`}?h-&V(yf3#e6*V>SmaTm!4=wdNN!;!Kd=xN@1h@g4EHPJv70eY zox@^`#W-WU1`ma;!U3!BQ=MC;?_rD^Pv{%IV5I4A1%22&e2x#_T*ff4GhATihs=Fy z`X@O?GikSQ^mkL3`?2Pq_~V_W(O?1ZfBSW~9(sCy4##T#3R|L;N!?w<&FLC~zv>e9 z)L-k`{5}0dgWK0J9C!S|H=VBJ8Piyd;r?Mald#DR^x=h{<3CkZ52ywjL=%E29Y{K)=>`CF13DFtrAr{u1PiwzQUF0S z9Yg0pL*OOINSV=$!d%loy_jdhK$(3iSas^rZH&MyWX zcd&NhB`Q4m0i!IxO&Wrkr^Fx93!YJQEnjKNjrNGqj;%ms!dv7;p40sJo7}V^ghw61 zkIZJ>kA7;yzv3ZSATk8kvSJfA0lDJOu>(v-lcjv#&ir*+n|KC!2#iHFB^>D5cygCy z6={ZuR6b>N7OA|FCj^&HaU|GsKALv5CDU!ocil(| z>j;|K|EvG`f13V>|Ka~Vef{&Fc|qy%qx;j3e)!e&_`w6^$!iI@#&Bo4r*N=$*LEHr z>`ptp!9(YdEW+q?(NB84c*T=E7Zaz1l%FR{xOtP;AhJmJfY&TOdgLdPeDiKyr}0_o zJDyNsv49&PWzh93R5(vwop8hT+gH=^+n264FH-1S7JhCnMOK?M4eAb8V5XJe0B)ms zzYfnfi4{T_b&yv(s|;MT;@m!q3i3x>#zh?Ka}GawguLv-&$$%W4|E=0vH)_NC#zs; zk4I|nN4}oN>jHW5kA8W;D9s+`jWy!oyW6Kbg-{> zyz5@-fE`~?;2fQw+7OrWU95AR+ud?MU4}q01r}*8qJTOulksJtFwa z_v!8{Z{Gwf-?FHf>k!ln`#0AvC^sC={V1zRE*r5JqTz9b-n)PDCYqx|UYmH=*Pt$a zErhy4##`qBc!AF}N(tb&%eZ+QNHoE3(S1W zn38{$!wI$}4}f=QSm6Yp+|q{dmi+)2Wr3@9Hp2o}^4YL8g3DBX0G6+i;|CH${Cz^{ zd>^>U*M`ylCxb-4m;8-@ooX-2_#3mk3D`}@!q?xVwI=%;?(g*cHr1CHo+_5$cpsiO{%-}CxOhwVT zM9KUj2b^X@AnG{LNC#_+ixF%GgJP6TA>oyPfHE?Gav_>KF8n<%#Y_q~xbSVRJQAFk zg{hY>UrygWeX7aNchlEj|6+Rf^t5;)S2?dhz_Z7rdaq zJ>dzje9w!8F&4{^d-d{#p8#VajC}3KX`b-n)ol#G+>PVAMqDxuU0I~d;tUgo-~?ZI z*MXUVc~=uH27E67^+CZh;Pv>s@T7%H2fH5BSu9YDEqV!KiJuffzw42-M*8%Rkh1?o z!UsS7Xmbv|m!uWkg3wf^+!dpCFixC_0wS~xXI8`YMHfGHOJJce<#t>X zBNx78@zWQr;hB%ylsx`hy!xQ)P{DPRo!#_#e*!@8L2>|-0`LB^ZCkb-pJ!0rakysd z2?i{DBXW7V4RTNy6)orMvB7?lpL|nh$Rs~wHW!(cKmL=Z{PBg@PZ`QgY>7Y`yz=Oi z-tb%~{<2SB(1eT0`0c#6ow}zl`^hfh*tew0haLBO6$uHHY}Wzjru&@#Hg~;O*YYU4g*d7v*#6p6tT|vaf;QgZ}=e6@5Se!}>uZP_cr4 zL1#YYa=L#5KgWsm9cmlC5g>%xL@&pyhF~og+Y0P(;OvhGSVy!WZQ2lfvCI1_x&qg4 zm$~;d0`jr~ncImQmjQdTtSQ>JGV96Gop!e`$j4&4&)Wye2AP(fUe zp;?|+zPK!+m!Ng^L&!R^jYyB;HUlt1|!t+b-nH>vBWjyVxi8oY%P&Gq9r{w)5vdIlbCU$(t9IRPE}gC8PL z>_y5n|2!s#6K*iJf6)tHfc-3AZ-QBF2qScQlRrw0JlHiv!!f@J+J-a)XeD(mjQNgW z8oWw3+$28+z&-(_$1uPs->{lfY`~busAqf&J$-jgTS4(0Hq#@`(V92Hb-Wdg7@FzX ztoSBH4k4tI4Br=ztZm8A3MY8q>$G)h?&SSHdTp!2Hd=>G-k44np&2SY2NSNN!+=+~ zg8d%Sgw|0arV4l3BH%#NT0Xp#dz)P9W8pP@49LST8UGV^upGYy!ApJ{-f1E3BO^V>L-DoGt@k^0TCR^3;2mGhW1;o2LA3rs2z!tVeKXy7 zL(?6GbeBbxnYNa9%CXahL(90(`~-t>BXgK-(GX4}1`arpP)YDrdznugl5TSM`3_3W zIDa-vd$f-oLQ632pXz;1DYqIg_(5CRSCm$S$6slZO>rsw$59*knfupdCG@t0i3gG!gP?;}U*i*v#|zRtm-7uPWk z509pYk9hU{qv^@xhrX#-CyP3#J)K_hMxmE4rqkosI@i>>?S*{3;MMmK#xnFIfup| zJkH@cpGFp)d0&wYUoVgh*Htoaww2^nbZ%hmxdyf=BiHx%R@|cp57j<)T zW8ZAeCk$wR>~Xn-7+=WSKGVKRgHsngv2~>Se|U5-J-oj^-9O@KzPv`yul@8w^-V}Uv4@&1eo z<#M1MWCvCBn^t^c6<)FU%Di&UH7d1_7uRGz-yh2&AUE&&W_bs-ogjTh2$@sX4|xiV zYlUtnk^Pn`?ZebH{lN>NKCh3@QKf#PgFkr9BATD@Dj)m=r1JH`7kSNIqmweyN4cTc z*92vmbi{DTY^KLD(muYvXIlz0ZwX_1lQ+V)d~Sj+H)3tAeRC*U!$|vR!01O{&Zoks zz-IsWB#`*`*0~nQKYip^w~5}(q3sj?#h?9?e{k!+{=fg@z9C!Cdo>U|Ls7>8BtlDK zn3Dzf2*eH*8i0O;OAirZK^DlAWy17>4ANM>6s#Tb*0`<-HvMkAlWs)Rca z^OMhP1CAm@%~zrugFz~gG?B|xeyw~))M6!Dx;_x`*TBVxS~(zQ(Ip3CUp(L8;C8?0pE|Y%Mb4C;X|GH#|3@t=Yl?WGURc64w`<~v*=vBPkB`q z>H97R(Q-F~24NkH$;g9;{%#r70TTmHCKR~7oqE7d>I*(KOWCaA0}eD?&%wiORP7Jl z3yMq>C5x^OCq8gPCrvZ3py&fBZ9yC8AjYfZxRZmjNekzW9?HwUv!imkud5EJ5* z^1xS$aF^F5?(I+ezROB|ME;XMi{$v=F+e9(Y6!n_ls@RYwvNxHSFc`A&%S#(oxI66 z`VQ~!O`m`Hxh74!(~FnSrk5|@xE{#k9SdQ~*X<(z4iE25pMCX2Cp>)TYghH6N$|UK z<(E6VXm|3Lm+t4>P4-SFP4vgl9)B_Y(O>y%)8~&Ld*LhXLIs1+ywc$(Kf86{&WngNPpYlqY@B<0733+tSBE*le(~*dWi&D?Ulae{DofQhW<&jFBJg zHy$t4el{#1UrQ<}3H3X0du~0qk^ayk7Y{J>Ji3mN^gnsn4Ec9{ z67o2qpYuhevI9+-Mbd_SCw9yhSVCdYQ%t^{=~|*9IGaQ_vJf`wiP@o3K^Sn}xn9aYd(+Yx;=0)q@tSWi!tLuJid*=~vQ~?}~oa zovZeh+?MA^bL-6MZYz$LMg@!P$7}`S*mZOuJjSk+Y$Yo(QzH_*q0nu9G+f79(>YEt zA4{t9BhFYn%7VA=lGw0sj%Yd32Re=^@iug3D7tNWKZ#G9c>p7A#B(gT>KAZ@t}J|! z&vXb254nEBL&G|sp3eZSFQCFm_@5ZrwLgp#oVf`$^03xOqVGkr0H=|GmasO_=_a=9 z0xNsP%e-PvTF2*tN^`E*Kw0d+<0UVbv8eD}Q};Ef@Y;CeXBPyug(<8q%2^DP0FxPTPF0 zdS`#Sw|_LAP>g zonF7@wU6h@KGy>9!%yk3e^52@pK}6Uqllf$_wk+URX`t`eI8uF4z3_Axt+HOk)lJ_;p=Vtdk52r+Vu5XzHN0<3y0aa zSxjQVbpIaLnRfi7;FCuWrq3T8c_ED_eemJ=i#OBP-@cf>}udW_Q&a zve+f2j8>G4LG?u$MHMe~h#+UTE|2;&Ht7?@eT|5`(obS1`$eudl80p!`kWH_CD)4Z zgMAkqSR=q+U$|1El5ULbhWiLtS^>H3sdTi<4LgcYAK$_S_2;UwC$@iF@in>=5ixdFy< z8zlaH?B4{RBKv*pHGHg03%K_OmCCP@*LI*U4DI#j1f#z{`Op8)w{HF4{^5VC($HD7 zgNe9YG!vPBl0vg{vb7B{sv7)_8w*=jbPpUM&9M=-(aJ>^;WICE$mCT?5h8=*m>n3R zWiYanP?UE5Wt*)B4I97|JXn;0${y%SEw)WA3xI2;041uuV>>#Zg_Cqo_StP*QHrPkW?v({^e1?4%qnnZUqh(T|Cfp9Yh@#W2SKP-XN1O=;?%g)Sx$ z9Jr`;?t1Zr$9c2h@^0eett=)`1~2}I&cXzCxLXCcyvV1rO0n)>nSAi!shC~W2MdBY z!9ffkows~sFy=twJ3v%7J~+!C`UMM!z&tsTPtYkn^^PuS?^iBl`kN0-qPae(8^zcK zT!$r#A3i`kl}-0YbaF7|4juAl0F91?nM2 z-I8uY`$l`I{aD<=vtGdRBjl2&MsnaqJ>_NN`jJiQ9vBx~=>x73(siLAlfB3?7C@Bu z*$3H3$34P%RGSH-%~q2GA9eXSqSeAN|EJaae>7T_wKh3E2y*NFeUhrh) zvlp7!zMbCt2}+gea{OSwyXWj-|OPT$Y(k^c{aUyaXQ`7?juFFCj z$QOUpPJ#Y+_-KFn;)~Cx!}~{S6qTI?Mb!u66t%`eEq5yMZ8G*B^eD@hpM5#~$A9&Y zrmsHxV%pOfq2_iyVILoJl0@B;PMx||?1usX%WWtge~VO~Rwy!BVRF0xml666ZA7#8 zO%+xI5VM>Rlg&-KpjbALrw&EKIfC<23|ov$fBN_T|9jzU6F#Op_QR_{ z{ch*D9>p7*a}%!9-9|S>^y|!BXX{hIx`RIZX!iRBzK{LuWY_bgMP^g_I{o(ZQ+&D6 z#x=0X+mxL717ptWOLk^%-3>2HW)bhZO*E6+9>^{LsQm`S^A#4CI9!OnCU@L!1k zEfcVN5<+}ko}~>9*ecXO+JvH(th41e2&YQ8FkLcA!;k$WR(Z|(O(R}xCJ%)Toj}e_ zMp*gO6jUkH_ea%7zfwHZPtOeNf2wk+$?m zB3|+rrSf%qmachD2ijKbFEHk@hBX~I&nY+PBW&6l)7jss^VFw#qH#I^xIjn0W80b! zdr?baXJ>!9bC0*c9Ozt*YX*w@2f}&%{5?%FIj_>WtD7&Np=)%V#p)zRG7d{PvR5V-+;# zwSM)Z%8UGL z_{z)sXg(#vqU9g`M}KAd@sEE``Cd*x{l$0F*WWz%0u$HG*vnaH;yRtL56K6gGs_0o z_wMcHdth8^d3679`rRLWHvP^Io=l%Vx-Z^czuD!Rr!S_Tee-O3_WbSi`uKD@InBZx zzOjG#T7&AJ@4bEX<&)`)C-;3F;hU$gr?+Zn_gDGCUDw z-~J@}p33q>WqSPhNM+rb-kh9G&!6+QsyEZA{J;*nZa4j@p9>Zsl?T^`oR2EK+lc0O zn<(V`G}os5J$3w%%q9DgV(-V6O&j+)IA?#jI|GdhNCt*)-d3HV)MQ(h?dgUOXKVeRGh_!J!6uADl$AaOW`o!VRbbn7{hxSMI zf%p;#p8Y3jj{7$1D6}B$6Je33|CqF*H3VPefjJN3(O=VMH2jtBf;X)Agi%JQZTp~6 zbkhbI!N>Aw*yPcMH$loZfW*I#{hQ!ZWWSHShL4qLfuT1_zkc&t1HW)hTuyXwJ2`vfgVk;B z&d~vbyFs{9;~h_Ah|a<4?35=diK@&Fli_q<5=PUZ3fSsN6>A{+KN z=#wvba6t58jLJqWvgg z)f+emY9HJ<0J@IxEb{bok;J1QBGX0TRe333E-VXG+6Qakt{7MMz|1{6;KHmzv=MUKODorN5xBV{fj2lecQngI(RGuoc zdO+%3CqOKGef#xy@`=}$Y688#Gku{6FYlXw{fch_zML*JIi_JdjeIGeTt>y&%75sLRo>4OLKk35k~Tk6Q%-m}Zs0>L zjJiGok(MTH6a%IeS_nMpQH2un*hIZ9S!o>62AR2iQLM6{Usj`nw#pS#gml%7-gxC_zFuR2K#_A z`HB}$dK+!FCBBkru%|Y$&;U!7=$NO$j_N=78V?$jcB1?a;*U;Vu zg8k{=|F0I(pEG>&!q@Ek7WlXY1O4bG@V;F50-~*mOTv}3RVNUB?A`>;N4_Pu`?4KA zX1^g9Mg;C3Yd!EDCpYQW!F4?7%)J^~ZjQYTY_nn7K;I^_4X%^BQD3}~+xSXn6c`)H zF!T@cZrx(+Ptul~H|X5t=Vlv>vOZQceX!jnSn;>$HEkXZ2HA|;!J9t9nzWYLqS^h&;BNNYQZn>6w^aenhLLusqZK;)91HALfBw!qp}gYiKz zW3-@UY(M86GgzK-lc;>1j!f6tsMGDe+3tXIG=t9 z=fN>`Nw@9Bv6s0>r-kE#@@@-;s2~&>amx&(awQtc z4$y8EzYY$)Aa>_op8g{6l-51b_V@Ou!^6Yr(W3{`<3~r+{e#_UPv@kX$}2y$zRs!k z_jdhlFrGU4#kb#0-+cFU`tI3_>E+8;a^ao7H}>xA)HeUd|LT7|y}z|HJ$rpRopIA6 z*I;x$#~W+7xl_(gm)ciOE_edzWP1Dd%r{&=fBt-W{`9Fok#T;?x$T9{ZCUKW7tT3T zFS00{CzkS*5Iiqzu%Mzewpsl0H|$ksoHIriHhp=l-vv_5)L*xC>U|rG^9WzJQM}#< zl83LU2$C<0E?gVCXIU1$xOvndRcPEe=!GwzGkx$AUwKN0vojVfmp8*;)91uhFL&?W zQu{ra{^}q8!Stga{$RrNGe4d6M(6x$3-a^AN6yWF+{CT(ZP}#lI45Hf>F%8m(^sE8 zp8nGBd^!Ez55Jhc`26v7cyD()K0Tkle)??s`8Us|7cY;elT+T}B75>9*HJhRznJ!P z9{AM$i)DF2BJ5T!Mx)awWSis`7mR#>)-o)Z43weL(_kT2f z`S}xHf8-h(Pn|t~_1cSW@85Ig^uagXpPup5SS@~eKXKEz1sOZIc1Ax6?SuLYPo*7B z4<0_8-idg8d^Wv(!&7W|63*wDTyjbEvU@;F%UWr*{}|=0@qKd z;@l9=^%vyR4}6VITFCl32kk8!=d6!eWN9DmTisSrgENk0EcZFI@&&xOS$zR>j>WU> z@`1MYwG{D?_4N!3W6NS_6%F*(w5xsa$%DP=i-!l({d?M%UF+D6Ov~a+LvYdIIf@Jr zf0sOn!JOWZZLrK>ALu-0I|I(n606Z2NxPA`MQ^^%J~0bK ze0%E`zxes|i(meHdiw0CFHUop4d3v3^XjE-eDGpJ4%oMJAm&;)W*E%vf;PM|t>Kmq zxE!$W@Z`#!yZ#mxlPT_O;Q)4cbl?GC~;-TXU$jm%d8I%J7PeK)Q&_%`vF82ZI9~-%wtMBH)dmo$F*fw{9^rWd42FO?C z_kmggV6gD_pr{MlMF(c`LWa77k69L2tglUMGU?F-lloGIk(HlLk{4R|lDbS;$qO77 z<;82+vRHg_eaMy?cr?8|emgyVsxigyboXE73ozz-e-hl5&I3(CKl|c| z#*Tf_-+3RV{&_s#i-t@%Yae3KNcfD z+_{KFqu1CA(L5HIp2#s93xG=X15TH2NL^Cexhn{Wf#J)k1toM77 zN+3nikGn`SW+jcRpQx?ziI4>r{bSU=vPl{=^7H|KT;o1=E$rXA!nK(jj=v-^haGGq z!3L0w`?(0%^SDq9O6B@0edEm*Fjk-+Kd5sj+|TVlWaOwHmnrFxRW~Apj(wQP&v})c zRg4JpcnOfBh^AF}Y;@KLm;utVMJt%AYZKZDL0MP5I7dMl2ss=3KEM^D5H@549$S{q zuWYMafNct&D}Df*n;me}#RIUK?4Z=xpiLHVsq08~F%kU_ZsF@A;QsYJtn~hLEr`z; zy-hB(h5pfsV*D-GW-sGR0RBpbbfFDbEo_Hvc>$)6ydnRlU#AOf<3a0v7Z}R~T&J^1 zZMjW(tX*eg8(c>RZsGyWAEic}v783)Kb7`4!LcRD(TcH=Uidayp!4Xuoc(G#wW2@i zQMU2!n4{jN@3USES*7Iw&o_jV9Moo5Y&&v#v=2nL2M{3c;`W+R_Z`bZiWLX$8s=w%uIxTrGlSDrC>pHN;S8$yA?uy9)IF zmd-El>`r%fb*^}qPfF}hcez1%|8P3G|8RQz`0@1Q$z#6??!L~$c*5)U`-|z9zxbKo z>T^%$h8JgN)4%*T|9blF*|X_V{qE@g{pk;W|M#aK|ME69V=fe|WmpajA zK9|$_Tn9PjDWQ|I=|VoDe|r9Idi&0SFa|%SN-lCuUX6+f_OTO>o}Zy za8tDVH#ZaOoS5;1#k71Io12?iEYNu%-_Yi|3+K>0t;4yx>sfW<_~Vd^rdJ_1DKymi zj)I?hQlKTh2vo-opG&(%xK5Mrtnn1mCFit$at%B5Ih9p>KgGkjy!s^9htLFZ~&d}BR*f@@C%iQ5Nm#zl`$rr;NC$pYbLPaaLb^TRLwYC_(M z!y8{-zdiNq317cG_Kr&3`%N&eX6l>vp`EESXW-b!c>U=YezI)uo)>$0+YNQVYa!{I zyf%>qDV}olx6!0Sy}dm?o=))bjHl*kH!@5+v&Z$dBHG14its3>->?&}D#n*A2y=}y z*ZOFa^rKwAMDNnqGsue=TerDTSho9G7qQRrJBRYYeOUaEDsROco3N+9AoCmR)__7A zaGuS0a$EKH+5O$=N1r{I?%(4Yt-VLc;}5d2vFI`w5H+4t&SU$jJUJX~vx&c!AK6&2+pCbEx?R~m5 zKs%*xeym*I53aV?p9hTodg1H8{zv~^_CoI{VzT2&hhYco-S&p$gIHmV9Bdje*D z$@PwDCSa4x4$H+7?Fx%s8%thk4iu1wj`bXzkT6RkmX&~aZ^?Rb4OG(Duqp{KUqMOI z^k~mp(w^+OY-KZ<7hm;Zp9SP&S^x_HYy`XI$pnyzT1#Xg(*aGf>q2>O(BzUe^}$^n zJR!n@*Z=2#{2!-(|FfS?Prv=vPkC{`A`e@0-6YK`2We_r+;9Ta5xVJqK;qF5g3GoIAz=`!$0iro5=)v`Ml}{}%C1?3yN{ zp43VYo9LiB)`!FtQU}QM1eF(fWGp(863q)o!ryb}5arhdgXJp#y6xDmVzCjyh9@Fw zL+7V{Rx2BJ=w7+v)h_ zsV2YgrGIOB;1AOt`YyAVn(UtIE9s_s+?Uw45 z1wfAxKGDgfT_vBMJbXO;!SDVh$GjHxZk-URnY@p?p8=H?QycjX+Du2L_|G^@OcSKF z%Z^Z9!HJ*rm3#vXaxn+nIUGpFr1TxE#U~_`at4wqK79ol4I%c8yiF2#j!U0YgdVZC z&cAylO!Q*QGU|^I+!sWkZ?z~gJ?0h(A{)sPQ$}scLmSILmv8hr@2l9Z-+VI*BK#CH z_E0T(^=wXH*>~9gy8lvs*XTxrQBST%i-A~bPN$5n<drS83E*yGKvL^%d${10lToB* z${NJ#MXgaPDybFw?~JgmdaSZqgTMPGl4XNzJ5SmlCS_#54cpKuyI4fqc7CNV`k(&k z|FRdpHo^KE&~u(mi0r3j=6Y5etSYnX*;|@v;bME6FDpQ%(1x2duCvE}X`t=tE6A1X zM|}{CGPAybcq~)HR-2+Vb(6a(f1UmaTV({-(Sc9V8717NK?6!8&9*s3A?m6a?G2(- zRahD)2br$JrgglHKGMdv0A{(_r-j#fdn_sXs87r|4lq|~==?l~HKEkCDJ$Lr*ckH! z;I924Ecups%&{HlVQku5*$jRfsdVKx+Eny0aevjtMQxG1l`$;n2Eoa8A6)z>D4Bp#w8+<73-I4`?4oy#{Dem9FZ@Q>51S zrfl-d4o(4Pp5v1Dc?d|+oxch3iE@#)z0v_p7x-AIJZ4TKqG$A2U{DuOJ_rkOWgl;t zkU0Bl4?%JrwE(58dzI@tQ0!B7&O>z$#rY`bDE_9;E(>7!j`$(3z2D_+AiL9hoj3mc z-~YSm#f#@YUh+D9oBf@BGembo5~Q{L3Fq2ZxVzUVC@Ccz4@R zdvV=~n>Jb0IN_-poyYooQ0Lk_b%rl2%Dj5{YI^fFPkOOX^8N$oxw$^Uxr5IcIY0J! zgvuj7{JKNxS2CRY`g)QINlU)J#SNf3@8vTe+(arrQm^awy9xUI>?&;PtCe(&$aw>M zjwDo9J%7sB0-lAhUHnuzp!fAK+S%W8QW@6^Uo3Xi;s*P3W#0S7 z@XtT{Y36Ua;cZ-RFGQp1#4GY2LWJUp#pC1T@$<%etyp9Q_ko1;oEV%(dh@De>VN-tIz$(6kg3qpW)SqEWRD9JnuO_;94bh zqPpYNojZ4-sjcY)DtBzZbDNxU?Lsta{qXQ$die0r*AnTMZ@4j7a?}CW7UAOq*Jrq{ z#^T|t`ZNqS{q&UTiSmx;+>``p1wkcEpNDg`4Q+7y4sWqayOZv|gdN`0$4}#2%`g(*vVzc(EB7?1t7cz9clwRMPy5K0@Tz`(x6JovwqmjdfnYhyyDgVdM*4 z((S__zhP^HoAPOxecpi0vR(nHeV@EtD=Ep?2str)>CVPQEZiJB5#gpnK_?Oe z#R{dTfbB@dM-K>K_$7PRx{@Co637r+Y6W=G7hEE2isQx0GSk~K9G^tf-vgF-o{(z5 z>w%22a?uewgY)s*6Tdh47hnH!`d9z@UrtY-KAm3b!14UqQ|srB84bKTXmGK)U#I5_ z=Ncdx;NUa4;FV|`d^w;Rzr*B&$rB4@+`*uMe5dYWQ2yxpBZ(T={VgK>?nus0XDQzd z_<5aSzcZQlLH7bzZ0Gw%UNDm^^4Rr-bo`Kwd65g7)K~pHajJs~wmE2fQbG`ofxUMS zY8XxGj03XsbQ>v1F7>QHy`nE1IbO-;1D@?69~I<$$A=dVbI`NC`5a)9AAX1vm(0tA z1OmPx=MxIiC^L3^@tR{Bnw2NASyaoQN>0f6fMz|V%Px5VMDt`rGWM?cW!1jmcOK17 zyJq61zJY}E5?M0N&-SpRI+Xwi^X6F=d(J?7wXcPgX2Au&@q==BA&4OG0$1rEOAg`W zm3a8$eo-9SnYM?X$$;qcgGE(Z+KZNDgnq$Ceev()gvodIoh}#okrzcbluy`&=EEE)ayfF+P0^N)LL493Zo=wLWr<0~%)2*FJCmg(IUGkdXobXZKXWvb)cpCG?%jwPQ zH?pBgsq9l?^5JeTKT)Rqc6NCJGOxH~vg~qc^2tO=C2+sv#NzZsCjh*bfRhgSv$KD9 zdieNYI(l$4?e1w`)BeS)MOg%++$@qanZ;*{s$E>bzQkRFcc$|boychNd49@!*-xj} zFC~A*D+)E4yw8FfcY3{>UOs&_ohe^6r?j*Gu~;W>T^{aK%LMJiw12cS9cdEEs~7pU zp!=EV)Ms8@NV#;%ru>igkEYKbJ((Uqe54aJ$?xR#5uSW1FWhySF_QvdrDF_&D{uM) zbp|O6L5ZyaJMo20saqGiVb+0GJO@F96XcUc@ee}#WoVojmLw1{wJbU5!V9#>0&PdZ`GDK=MXvZUmu-2u$ZP}aMIPI>D5u8ynBB*|*;lP@ zcoPq#P!>rji0Y{P67JZ-)CYK^|K6YeeN%rM@E^j$*Cu#w;|jW34bJNmGef(Nfmc9w zQuW)bntYPi$Kg7uQGc5)<{?0joA?BHdrjV(c1X|T%)o0Jur=>(G{P1-u$8_+`(C;Q zn>^C^KGH{g=2h{`sSOePVi6=aqvrO$jL2rb7KC1H($M}S!9RMfKl+Lo=$OVRY17IK z&@xTNx9AHgUKt2Lf)CpK0qplmJ~ELV=mM9aZ79m|81=}Fz5#7^qZjh5W6O!n zn0ZP%&G|s;JnFFlfcb{FAs>X2w{t;Y!|w$+&p|$X`7!nj>?m(+kVlh&*}qDIw5?8~ z!+Z!Zc~r1|%O-Xis~|r2TC5vdKC!sciyzpf{tAkpb0P?JJ_R+AApLKK1qCN~B$24p|#I?WAv zIs=i67ryXYKVN@Qd6DJ(Ki~UiEY5Wi%9@)(V~fR_2M-?knjMYKr$@Lh#_IxE2*geN zVLV5Vn_;2jAJ^u5zJ19z?r(d+>2QDFi(rR`d()%GN7IwXkEZ>-17D-V7P`L4S3aH` z^GSviFC2aT`2KXTx9cYW`QF&qPhUUx^&QqD*B zA51^|>I*;pbVOJBNw|6qD>ct|7G;$ZqK?LdAb%>Yrp|&8L2aaR`rZt6PUN`U;kFme`=I1dyK^URxiLW2KKt%{o>p}Gc;84~D9~RL zk~cBqbNV`qnc0`2H~sMQqv?>h0?`j+c(#uY z(0IlN6+y|)w|RYS0DxvHyohbc2U>TbEqMUY&CzBp6MUfsEWeFbIAFeIsExKko{QAl zM(VO*oBd62pVXd+ph9nWm-Yzz#JL&u&kK?(7}!JQ6yU{q znY<#QZOL=6VyMGc)VZ+F0L~pc{W`-}uU}1X-@Nrfio0;$ym{jbeL7_OwgKz{_D(bo zq8v~?>7bq^#>5P}@cAXHn(#TF*t1D(JONPNcCqsE-6is&7j=DN=ZsTEJ7T$8ernF{ zD0n(3Sv98!JnGIwIX2T9Su|r2w!WKnDW3%NPbNFQ2o7B_V+?fea>GA90PA;F>qoxI zF8L}i`pE+E7l+(0B}*OQGk2(ok@`>_p+=p%zkJZiz`OJ5^pbCUU3l?|?|L1-emy<= z<{O2tr#CNNPG`qw+BaoelZ{M$kq^dRYLW=tqW_ELa`L(i*SBno z&&kT0w`bGa*C*5Y$%Xe7URQW{bm%sH{_QiEzs0XF- z*~SH+-cOLDKhk%k>~Rr*ikga@yh*1LjA-UdMv~d_ld)N0!;?aT>r{5R*-@Q8yQk& z$2H;9wfjuTMBh?r4>0Trx3&nDX|Ns$Ws!_+K&HKywevQGG8&;AjQNTxAFBw0 zC*>l}eqfvYoX{_l;}&hpny;-k%?Y$jDDmGUmw{Koc74Rxm87;XI`0CZ@hP|!OiSWF z|I`0+5dQOp|I6QF;cM}FfyIR$r*4EBL_SG>1FqBYK4199ASIA|DR>?-lnZc;-;mcP ze4n!9#6G~jk+CR18pn|E__1jh-VJ%dvyH+>7y9xJmO=O1;#P5VJ(ACYw&f1g78#M zZv$)jwe2fOrQ>^B=%Dj%V*9d`FRnpXBof}i>4nS45_L@?MB6e~hNit*=U{ht_H>?i zZ$8g3aPFXU8E)F-x&zmSc(aF}GP;w`Q@DRgltsy&Nv`s@r9|OdFZH$AL^qKCH2XhbdY`c-o zc`4T$FmI}O$uo36xg>jBi(t_%`x*Y_8cf^p^)l6G7RV^0cqxqQi1T8u4Pb+M-_toV zHmf)9bft8!zVYDn@izY`UDU zDM6=9l$#skAKiaAef8xR)5AwBK;=9Cl!paWo*X-t?-yrW^LXcLB71vxriTv>rY8!d zedGU|lj)^=c=qb8Uzd1##$p{$$f>Rl4y3c^{O|`~e3P(%K6i9@sF3=jKHt24HNANC zdV2NxtrzdS&#E0cr)1IcuCFz6-7`1v_6_4{*DUx^M&63U!k-tZly~Vo*N0@ouUWG32wIIdO?zTLxgH2h|Jw5^7$JPj~mKMcc z^(nznjavYzNFql5znTY|kp32{za97o|HXfH>(+nskN!JVr*@tyeP4(nqMk{?YPT$_ zU&l?49EAWW#iCxdA|TlyGWq+0p8jdn;J!HHIHGMP68Jr1p_3H&PFCc$ekW2wlaR@ z4h#+^9GrYGr~^78&O&Kdm43+b`Z<6Sa?mx+gOBX$kALLj9iz(Vv}AlimVsY-sfT3J zlPNOd1FQ_pyfTe?pdS0;Co(mDwcMaKeJu9uec&r-x?kSW9?Nq%?$cA`Wah+R7hcONOdo8 ztUBzr@dObevX;0Hj!Iy@Cv)vXpA_Jq^Q`hD7i{xS44*#ciJm7Gp>-ehVwfvds@Rea z_T4T@(68JUou6>nnDqt7IVNeiz-goeB)G786M+=cW~6R_jy z^^0fIv#-CMUOs&`ogJUr27p&IR zki7evg*84<%w&$fzNbkpi)r}r?Ca;#>G8RBfjjb_I9cRw!0*q?Cv@TO_xf_x})}7ps)1AN=M7S1Iz( z--4KQ9Z)W4+FC{uDFaH8x0sb8S1fJ3g<{{`tHtE^!K;&CL@2^tZ~ES!x3c@{Zf=7Jhp26-p7 zrQAfqLn{nfuOK3;pM6bT4%&eb9d(h6Ym+usX_bhbS=@-zCRn4kosRC``!9Z*3t#^Y z9(V5E1{N1m7rzFO!>?fDI-M0&GGltwaS2q}U6Q3;1JK={3O4imK0a@gg#x`#YDbAr z&P#N2Huli6reGUyq-}C ziIpwzxif^m=2yI~?uA~E8xl5jXL}3Yu!w=Ucg|UO{8nJ@X>JS8I-zy4^=w5|v(YuS z$^y_mW|e)X2Z5#wQ&<=aeGT7_E}xk5&YmrDbN?-tW$JLcY3oz-T%~P$lg~E&3fN}% zy1a6{y$Z+^HtT$h8)kZD6^2b25mFaMx9gh?PH=rSF?Kn{AZ?$7(*jrhTYLa~UP3IM z%?=8tDb5ix<>fbvL^XCf*<(NL%-KRW!oP4Q3YRSPyNu)`aNfcBvVLOQmeu0FQQIk7 zf|%`e;@O9lT=BeJr`wZ74_NRf*DSzs$}WIe2GCErMmwPwBH0L!dChw5h@jhO0p)D{ zwcY|!UZt&3n84_I{{+}K$#%%vu(rJo@TX7%iI3@wFv^m9Jj0u|JNqz*#?Q0_z&K6q zdBMnw0-W2jSilXPT$JZH!u20`oJ-u9c646J0tAZ+I)kl!C^wsWp`hDVb;C6&zMpl; zVu5&^tLKIa%8#!oQ}-74ISp;s3rpVze4Rk$=<)JS4uRfZSXk-vSAb&)fUM7VoD$u6 z<~kVH$$UO9;F_IvaaH3q*F&)Dd?d$p09lf~4=V3_-^7kpFLbe}D83g>Sp1TYd@G*? z$G%R$4XS(#jOHv1IsAvq=|c6+Q&lft@yf$n(}Vj*eyR%jmv7FepZ(&gpZt1z%z{rAb@+?}Pg8N- zf>xx?e9g(%q^4G;I49;)5B@yME_Hg#*G}+_{5j>l*Kes( zId}!(3zhGsZ1IE`i+$XfO)FAwTwi5Dmv680WFt?}alM9XBh){6Qr?#@U;2TBJQc|e z!Zi}fUv1p4)0gw=P6GXuIDJXMok(py-`t7?hPv7xwgCGVYV-lilZGJN`8QATq3YvD zPxhwI@2h@x!ndE5PvWGbA)E@Ed25*^o!A`GAzhIHIL}XPX@^BFv2Bp#y049X0wK3Fo5xQiSImiqQo4Ukz>P>$5C1}+BD9ED=E zx8&=S47WiJ!r<`~+r%=Vf!W{oDn4~(n*5C4Jpi!q!lDZG!hl^iEyJKjt^y&ZLxU&+ z>7dj?)s|?{H>dLENtqqnxYWTFNw>o&2Y|{sFH~^wmt5*M;E63s@>9rUgh@oH@*|;? zPbg=)wrz&Oi-IYeqYfdt9YCsF)xfb=GRTJwGY4IK z!d5PtSJ^60*E8QxvksO8wk4j+#y>p(IwG)X!G7hZth(O3psLstMe;;eKQGQnGksJv z`lAeW|IOVzcRU$#`9vch3K0(GTt8)stbrzB@n+C>78XZ z0&%TcJa9HfRAvkbQ1v*1J+p=D;OuO*Klmg}e0G8GyRL|X_o9gRu98oA#3xPva2841 zMOTf99#1xPcoNPoO5AC10d2)AXhRUabinBg>}%8^#~12PR%3%akVj2G$_#w4FW{!k z&4mPrt0bsHHcbIVvG9Q&k~ZQ)1vQBbC^hMUftivhAIg^L6@~3YQ0j|h3C+}5O|W1M z*k*)_^r%~gi`3{$GJ@Wauw`#-2;XCY;_Mp>jCuXK_#zboz_E<|f62P4$6c!2Wwe1n+d>AuYbptlb zvzZp9!oq7$m(g?4S!5P(RyGF|FmDttn01;zz??_L-KCObLs$&1^51~#c%gSln%|W& zE8>ixZzgb4&Hj|k25h6RXy7%cY#9An@Xa#9qdu-LJL%p(*PN0q`B86e1H64$!$|9M zAmEBE{oBKN?DerpJzW9!Gd)`S7&{#TCKWB`>lo`uz_9!EMms84Xvq<1d#%Y?7b&Zi*qQSm&!nVPJgpc zLtYId-q*oc9PtgEJGn`m>vnkxD*e0{K}fT>#WgJ!ly-LR$bYVFUEr{7`3Bit)sd3t zeCO)&a^iJ|e1D&Fddj=Ezc)R3{A7Cg;QsXP;>-&%uiqT!x}e5-dJ_v@M+Yo49olC; z1;GLtucgG!M}{M|Om$iJh*z3Jh@2h;xU-t_9t z>Gbb^@!j;@vscr_Ic@Y|I+lMd1hJq-`KZ&}G@P4v0m{Rt7!LOL{rbftK5?+GKJn<` zbaZs&C%gEj7e3xqSK7Jre!72fXL@|ZH^6UAXBQu)m-zLH?{u9{Cuf(_@v&ka4B$pz zRUivgckWWBsV9H`Tr@Sp^j`IMTQbx&b;5VXp1*wKC&~DJ`k9{;i|_crTWt9LIBn2l z6pLoIy|?e{94yqme*M}{eqB&@^rh?mpuBkEtDokB$2Zh2 z9nuvUV9W!-G5@}ng8p{ht2AI+dZZ)|D6P+CsY77X21lEQ>+%J%zh4hy`L=@8N4wkd z*ajby`&2vI0M(3oPC1a$F!B+wlrd|`(68>r2;EP9GuF1jW_|Ih!#jWTkN?h3DvgAT zmV#wNA94}hnTSm;V^#QNV+a+0l=L;Lk#}_T}346+~j@91a6Pqr#apjo{s-;`O-8u>iDXXN?AR)~$ zbWW~40g^8D-V+M{s1u8_1qq!A5-Obdc@hIpx_*)f8PlAB^P%e9N6QS*?U%+*4k?-@ zFfI#Jct*mbbt9yI;qdkEJg`IX37GzU0p0tBf(KZWv@wnRM8~@7wCf=I5eH8mp|5uh z*MTqJRKo}9K#*bg9p_M6%3HQU@sD)$5YVPhJy{rHk}Dh<`t!-C9IzehL>~sP*@N!8%kZVzvL`y0!!PPf zE~JDCrl)QJ-e1jou)q1{m($Pw?Z2I#{^FbIOq0zI@8T!>h+i)#KY03yMK7Mx>sG?`@ZWduQ`x?`haxZH!EL!^qqHA&-UHh1ly%;X&eA2+!ujiOGOMi zQh;i3lMBqHn}L-Nv|azqbbU#u^qoQ$Ir2~ixX;;^jp+}s>KYlVEOp;~6)kX=r(`YH z_KOD3{mK4R*=5smjOpUjFHEF^kxxFIp@Ee9M->(TvKT9a$I$dS(Z>BXA zPZ9i080|E^8NLrVw=H^3ZPH3^o4jSA8(nZkSubD||JlW(IgvN2d2nDlz8QRose3LeYapzdm zx5+}>PTxke?BLhPo72L5JRf-08fZ-qzUU&i(AS~iQ|L*D7JQ_a9C?+@72Xg&MlWOw zFQKy8;1h?&VV}9L@kQ7n<9TgN8f`3T>~oi0w_PG={_zL}ew8+Uyk%=tz3C92jzHc98)X=$sRyC@@oOe@aYAEFoj7~Ejj zLfa+ge2%LhIqwnRhiL(qx1i~!DKrN<`g!9~_D6#RY@PIIQ$McHu`rZt0y(e4ZbGi} z-gkidV9(nVJ>wJuXB2x>)*c14aD!&rm8FX&h-M$_fsmBhga8m ztf6h|{8asd>u>nSTWnsxe(UdTz4Z6CPI8?={!wo%INd+u+g&i`+W>7wy>}1rwH^7&^$xDBQU|`y=fLb~!qbcC>;~J}~GP@2bpp+6W)xlg%je zQF+0yo#&0fxS)C;>T8a_hgoae&aVR2Uc#_{{MwM+WCh*NNB9?i_D}x7oxkbvlv@R+_aTvM#@{RUeIy9=k>=!6vvZP*y4Ic%e&! zDhEOqpS08a;;>?WE60mq$iQcygPsEcjY{n6`{e3;7}T@yLq0x;h(10A=XQgpG}qus zGT3b zZW96@UdlJ>fbw863$5ad;Jb-TO`fzB3OUHcmg(kGYNbklE;Ds4J+Pdo_8%1qPAUW%+?x;^s_PT7H zm;P!wt7q?!O-;Oj)Q#n(|tyuA|$E*(dSi&hG6jPVF)gVi7qLBkIn@!50ND%BtRYvg`cx(sz0B`2YEt zCRphn0m>rVd^e28`*~f!-Fv(~LK9II1T~o@rmbBDx$iNg>fKKR(uTCRewpa0PNXNp zS(uWK^ku#i#$8=DLLJqxWq&Xs8;nDK8dFRr!hX%7b z+mVmTllFH8Co8RaKdw-x0A5gK`tMCd@IFLl~d2xyC~Fp6f&E*Is6Zk8JcJU-fv zNUaOk8#%{#(u>RNE0i;J9UXtSOzDh=@g?@s2N1F@7X_6st>S)JI3Itdst*LXrTyEl+1w=l~%Z9ukT91-fmMb4Zg4XIatf|6-oMKgrXrpsC~wvj|= zY`4hF{G~n`f~AE^VWwHEWwArF;xBm8M4>DYp849kEn24Zm$H+-HT~H?|L4E8g|GkJ zfBH8yPbPnRXWG~nK+@NTPlA~KmEfklMqcw*v=CPFi6;UR0X-39>%YnAG;7 zocTf0wy8g|&Z=Z1S9(blTXFdSrDdElUc91*x1^IuI{0;RiYpC_{t@@=G_(ptqrRd} z$J)|ABNM(h!8`4^1L?6dF2NBS14#C<*6YB25xO-Lh;mF%s%2>p6U-1Lbas5ZKw4Xe z@D|z{U-661X6EU)$S?JoKC^^SOQ=G4W(d~2kcex%0o~+Ps9FiVfb^I@l)yH8Nyp@d zu7dkb2S=fQJYW|9`FM!hI{z`O zo=>O5Z`E#R7xs@uByNoNlT7wOWvw=}ubkWZnnTJ$anh#XY3FmU6`Ws8$H!;W+c!LU zbv(U2KJ}AW_{$>P;r_kp?k)Lp{ML(De&R~?L>Ya}je2zDzVpqzyteQRe@|ue_;`B# z`qlL6!9r*8*HH=Gx9s$#5)ZbhgNAI z{0?ScfzbwXUA{4FgH8HXotycQSzt504L&CGDK@qNYW8Was}AmQ5%@%~rfvNyAT6#N zb^j$@{qt9W@;-L9gwz*dfm-?h-W0zfuEpN@5 zJuOM4od|^}YAP>mwjx5e?IcSsbOuYFj^Ifw4isMKQs6ONUpT&dFBg#rIWVyDO)1yCn7%v1vZ@CUpm~Zb{0!vSgq{-^)h)3@e0B%TD4y~; z0LoV(7bw#v*!5zYV&_qnhmWAHJJ}*OP7(qz&$NScJc(q*H#uzhf&ZaDyvwvM7a>1V{m)**k=p_E71cU^N~n><3}8%;T& z$GaRPrQu1F+Ewzg606vtU*HqedGQ3_CkD zrA!FytMYX{;3`?MsVp&d(I@gw%U?-{56(Kl^eI+7=212W0a zSs=IJBdEu5(%`~ePu2^W4YV>NosjXb+QZiPs1p{Tku=ic7u)%L<=NMs=3+Xl_ zujB|hw3Ho6#g-S{{)k3C{47f-U5ggazC@3w6oz65Uef#voYa z6i_o+PUE+~g=u{l;h|@85tMC7;7RzdGjOMkQmet)=&xN$vAqwed7&U;hoV<>#T`OO zeHgVy@%c%YACP0%t?AGH?6ES?p`gOsj9O~s`;X25? z;Cg6pN3Umm!>;M%SMes?k6Gr+PJPNF27CW0dBRxFE zh(&JA3vANH^os7nEc`xpnK#Of_>dmyz&1Kj@J)H}>vYz%O?vS7TFIg(y_SQp&}RDJ z&x$_8S9qm^Jx0LzkYFyXfkwzEWX2p!8`5*QVgo@A8$ptHd@yRel5>Arj#nMV^tHJE z;8*#Du$g0`**9>DM9(_@gKw)7q>Jy}*H~z+Pg!&@b^WgB;G5~-NfUdkIC(j3-U5s4 z=6ZN~X6Vq2@tkNAiN9$UC3B^IIXk&g|=L@g- zu^G9@nxH~2w5tKFCB4|~&}ld9N|w<4;O*P?u;`Gklx<%P;f~O>?P0AiiZ`&FScTZ9 zA1bJ{4^O;~|MGk~J$^GCzkTa-a?VN3`|wWkI)BBwUva2&Q(ym3 z7V1>=HTSKd&n=h$mps7@9^|I5M9d#^9-u$|`WLuq-V|A46`;hR1raG1--?wov|P%Q zG>a%ZKA+DG&_L|w802dQgu(%IkvTlrpB_ED?>Ea}iyL6G_{H@Y5!kOK$2AO+SSG?v z7R-L|#b?u(PaaB`R|o36|J?__n(s{K^elp%o%3qJQ@;w4YmF?@aehzRu!z;R+&48= z(Vi?U<$7gq_`P$RYnGe~^K=;bD@c)R1lT`0Ih|gsKk$9A)6)~bnsEQ#&U7yP>C^9~ z3;D$>8~N^5=K73PE{t#X<*6^8OylXe;Ahj>>FM<1<*Vt%tC!R9n>W+h*{K(++R)ie45Bd2~#~X$YazG!yfz})OYnuyf%0zPwky$t!CJbx4+whjkp(+FO}D%2x!XtSR^C3O&BLX!bIHr%k_*m8L!iZNNsLCT~A^kl~QiD!$JE!+BmVTnB4 zcglt>;G30&gTRMv8A>XERd&DwnPgxuKEp_C5ykWhQr#EQ253eu{c~IY!Q0RfWn*2c zrQ}KbU`Cl;j|t9AwA81SZ4?@I!L5rPY&+I=HOW82MfM?$oypU)kfs{XsJ1I}>isK0j3pBj4!F^t;1pG3{ z*2xKX6TO&Dj$eC`gYR42+h>v^n-~+|JKx>n$xZ5l{gQ=iFB-@e--nWCl2<;Os4>Z6 z^2JknPac0h{r>O&<>`<9=&w)z$^YhmJN@qO{GKL~x2LynUwg4?XXmzUGXeCSMzTqH zv~}#)k}6LYo4g3_I*?ENs8f8L>n{^O@P17u0sV`!3r!r)#FugvUk=ka#+bzMG#lUY z!UrnZ3!=ijV5GeIRf!&NsAA=VFZ4D~GF5i+^Xn4u4L!WV2Xx$Ls3%#)H*6@za~3q| z`uIejGlmSZ#w(3Swi}}RitQ4GAKCP4?@!bzY4~E&mjU-{Pfn@Z@{t&O_7@Y1)i3bQ*V?u?Sdtlowt5OP=~sOO_?CZa2|=cO55`(%Z7$sLepa# zQpu>GA+d=}v5lv_gHzw6DO#$-7A$NrZ}gV{KfZICwy~7`NOgBQ(7XoBIQC|#4->Fe z0!?z=8-K%K%Xcn=jEoYAOGH$nr6OtJEerD&>^nOm+i#p z#h-+wt~}b-z6%i14oMQ%@ki;BP}-gvpQ#o|9hrv>%K(x2Z7zJ>zyIhb@89vE?@QMo z^D^}q1^mRH__V~oBDASb2?KbHPbC}Dp4W$)z}!KOZPQE#-+)c~t^28Poz5n0Ok1bo zhNcOb)7#<|KpO%QwnKV=ZL|?aUdvu5-*mPeL|pVp4=~d!Y|@Ib3Q$-40j}r@w$Xq! zJ^id@*cvMu<5>36a1dMMn^pt4A-v_-BB;JR(=A(8kzry1KFdUJ6YqF4Tu0B`a1AqG ztWmbZN@kz|+vtgs_VGsL0Z-Q8t+!Eb)7nPxC7p4IWWrUsnWmrrO3%kT=`#ky>o%D6 zoLbw8t4n&5zXIpg$9;H9J}aFq^@}o5@HKxkJ<|reNozCMHm&e$Y0h^|pYhrE7*5&3 z(>Azc_{*Ha3_;NFBQxTP5z@ibF&oKJV~r=h@Rl^VY$&$92*4>Z=$#gB(Mls1A*V~t zY0K1{z}u!3bb1UUY@?5~ksdd?E<%94RUW$e3bY3V$lGL#2Q+O{4yyKuIUNYqn4*>Z zs{dM~gi4Oz%%24Y{CZgHxOD}juZGA9E1h*%%F|)72avuVoP$N8H`|!il#Z0f$K3Ru zR5*-ji9hI^_jEcvemkAMeK}p6zMkHlA17S$`a8}&FLi#*EB-iV);Z&4VqYtey&jwA zF&f)(Ze64sp#2}qF~-=&)F{)T0o>mn?T0gOAl}0CS!wa2rV4g>P&gOefws5{`8r@S%!Z{D$^m~0aISc@@+H9$c^H8ql)I- zDjSPgEY@)?h3iAUzMzorn4e9@Z;$;d#IrM%sh-;Eo5e2`vslKf9(mF${^Os1YER0T zbMD%A)V!2Ac_c4?Bi^;3c9a~~k#apmKet=1-S$n;z7_ir~vlS2DNb@({X^t_|ba3y^^nkYmaZ|nNwo>>;yp1O5ZL;Q&=3jImc*<+$Ok2wV zE4tAoFJPPAh&NnM>p7d(vf2LU2Cq_k-QslsjB#Mm{6QgZ$yW3&Z`8wbqPf0QVUDC|I` z8#>PncV!{}FiQX*e1Vl(RK55jG6N&;LuSEA17AEY$kSww89B>-Ysgoz*|+JH#}lN=Qx z2UjsD0}mf{K9`crw`$)Mdw=bqAdLj8QWE$ zjAhi;*l@>Cle8TN_p`bL7ep6aBAxh ze0)h>QcHKKE6OCC*gw(yeX-lTmJm0TGpa7O^k`Rlk7Rak?|KY)`}&PeNY4EF#TCf3 z+g;__+hY>S6R0)jc%d(ClXj)4dR5QOz>5D0 z9*>+H$`on@uwgu$dCR8C+;omBDYrJ(1IFzDMTk`Ln2%c`&2%NO3pgrXNWqZrl;aY# z9V^2bY)4EGWNr_q7rmr_u|Aq6=yV2&q$`fL>I1Ck_z+9Y9q`(O4vaF`Pug4C$5Q$? z;H~K`DSq=Di>iq5+g$ki<`+Nv$-nzo|8n~Jm%qr}q~~YT#o39+_srYyE52<)yxxSW z>npIuz$ZZ0(XR@d`t5Vdv|+nwAIq_IH^W%+O&jnxVUyN&MrayT;%&9tIxXAy6@XS@ zlx=9*7;b{=WVg}TI&9&Mz&N|A$8ECU6-NH1wJUmpQGNuHj5EDojxsH|q8ATtXht0` z?4=|NKk`1L`jA-moNuSauxjk~_-Bgw!8f68by$Itoz2<19xnG37q+1vI=nDk?`fWKbL9>85S?kQY`3tHa`6mqfWeYIP>Et_iWP#1h zp&8K~LqpQURaVP3eF=f)k#A&*Y}|oF!Au)N@q-nnOiqfsO-=6`|m>->mWBVtRjZI-Q@q zp3cwSYW{RQogTlM&QIS?mpa#GF7^H$ul(n=`&`E%1Z;`^N@Q~13<|}ns}GC0lx7W_+aZ&4G|mgT@hSS8SHkCdzR=DDQ)#qv_$p`#LAzaeuAlCiLz#YDql^ce4!R4FZCL?*W%9Ct6)6Q<) z+$uiTQQ)~=Fit(FtiCpIaWS2ooJ_A?y_ufBdMV!R>A`~s)4jcYm&MnTxTeCj%sY2& zpE_X??0tRM?jDP12X# zxcuJzn(x<9MlXsfA7uIg1)j>=!Eb*u} z;tdOpxI)!U(gIZ$>A9W=D_gy<2iCkbZ1TqRXushmTfncw|MhJv1oL(iKBgZ)hCY$D z;@7l7GJdO!umRlNd>Xvg|9#UlfUzm98R$G#r?1BkIviv+0_li?$O6UhI~Hu)G`eec2%{xlcQrD9I*>tgBpJh zn%q6Sx)511x!B2pmW2onn()l`Uv%uDr@>SMFoWk3^eI?hT4zeCGYmh2x) zIJqlGxynz!eo>RUJc*;cB#T_${hWQ6i=brx{sSMBbYJJ}xqGjU7YXB~J7xg*c1v~d-%kQJ+ z8)Rg4nF-iC$y>*hKJ|Xt$)t|g4}6$*?(BGSM*Y2h`Npp{@PaAzLIKQCeMyf=E_a#j z>~bd)cXK89qs5B3ql-H8B$v8WeG&MuuJ5)|{_OI+V$tnFQ{b!+_jhTf6NyItSizTy zz43mUy7jnVfyC(t^rx7xqSDMF8LcMX{&+;V0(1TC8L9`rjR2E{Sb>8v>{3Q3(HmXaDTaerpR~mlvl$IXitdy?Xv^`u3MUoqqc7 z{^#lG*FT%ij$dg!KAS#Vp1X|fTT~mzAbagPw8z0`WLs#k(24?tI)DhS%Prw!uuXn5 zJ;KPF`HgQ0_Fd?l{iNl_bmmOJ zNO#!CXW^y4#Wu%7#RK1UfQ|#W&o&CL0C>Ks2t5!;q>a~HZpBL)p_%7j={bJFxNr0g7vzb;I3EXT4c~wT9gf1f;j^YjQoX8Jks%xGA%Y%pyU-=!MOi- zh^^2Y+&(K<(ru$5c2Z}A(e}3RF_`6?P2@$X?OK1ddo^q;$EQQ*v}t!4r{Fc8dMSm1 zrU&T1EibP=@N^eX&v1UolT2qiXFZwTUmPo(DDMmPM4dNEFXu$)Cj(5z2Bj0td6){~ zdFJd2KKLh)ylp6fO(Pa8nZ?-|PZ@%DyQ9l_H2WdvT`{3p=jU82;95j4g29WP0@)#_ zpTD=QU)zrk=gp#Wy@6QroU_Bn1U$~EPtQ+n@BY!j^!bwq(}SZ!-%yGTFJ4g==AmVq zYkKt0_D8Ol>5Nw_Qhnla?UHLPTyxxXmuyIGKe??p|_vk~C8K@K6$8+s_O%W-kxr^)hK#9Mw#&i?*^!hRONWRG&-E;u(e z`%^c{&%V-D3e*9?xP|Fw^1q7bdLS)dVc%24YYrdmt9>L3;BK&}VFQA*FUFi-<=r&L zg*zS6h75HIpLpQ`AIG=kS22AYe5B9w57M-i@@^RiXpQTareXsvekMe21siEgibkFd z*ckO(pB4m}qpP+DxQW+L&0F@@@+0p${!KZMKfkN6(Ai!Wl3#-BgP$w90#Q5@II#hu z&GLdO2!6HJc4+SPQnonP2S(W@j`a?KfAMGk&wp^|Z~pP0`~(#W(mP8!76UI9a__Y)!JE8!20|LTD?p)hP z=hm5&Z8+F#ewZC;BYBsBl;ZeY01^=xMN0nZ@Sy>-&mysN`MXOTfV_jI?3gIGJg9nb zw%zD@46|*u6MX6Wky&4S&LUR^^yo6!Gf?`e1@r2lP5!1QfASvv%|(35seJWk@yH&y zZCeT-*~AZRmC!+<1|y_0aNsuw74cOT4{$MKpm<~6-d56LitUSi#dm0yiY)mxPJYC- zMW0dt_~L_x`=6#(B2%}?LtAXhH&0gZku)Uzu#kb*hO~(sw#yYkbW*>Fr5(DS-A*hj zNp3!f3h*Fyg4sXU8#w>ULmQ?{%uHMtw2@tP2?VJhQl^mwdM=Ot5@z}6ef1~%DimMI zmskJ!Nf+0XL&ceimb3iRb#t{$Oxj9!n8Te>yn~!O z(PT$y+VJijCO5mD*kH?dt=R@ONt-8Me7jUWOe9&5x_|U=`b$6lE7R}&-tVdIrs?ND z{n_-hpZ#?D`s-g#=Vxbr((9J$naB3e6i!cB;F5jmo}QfeBd)Jsy_sIUd^5e(krQQH43-0 zAK%-fjL7G1FJ5`blW+TbSv=#_j@aT!IogZ5>vGe_Gs#s()VCti{h9(!5a_M2afYr! z|D;a@WQPiOy~?)Rw)P7{^#l4-dPl^oyh1#-^a+%iGLh&uIDim#oLl_Cj%^{0?}@Pu-CDJ8 zl8*iO0(+%zo(03hZ@j3q+pq(EJC0965Vkxxe01VtaHOr{Aew%uE0cQ@3Zf<E%c~$?aq0Lh!|-6r{BRzpS3LZj9W;!li9c& zlE9t~Id{v&9GR9bc@fXH(dWO!(ai>Z)2!dN%`^s#^}#k=6qPD{IKRy&z63u>#29`u zou9A>_H_E@mm0f&`fsNf&%V`(`x}k9#~O3becYgHaFXwDtt!zc&sCs;rG$w)T!rn_ z-wxcAH@vjg0B&en_zEXb{DvFt4|1E}K40Pcz^J#)!<%f5y0cvMS70lDfH8fY3~&=~ z6GmA)=`sAevT2iegrarW25a70exz^m0*XCeEdDLLHH^BmocEt4EIc$CHh48wn>x!! zW+kU&=nE{ogs#hxh8fds&PE&-TIi#W^~zXm4D^CdFJVnnDuRmF^uT6%o7`slstmEV zU55kR3}ZU>nO=MoBNy4Ce{WiLDdOv7lqvz{B3|Sdrc!P6|6_KWGYY&&FOs2fe&o> zNv{h{^LRtZ#q{pox#BF4O`LmkUN|3TE5_z*w9^5s@>_wE$i_#fsywz)Fqgryveo$_ zt8;-Ynh@s(Vd@nTu7mK}!9KTzhh}LDG9xliLF`af2b{m5H|NW?a9^{~AO6KTuk<_B zRP=IsaQ|?6^7zqoba>!7C#QhE`CH?g+ZrFsUq5A}m@hT(l+cIw=hKdOetN5}`DF2n z@}!(x?>Ro@Is`ZD@=Yt9^WWQ<4)*qx_tA9!!BMVPNdEHja^ibij#&gc=f>A_U(;a0 z%QwREgcxO{%4CC5vCL-cE0iPp324^jm;b7hH?j z-My3R54CXQHtI`i@-XKEv!&P$sr;G2LOk#jvO-?3-$i+UB&hI8Gv`dH_w zI30-mMOP3}_#LWZ+Piyeda$?Sr@rpiLj|^30A)-E$5uk)3lEB_nS7I+>A<4HaUig% z->_Y8leUgG`AbSbHJQJJQ9k3NM;6iXZ|L~AFGz2r4th;i?>!7`MXYA0zB!qY`#gU5DuW?Vy!ge7DbIhz70J}5Bb z+Ta2>8jfu@%zlCe8!lZCI4*-nDra70wmgGa^dY7k4BQGH;OHdsn>2J^j8Dy(>qS^!IOd@fUI~@gN~4G zNuGlM<1=NHV&o+&mdh^7^Uj@D9Kx`I{@S2qC(un2eU|0Y-sB~k0#zO@EYk+$0mL2< zUa&UVCjg{5c)_PW<)zDz_EV0vu;hc2FWScjl5^jq+{Pt?>yphuAFGn6`bPr4@!7Ig zEsN;mlT@fbbdj~55X~K2itZ;&5I@|aM#z#(srO_zPY#?PcB@RJ!DTZgRv8tsND)9r z`H1Gch35${@y(JvXxi8udz9l~_V*n2Oizfz9^S7*JR1q?f%!v5mr*#$Kt76NN zhx1B(@bi;M?t9TS-+}r_KJgzLs!!Rb-@}8F{U>)AvCmO|=wtzpT#2LOyO>lDfcP?eEZFGeEe3LyaItIz}|b| z>WwCSOd>DOneg&t7ayg)n9fgme|3GVRrvXt!s+>RcEZPm6$_6oP3G>hIHd`e%7g8D z_xAD_zG!<2_jdREMAyOLp+72ncyJ_qU;gb)hewCgeNCFr6Mr_vZd zs2}P?L0PyCR4oR-27%h8O;sjNVwmJoJyp@LU61YyBm~|^6#J=ScDflvW$4qc+N6Il(rI8}R zi@Y046w5Ww+C|nz2sOw!M(p|!*1E{2jwFvbKgYIGGR7cQyO0248%UlCGV7a0O2~1` z7w&$dq~~ptkBzbmzYy1mQ2Qks#a!{xcirnZ)W>i0i7!DdeBp;LG~s)+XCfUr3d&l`Z|ofF{Jjcms`5kRUYg>aMQ}pR$DV&y>SSE=4rdqF?CG~ zc}1If1B`U~ziAtELc=DFXp;tP(uhXdLccz}NfUNG9j}G^7({~%ax_oNE;`?n#&1rq ztFd3Ag!(2yC{R+tnXv>hD|~gk}jBe3QJ8126~4@FL7*lyo4}2 zg4T6>HMCTRtNiVuTKl6RKcu&X?Xc;?%^^7%IG=uZIeoZfkw@V}&S}~2-}?sZq2aE8 zY}r$VHcI3?(g)gWr9x+ZTyr&Iu7z3F%952ZazNyDKFu3X6i1Kq+}I3MriS2i-V*FZ z9~N_bPAA}6fuZuToPM(vr{8&z=*`==z81hD&7+6+eeTY63SR3+seB`4`zy2e4z_tvy~=av_Pe0@OYy7Qd=HrG6Oo68;9o9bz%_=`8t$(N_jo;*65_IB?&U!Lwd zJ2{=sEV%l-X)#>Sq~VI4A!+%b zSLFt{iMI(Klf90AlNLIk?!gwAmD5%vSN4?1NL7g|P#X9?qafpW`TZdl0`{wd^MU5= z8ocoJw|Ui}xEXe%pk2Xn^mFhC9ue(+^ZW(yiG0w~MRuuz)(brcB0Fd!VKvVqGzpIf za5lH%2UU$JZJlsqH~xetVu2;Nf>6rVGw!Se!b`sw-?Fa;_h3&NpUZIDsAE?2iP*MG zQXq!*z?`Ci_@bg{eJ2R%Tu3GFT!eSakcSl&_jb9I%qLZ_L9DIGZ+)&fVj|$hm4CvGYR!w7a`>!&KijsrlhXNc5Go8 z04HS;3v9y=!ofhQ`&wPle8i>v5!~|vJ!+NQrk*i1|ige2U*%e2N)VZc9TzS zOmqH%#Vd<98Ws2JnPf?{(2ZY$5*Z=lW88Xae9xB-y}f>K&OZV$eri4VVJK7jb!PoV1@tK~dnv zv2F+b6EAjqQrP1}_r>n#_$AD^HrB%oIYOGD66Pa-54LMEb71pCK5 zO_=z`6|W4S!pWCO9Zz_%m{UzF@%Wj$dsql#v5SeHYDs~K-O<5=>8r1PIDP*3i6)8f zrf11q49|rGs>2~!PK-zVVrc+Ks zfX2or4UR)Mgz3NO(z&bsIOBt4X>Y~OOWyTj5qh1!D5yD2AF&_Em5sUI5SN^J^%Eg^ zpodK9$319@sRxgn1nQwqR#bt`%W|Ry<<-GOjJU{8}F#dZM9dJK&;_<|iz&1j%CoT13!P5IL;H4sq8Lx=7}i z@j%qj5ujd?*Uz@4=QMtj6*6G{BhQ~i*;R~H_f_E&fgpuhy2}FS*U9`wU zj*k7aD8-q9b0>Exb|w4a^4o?blrX8QVP zKb?O0i=TQy?DebX8p~fz?=H^deZRg(G402g^EzG zdYxwLZQ34bo4ieE*)ePbs55_y%*XV%!7QK2#0;aYS!M%n;*Idha)d$F@`KKbKBTvS z=|h=Xc2j;EJ!;U{Z#MbFOBnft&EB)(TW5rU*CrWPXIetTr_qa8u;zs+>ntX z9#gLHMw&vZZ!K%yrfeu1wAA35woPwMTj=ZbipK#GT)}NzypXQy+(aAcK2ERfEqou- zz&l-d^EnnStU*tp)IuwI(nbYqzJJ9GX-o%q81&}(@Ej~Yq+I~VgnS2SZEr14`qOy) zoc1v$DZscZ#@tyxx+WV;<6nHI+c%Es*eJOr^gg{VSMx)Q&Zh0~ErQgVM_$Z_2bwmK zFPkIGG6kbv(^qNtFKAon8?rO+3O(r&*8Fv7SksG$Gedwr>k&gQ{7P8y+QdRjk!Hpm z)_x>xj!7K?RXM+Lh6oNGATgv;XB`Sjw|Yt1d+NcMvla}ITG?{mmGzg(-}^?SV9@bG|F@9jB1z9Y`t zS~!;{U>62;L9XP_8(?nT;aljp{5`Of)3fRA@tf)Rhr73@2L~#P-?$?Yq%2#p#fNk-;Zk$7JLl(aN`0x5vhg@`Yqn9&8T~#5Opg%if zB^`o5vbaL+PMtK&cF|`?ha+0+GjE1lN%PTwZ>;Y4$9iN!_ri$<&Gen!PPCr!b{GLR zuo-M(%PfL?nEh0=wjG}>XTEgtxdki(C@EQE0 zT7d!4iv>zTw{59-A&ZMAmJ?4SVPCAw1zCnqXyE8jX1oJp-#ZgJjG_h5ql2z^KBnX# z4_zA8$=K~`0Jhfv(vYyFFm$Azd z5Gi8LQG5!8U&%xXCUi>aK;<&IZK*SKkP}j(@iFCv=3FQkN!wE0O4k@=5)E7NCVkdE zlGKL!;Q*fg#y>WYbw0*Kfu{|Dc4y&-$%7B>*l}J7t&87Gt|$XOpv%O=eWDg@Xn(4T zm>CTodhvkzCO;eyfN>&-t}`^GRF2?*D}T2$M$r<{7oZWN9u(*=?&G4ffCQIcSS|H|MJVPHDsaa9(NAivz{k0mzVB)ckk>-nD;k3bMaH}2y&OyyGs_m==VF* zmtX#9`r!|M6rym&PopPpzEcscvI4Oq*keJR7e z-MiDl!Jc0~@c7}Q>A}Oteo|{!K2wi->c~Sd3QI9T)RvV zYf=b3Pros#ti>V+#veIDp!BYHwKMHoZNW}Ki}je0zLEaw0NoAQd`eyPnYN_qW9%tF z`XRbb3L?{E2DtOWZ(@b`Oo*=c9c0UHXl)yW9E)yV?DtsWK2!SHCrAfxAIv3|AH86P zU1adfHx8J9vGRm6Ss$NC3s>wh51G=(o^MzHN5=frQuJeE^hHS8!}d1HILIYkzUt=- zG|#o|C8Vt~l9rWL_93Jo`MgkrdR>6g~A#!^@2 zfO{8CY$$e#vf_d*%|3GzkIqbwB9z@ zlSsg1_u4q^(x^-qA>Bh~P>ESKu5qJ6{@|ib9Y#V=jdONQxBIi!f9U-l) zdr{_+99#!p>$i<{8athqUC(h+ucnElZCMwHHsb=utIpei%~=NfNjnU3*0XNOIJCWn z(i?)gh;Gt=ftKV_E|)FTfnK5VzRH6(`m=!f)HOo#xi4zBr4b}K*j!7j#(PCZw*|pc z&TT=PEn%szL_o)DzzF3k!_h-}e{#4<7y7eB~ zJL$dC+*LlJY7;pZ#g@DKn8$2Wf`oy_`5515@^v8FP=GQ%+b#L z0&VvSSgzsI4&UCQHxqV*SNJX_zA{giL4GTIfXmQ=*_3PKuv*#}~ zpMB|1GRTsBqOV`7p7^vw>bWeq{0tK0ntEnm!ynhN`Ly*d>vQdZ>xoB4dCLs*V-}B2 zPS2;~lLQvOxR!CqQ(Gz%uPN-$F8KUjnfGykn?lKfR}j8^du;tPUd8CA*gm*!C>slV z$Kvz09TpbPls>;WbKZP5f}4}2;I^^H+FV{g!W_2Z}7s`-};k3 z`ALQZK|7+DN`vf(BadTv7H}}?2~cHa0bzmCaF~{P~NTz%bGL%k_Ol&w~-PoPj1zKx#WGx#5xf9;x2L0IE-$1#jk^dLk;FMw1-@H+(qEQ z)Y&9o@_>en=&=`9e8F2k1bguI6EG#`9Bj*mtPf4Oh){kJ6%(I*J9l|Cx)qN)v6!Qq*+*dr=U(#Eu* zJGzNYiJbei1&HEh^Qlk3?dZ1QVt3i|w)n)e4{bx>ZXl}uT{v{f4aF z&qZUZ8*cGPS&u08ZFwg1!CCpHMD_>CxI75Zk9Ze06Gj$_?oRuf6yH;t_ebBltqCLT zQ2U$AXu^YA%7MkOiA6C@$Rz)}Km5`3#TQ>$hDEN|nzSNJf8kY!uU@|PomB7m;4h1e zAA!`7a=3eIx_@xsg|36W!|CXNICnC!Aj0BS?rP#AtL$s|C4DKoh)R1uce`i8?Y^bJ zol`7~b@@_1oDfjo(w96vpK83typR4XS|AfaNaW-8(9it@Ju&9vi|xjrj46^)g8sv? zAwILvnLLq?|Ai|Lg8Ppry1gL9f|ts|B)k0Y^3pTNLmT1APXgwH+ZF-3Xy8(mh{|tz z{BaK}9RqUCBXx#NvNGLz@mYz)(D1>u*m7PiN80w<7Nx_F*mIfq!Bd=n<>UO+u3qSa zO&b>vn-CSF@3F{2HOU6I9|}lR-uOU$VFR7p>gULJSuBGNu`QRJVuSf+^=1v$a}Mrj z7WKwVHbo$%{$YFgDCoL2Ex}!^;-u5py8TC9r}1{|Ut$!Fh~m;E%xQqg#==e<#LbhM zTF1q=pZ*C7pXH=nB`k4qTX4n$ZD;P^bquh*mJ{9kqJAl-^sHDi#Irn7sUz$F>GR|j z8wT^W5yP>9O-gB|6BUoY_gkf~Q@wEJIb>sqo-E1EKmBL_>@Vn5hrR6pxCF-VF{P(= zIg!1XE>7P}ubzK9ee?Ctr|-V|+TR3w@#3k!3&zu8A2i-0pPN!*fgjeWFQdOnh^xPG zu8xamwh5o2-}t9M>s%+l zjSrsjae-}eBh36tZ^EcM%Wi~C_?XO0Bd+ueCd03^U_K^pgdS7Yv;`LWI**0E*4d=r z#B<(T=>w1+#)cXpua)1VjdF~)o3zdHH;lBVUzZ;71kzZ(TDOF&@@tysB}01VQ*s|j z7y6h-&oMep09?!94$Mt5KXG*wz2D5?`4pjaW;;z2Bw2K)2f2@>LmJYGmGw%7oMwEJ zx1`+{W}eDfc3P%mLdr_oWP>=K*ZH?0pY+wfF{TqtUefxF=@DPkw$t0u>-gK~9l~Fy zV{08uUD+{dNH1aWXM>*Fze4Zeea*oJw#saVhBbX0x5}MuFw2Z#v2`7c@=Ar~?Nzwm z%5M&QUWhLp1oBQl_F|n=YEH#Bs{CCrhYJUu4*PJan1vVNw+TF5FFj66?y4R$t}NwE znMFaMfW?@6<7vm&NxWF0O3yWrYD@k2`#K48bDvYi1~yx+Vb-hsfMuKs`1+aTI6vcN zTNu6}w?bP)hCHEMyn8pDoL%_sFx;HY6HMH2oY(NhcRq{Ypt|AO8BaR-Nj04l?%m6c zuD07jlTK~PJ6r_^|ojcXFnFW>VN8{a%uZM^ILj8_+pU#p?xWt%gVOVKSOPG93a}^nfk2b)HxCNJH7w zykdVyj`G|5*hXs@dB$&$1=5b!!^j1{DevzMGPUxz!VF3*J$A(@XpM#UoA7V65PO97 zW6f_^J@J)FAI0bd+TjMWDZ-s>h9`=|rYfnl(c%kM?IpbL>_^vTtg@tY@dYBx=#)@F zBN|MEGL(c;K05_ZIt&Kp0pX<#h3jWoa~oUIgh(egM|RsrkrzFa*o4>K1Or;KB&3i7 zLoOVegAqj@;3$J6J@Jmf|!J-E?QC%0r_*Oo#E#J}0#b05W6O=7<;#WUKlE;5VLr^?loU{VQQ(|-g zF5ZK2Fm^Qzb>%wIKe~}~Ul0Wx;PB$MQT|{7d#fl17pn+-uyWY|WMUuwtVupYM+a{? zLaUc+!R>g;oN^J$8w5+qb`(gZO!`aSc~m>17l7%1#X6XhO_Gv@(V&F#XieIbg@GK@ zP)g3o^`aMeyV_4#@lTs6*(8&dyY;I66cAB&u;1=qBH&;1YE#17kL6XjgzTrONBf~X$sQY=Y|tFZFHfYwblc+_^5t_Dd=PHGh08Vz=b3EZ zVWdjF_^A5#VvlqvlLSn6XG9)<&C?Itq!ssAIjmaMG~Shnt5Lfee|BjOD=*iSANH5&hH-Dzq4Y z2I47a_{a(^P6vL(?YGN^py`oM-bpVU0SJnPE)cu??2nkZ+fp%w-Qe-Lpz?9PB_F+{ zVl$YbMTWHb6~}|{atwiz`e8#nhKAIKEXZ;DN53ahu!|NRH5w|P16)F6vs=O=Hbm(RbRzWeqU)3fh>IlcJq7t?dar#dG1?p}@m z+;o%iPQl}_epgNZ>M*+e3E(m)WE@zBZ7|X|_1v1pXM4p0a)o{jM!OvvZsKi&n`Ayk ze-m2gTD|61auaUSZF^z|+DHek@&emv4I^*l&oq9fU(G)^g$BUJeX3!UZy0G! z-=t+qHp+B;t;447m>%(kw!Iz+KAMa)muj1h?RjY9G_h$_cZ~x+6j5)Y&G{A2<7(rr z=VZ&v2V3U?0=@cSqe%?=Q#&A_9_Q*5&uIXdCX`|e1STM?k7uclp zThVJQAq0q2d|hgO#ZzEs!WCbh>fBg(Er{KE&l#b6qq@0fWIo5TA%m|Q7}5Eu=3M(a zzu(=>8(!GZRJoo(U{MKj{6w!8d6w5#1I(N5SPJ>gsvv0}HW=ie&qRn`%Dx8Ug{6%D zc*}JxO2su4zN>Y@(^p>1;%PPZL-crxinq^PPG@K5UR+^OjcvLqqr1&l8m0Wh$6iZ|If zV&te)#>(+n(!BYJFM@4Trj*ONhFgBi&%=Ye)BdjNlYA9oMSwlq?eShb=dl?Fz)dZh zWBwa55IbII+vEZZA3p-y`3nsoy`~7LGs|7oU%?hzBaploC{Gq85ezQOFOnGTmW^qw_M3P$^c#}ru(TZGC=@9 z*7Aw{#0V%k5No5z>HOolpB{21F=Jh&lMOgB&V8|6x&|^a9zV)zaa%@o=U@3KqMW`k zY5^{IgrD7BR5QZ&VC+eei<7(LT)-8cw&2_x+gS<|(#O+%EtU$`8RrF3&Yvm@wKURE|j zCXo^NLbia&Z3%9ILis`tIf!$Rmc3+Yh;0#sq|Z=i?GvR^UX=&N+<)}zr>SU92*b}+;o!KYS*og|Ah`((xnV{d{XIHHk zU-a|SY2<*v3aq~HssZx!s}GrEX`;rf0r&S0rh@~%jdfUeiS3zprzUi?)7`uGrpJ#z zn+^|;JlT5w{N?n`*WXSro;~;7MK7N}n@-=ptqD>)yB+YMfl`uo-AR{^(4K3eMj6=e zxJ$~DPfc`*dx5F<`Rt1dwWz~B31E-9rJiD68@Z)g3nHNEvw$UAR4~3%SJI%LMT&M; zK6ET>D)Orm6_^m)9~Rf4;fsR(7Tx0vYS79*%GC={`a8DIGVFY;M_P1bp^5Lsb?w70 zmxB8f`PhGGZ8P@5kFAVTsW&lPAFhM4t-t-U9mzRW{Ny4HUlcmUj^>3j@DPMH~BGym=fpzl4yB zC8LCS|HV*IT_?garU`Sv7P5#?u4d7fk{{{DN%+`1=)}ByMyhbjhM~|XR*1DNmL!dk zoAoMX1gy-29&jErWN*n2sBH~Ct=Hbzpox@KItp`rSZ9=O+hM12L@^uP-cuvZ#&SY( zj1ZSJn=N;p5^@z2aT z{)>3kAvpuoSz~Kx`T}?#h-^}7uXh*I+3_oX6YS}C-%QWHdpdom`001QoX$_*=wzE$ z;9ku8Ujp@3i4mx#LW3cb)K=JZ`y+6Zsq0|&bpx8-ExFZp$v6}VXxgs|pQ1bGyG3^7 zbr`FXF@9Usw(M3Yo+yt^o8xfo(d3n|Oo~ZsLPo zrB~X=v7$7;3f1YEUW^<%i@s<(tmOkEZIcIF;a!tIWb^qe&OGA!e74cH(Hlk@WATzU z*Z3&cFs2*dPFwTWyaXS;Hfa1>wvaijXpR=Wq!oJJB=C4G+;zzW$Mooew7w`@qcYQFv@Q5RK zV^PWbCy~~j>8oIt0Aw9Dg20AGF+#4la=y_iQi zC>wdwZ~P>i`x5fhJD;|wYedLV7SY|t!fB^m+sL&BY> zUmL`)$_qXLy}*ZQUv-g%FLZGwGC-eikK<`W%Wcw3Et+HgV>(#jSM`DP`#^jMT(xr* zCwP8C80l`a1W_skLfe21+NKQ2k=8idwd7jPFeJyaZiB7972L$zgs~pC!B$(}!~RD> zrp7!*)9%qqXJiZIY5+z&b(hrKp?@Wam8EYiBWz%u$E|wR;UE8>bV5If)+Rr8m=r44 zB(x(hLIF^McG9pE3rQ+lu~Jc0P;X7p?yRVGdD+$$LIYxKf>t^R9+!#4N_Rzi5HUUJ z6uC7EGjE~w#i2?;P81PC%P-IxMOUIb$0)g}6}iPc0~rHcSc+@l?!k^uPuWO&{1n+` z>%26uQRY5yX1tSp4eEZO5gwcERFR#g4k)I@D~k|MM+PS(fV9&{v&8TFkb5m^~vGpvUGFY~-?l+c^V`$?R8M0`?WW^H# z^UYN#ZQB&4zuUx&_~VW$yeAp1e;QOcZI}s0XiOBm0AUmEta=Sl@kDUB)-Zsg^GyN`;DkdY)W0!>#_9>q9BJA(+ z;n<_Z3ipp5OkaNa)pU4t-?muTef{Fq^z`Yo>G|{L)3@JzH@$lKVmdwHTVCh(Yk~Ov zso)Z*9K816@*S@LI9Ho#g0KCHg=L-wV^YgP9e1&Lzoc%fJk&pRM7z=2(24OVbaF`@ zrGJEIpN00t{UnHO!1ZJxa-iPmbJSfXhaTTNqb4XVe&nQpU$hfCPKWM(Te|Sl4>iG6 zpY`}JARj*gMm`F@Yua)Z-2T~P>^-F7*)OLh<2)EEl27uAZ2N%!!m#4}+h1&3$9cgQ z4gavAK4p5930~W`CF_9~4SYibH{8PHx81B@q;i62$#!P2wpPe1H%!) zwvmdA@eZ;?Il9SHsgY@zv8za7Y-201P}#bS-POQ7rWIFovT_PPiqpp<63w?yII2G_ z6DI%YSl-YSjEAxv!rUgZ)H4ZTWxOo|>9K3=wGW9qP&&YM-Sr`b<^(fQwnJ$;$o00V zwU}%UFw3kn9O9-eFzb-ntQTt1fh+Z)O;cvr;`2ZK3;xE}ZxVRj;pqvlL;PlX{`BY5 z%V)owzWe&8(~GBHPZy_e{SonVjp>Y=K5n^A(NxU-S@lD`8#B12J)A+XP9c2ku;3l46)E&deU{iLR z&L)4GOhfZ;>Ow8EvNOM+tOp$gsc2`+4BU4k{kV>c|$4Xus(SS|)F}+C>HmAXx?qtzBd@Q|L&NZ(%D_ZEQ z`Eb!2#<~f*=oVqnPhEQ6sSv8<{4f0uD|_oU9PKxr^nyFB3>F@E+ks|M;iHUV$#l6o zTus}!LiGdT9Xu5`kNKqX8-3QlYAxxCXZ~iIfIW|;MeD4YgCeJ&ErJgrpn1fKKGY*K zu1YWTvR(R)6<@@1wex?0vD4~tnypg6`i z0_51pft(PQBW+aWj!RrP^|mFya4R%)dXq057hoOO2Cni5&c}6jHOzJN>jvimTKJ03 zcGJ&}6WsqD@R$2tRlgtlm5Arl^iF|=FxR`rh1hJM0gjLYRb z5=dj$i%z|;wY%%ZJKj*!i#0sR#gkutE#HS+`{VrR0O-Bdt^IAa`*T~mb3HT>+A?1er&_=o}obf6}7PY!;sx6nv@~Ef`EKc#w zt^vo%dr@kKEnCn zJLoDO5AQr(|XxQTbX0p?T zIEn~EFZ7hIX>HqhhiLgnF7CLf4SLW(&G4YXVu1#J4$5{!H0wxCX?G%%yOWBp*rKHA za3*6X`H}Y177~I50sWpdk2^JKX9vWPbs_;S%!!sXC4gN89|Hhq&%qyh?o#nYf?xTP ztjj_Y*5@$WWpugttIo><)0_>ml%)xUS>z}r^Q9h;OiR^0BA zr@Z*&J8D#i)KZr#wv1IQE;L&SA7Nr1J10ihE#zv_L`@==6J)Z%geY?KZ_BIBdI8WI z|E&n2^c5t$OuUqfJDJL$yo*hgve^zYiiD3ck;86k5Idd#iNmX>gQMxm8dK3c0ZlhRB!mDWVk@5ZKtDuAD? z+R+3`BwZSpEfc1*zjje#V{bCoW ze4%9%Fbzs*&X=@9tQk=mwJm=1TE=+olO$&_FO)>F%du#&OQ5`f+rvAB&jUYL%^d}vMom&c10>p9|k&K+f#bk2O|6z^^LDTFG!E%Wcy+|V-f7d zvwREe={M8Yzx?U+;`!6*^6bRCcNgb6Rxs93AGtvz<3#V^3e_*bQ-kY}x+Ew`mHryw zG0cXxz?{!^{x<5hwzfdqZXGT%j4<-9gH0PF+{C*HM!oB*ca+(Ln|PbBDSMON$7DuY z%iJW}q08v~cSClR8{t#wW4dV#o4k+lM`#+pcOM?xYSu9k-NjA<^uS0TVWe;Jx6?QC zK`xvXy>L^TRw1;j^o6%h1Dmul9om}Su$CFqndgMwyv(V_5c*Y`5LLS>9vd3x(k>(x zosLJnB~4x&doqXHw z7y8IgSa?esxS1Bbr~^G=p>NnJUi#LWXFlM%v-TCfLmjTcHvyX4HAw^bHra;R?kX(w zQHDNGU+MH1$Y~p$a1(5k|5d_VaVfEA@^tQhqBVPl$Sv~30kAxAL(sXrgU)@me{#c- zPJ|`TwXohoS?ZIE+N&hdE-;9ZlPe`)u5u@_?$u)*BNPitLXD*eH)JUlwgn`k(n_2SrjzSVW< zZ)Dlh?K`HuIX?BG7in)58ac(;hd}?%s7> z;g6rr;`)uoQGCfO4^JU?Rl#|7;Jp~rG0O}sU2!6Gp^svEV z+%8X))%6bQ0=wkN;#Y2Xj9)Co`I?P=q8&-gR|V|je|eStLbj-AU)#Vp`UX7Fxqjkn zF>X6kODAQaEp~Y-O+KZVsR!RYEdu_e6;tLV#9w@Ce;i{QKJBdhX)k3p?W%fM_&VCV zJMA!T*14KXfi3;)V*$J|1~zGIjq~5+t>T1D9x&5zvS2I!8rnh)m@*I}yD8Q51+J#O zEquEy+vaS_%rKB?_fLUswyw3m0b@O00kLK~L>-7e(f-HaqjtoP%*~+}y?hO`Y-Z~Y ze*-Kwt_>gcv4S>P`1(74CktOp`X~TDqqS4BGfCX9P|}aBMLnnxhb}Bz5kHt_lBx5> z6Vuok%`nc-7c_!}Z@CY?*iYKR6=Mg~Hs^5x9-WXa1bj9FYIJ0@s3zk>Qur1%06alzfAd}#adL=9M%_Ev;JCy6EJ3|w0>5Id$@ z1YUy0MNR#aW9qf(mNlOUPfAA{r>gCQA{80gu{|#ISG^+NPf9?uLV?RvE+#+PDs9`g z>0eCRz~NB|9E81?Abakc)6d!K ze*hd?I3%dZHp&is$j(Q0JXvDa1YPyvKKo8Ni-e9Bkp+GwfXbT%EADRMZmUBF7ND5K z@z_5fmE{gBFFEWYCnp{4do{0Y7;RAo* z_1^wHPsW*i9vtpXM@RdTxj%jN#plx(Uwtn6f#mk52clu?=>B~#!coH@$kcabl zh<@9Z_i3k;6HA_S;)7&Ehz;xT!!Bv(gJbFU4#lUA$j5h%QOA9IhUf@AXu=&QVZ739m*RULfT81Al@4lT+`OR?2k$MLjrx#I+cr^U_^1E$e`yO} zo4`1IF`XR0nO?tmI=y`M&Gh`+pH1KV{NE}4-E?;PR=i`bFz94F9|w0m@h)Hbw{3_- z=X9$2XW@kKfa!fTt?@0g*V$1w+bEjM0tispfD!tC%x8$3yRJLb&WExtwq0=K> z*cBQu(iVEBM}BicgOI2g1>q&$7OJ2#T;W&VvyDodW%;E|JA5BV4*#J-4IBk7+u*E9 z>wdOb{tlb4Va)_yi+AfoJ^iJ5)-7I*_~Bi?9jI?8$9P;89uX%j$MXy7yL$Ek>E7t&B9`WGkb%s0suGj0gZ@s|B(_CB|;L{1Oj(HmF zaymUf_xQzAU!Ofbnm&JYB)j)~b1moOEa z&iRfP-|#x~x4X{IFRG3%Qx^pMaX$DYkA1=v@U;O#wF&3#)Qzv5NQ~ngIM;aaJ=YrY zEqLf$D@q=!k!o}D@bS@?meOtp3<~Hcj+-Mo^1k*#o6GLr&h6>G>VN;9eDQ^Z923YO zHWN2AejUx4%~NFBHL?~M>|ZYzxQPaUJ5;*CG6ONk9tfL~B|AWDF7!l=FS0AV0^WXp3Klul@{^39Ve`F66 z&1_OeAcUpn^`08r8Mbr6tesiJ<@7*DG_swglDZ1vJKJuNe^O=5*33o zCGwyooS2h%Pm^Z60AESjwwMJ_oloZ}oh+`1W1BE2A2fa%1kH%Nc}nIEX6!iQS!2;n z+=^fgEotr|B0z^7iMt=Ln>3Oc@PhlmDTW7L4aVT`-SGPN;+H=HDS8er)f#bLvdEJK z`dN5lQ1;;OOl3o9?g#PRvv!9?iST0+!8*YEF=S}yBAZhB9l3QN;fTp(f&<9qg$_PC z@JPV+d|<)9I2GIE5vtv$Eb#o{cOBFyqisqGIcF^$5HGGlQ`#oULjY~NxJcT$C1xlax%w!=G zH|+WS$d$$te$i*rhUk|a{e1TevT7S-y~w08n6AJ@yzCBef%uCycmB|Z8T3*&mXe+^ z<%bVUmSoJM6AJW6%UEIY+Y?IZ*qqo*DD9(sa+$@atdxyBlW)v;f2;`!_Lzv>Q<_QM zyZ3xl_SBQD3-$d=O}?bIGavSPd#zF)C8Tf zr2gM4KOU>+)dNiU(pI~>J6;4kJ3sTI{~4`RPWiUOxZp7+KC`cQg04v=G?&O5?c3Ci z>WlFr`w%%Q4^SEHZ)QnMtkCt>##_s~kD8u3my{Qz?=Z1exqY{m0)9{jJqZqvR~qod z8vQ2qjX%_{dmq{0hh%A6w@I}h?RaPBp4*LfrAS`D5=Q$$@G-3XPrKuAcquOv_DpWw z{w66wo!BDfvADrhWP|w!-#pV5YvXK%Uc-J0|^isxI2R{LWz`y$VWioMh_tAMnk#-psG4` zvd_q9cN-D<{gjb2 z@#w(nQ-gCN4z%xB)3>UN7!JWaprk`g@O&Nh_*AZ-h>eP+4VE$jw2?KO+IN>fGemUz z%rb$+{o@JtlxJq>=*EBV*I;ftZwS*!*rRpoh{?hmpcyeYO&vECX&=Exxp4?--$IsB z$DFJra%113?8-vziQS)7dlb)O#k^Pq(l_z9fN?hOSSnF9=LQ(;3iwXh(EMv&WVSs{ z!5qX6`3-Qr4{reX`)>Uj7I%g|w+FyOdkiUmcW-aH_h5f|_uxQZ{12!7gNM_TPk%A} z;`3i?E_F1$eD!*I`SR6tc5&+O@_dh{jeP7W;ln@R9zFUX!7ber?9}Jw&97hCyyUZA3Z+S+?j>0HH4wS-CI46JFdeU_7Y% ztb-5wFoSsI#Vo^#XU$SqXeS-+>q<`(?&G~T z)29y)r^m;l?-8T46^A@ZmAebMR|43+pz$ms1>nJ*^^`Fdjb5`&+c4{IS(gJ4!wBng z#vB-Vo0cUTnDGT;ty#JPT90IZX3>TkjfEp^U0?&Jts5WW9)a&r=^-8SgY8W)meH{0 zwa*dOZMgx&N`KdQS;Mw6e+=wuhxdhU+s!(07R&i_H`prZ4%l8-yskapoBsQM@qf7Y z;Gg{IpZ&IP(8FX+heL)ab7N5K8Z@-8H6bMTViSIqqXsyKKNFQ#iq9@Dd3 zliVzLX0UTk+^FKxuY!a2!6=>@*B(m_g(Vus?R0b*+EV)oPM4scC!g4W_zl+FbYA4P zFdj+UDYtJ?`UHc=P3XMtEwA5`jG)oz3>gGQoDQLtAem4&PQ=YK*1a=(rw6@f{oL>tixT(ZP^@D;h;lvf!!y zmap}->-r`n@APp*88f};g`V0F6x!E68^sNog*}&SsCEOySI9!j;W9S%5Z^ zw7xW?9;L6GN8i2ZMS0X)WpE6zkb^31!K8@S2RwRs;#Utm)`X3xyFUHolj)OBo=hKo z^ik5|$CmS?7_SE4k6ii17QcXELF?#Hg(d^zlHg(jIOq=R(|u9P_EabvT|t0k?Jfr^U6?zWN7goW`Hx@Pe7z zBwrNh&-5YfM4x-{P=R}qPB^ykdZF&VzNENsaVeQ&gjTX1xEkKqC*{OIeWHUAy&fHp zRdOcO&Z#e<<~-JZp`C=sCUlRn(CAj~R5nW5ZP3w0hxjx8Vw1Aj!c$gqNh1@_;%K3u z@=+=M>@1thikfzOOqq^ucyI&Dxh2Uer5geo2eva2o)^flcRMV)#;qOj_$VBUXw@(= zR@%f2ASh@#06vFhL6C))x-7iLmjunY)_$gYvq$?dV!62<@Md0*Iqc4w>wMO2q3Z=7 zok){|O2OrTM>02rQE8GpxYQFY%ti0IZ!vAtFyaHa{IbCJY@;4tnJlppQ%WTE@JA@x zz8ERRDLPX2L#)Nm^|o}h`}_99*W4DBHx4X#us2t{4)N9W`sGvqAJ{iv{mt~v*MB>` z{NelQCI1`w`jyWYoLgvRzhc%9eTl8rFxj5fP$;m&$nbXqprujvs+{W1NNx;Je2+XAC}mmZwkbbz(aHoXnm zmileTSFlaC#t<7dG)W!RG_M~o$z zTy(8eeH2)Hkvx~P>8AfN%{*-`4_~fVk54<;!3#fQvS^FTcP2QYZQgvVEjE?5mOs2cdj;rOSIN4iNX^`$b-puy0Do64JYy;MBlvF0 z6I1+kg1-w(#*JW^mzl|yL0Xh@ZC8- zf_-&*KD|6WmCZZfW8j_w_wg>@u(A*;n8&O&6&!)^t}z9a^m|c zHK0v7|NES;#C?au!@cRFM<;nzqT1DqScm(5n+^2I3ICOT=%>maD?K_<`|ss-iu@3k zdoA<%Q+w_k>?;oHK;8KfKL2yh(`lDidGhU&J`;~0f1u-dglF-Qdx2?lHuLDSaNRfg ze$EezW6z}xzJIVwU5n=aOrG-M`*`1r;C@Ekui!pK`N4PUkhmqVk1-{J06Mx$iT=QqE=?VHHFU`=@~-m?@Mw?<#P`8#MflyRrCH_8Ww^Z1-YgDo1@m z;w(sg)gEFo$lVUKP71UvAgszOCz0i2-rN>Y#Lze=8BVSSPKfa9mj`x$Zr*zRX!A|!ibG<$%CXEorGq0p+m80B*tARiZRC?b zC+b}MBV+4DxxIV3DEQY6xT`qq2w(6(Q~)l$G%?FN8-8ettZc}oS=*7*hJ8-#^F1Q58vFA-Q42P zO6oOHB$4VbKLrCW-)Pd#$onar*zuuEG*X^rP$r^Fm|TpR1i+@9eIp;=)=R$$@mPVz z2RqnawD6!3A%@G);4n*dM&=7Ya%AFr%rSr<%5T@1cFUrO;-dh3qVKk@1qtioE52P8 zp!R2cc)VZ=3m@dBuwlsu1C`@RN*fc7aH;v%J!Yq*I4Zgdqs>vr2MgDkj8;sPuedy+ zP=lGVj}2C7QPh= z?Z@%t1swGUWxCo*?iANiMDFtd#~d}MEYWU%e5nC?Xir~LpVY~Gm6OFZ?1+tca9ibI<+#yJ9UQaug*Q($IWdLCCcdOtdWn}5 z8eiJ%8y+#TMPJD5D}6wY!}zrsJ423R>x2=o9Ur){qn^&aC#Nl&E?x=(n{zd1G`g>y zWdu0QJnxlKAESmYA+iXNmx8i664-@1i4m;xhW4}YI;Zs5X#=%n!7IAr$qxi$1_eX( z1Dy-ZPNWcE_LPtDrh&?oSFC)Dwq8e~y)$-X%Dd6c$c`*~oCtU5qB|s@e8*Mg*}-sD zqQVQcH&pA+=zHRy?Xx4{|WZ(SHGXW`TC3L`Sb6m=g*!_XRluB+*s!eS@=gH%DW$O zUF;4ifHi^*wj?q+T8^0&+$0mU?RcKMDQP!fpWX+y`idZV!8Q2+YuPrPHH^BW?Hb^Y z^4mP$=5K^qH^lW+F!~$uHMDG(ykXSarF)yaVbojeu4S_ny`o3?2qSN;GvdHC`I@)l zLvP4SIP=)d&v>5aC8aaMY*VRW8&BNgfw%8Pr}0ic{*CJ-Ar)IFpLIf%CxP&$M?amS z0&a9eM&j@#*EA$@7dzT5sd=4`d|SSNpV6|L+%zIegdUKeu^pJ_|`Kd|lN7i0y|R{o(I?@`+vF>q>d5 z2V=-5Klt1~kX89e(UCBpY!FX_VI4`L1J@rsA;vc}Jy=upshp@Xi zzwkYtgMI#g{Ln(a`Lh_se`WEMl^2i1yLj_yB_OmMw4>9iWfr ztsv2lDf@lkgZr!G0j+d*|Fh*zcpqQ2@b%}v_4+x6z8ix~2OkCT5x<9l_wx}(#sLSe z1F`5n-~g{cP`~`E-@>gf*Y+;omdlS##r45~t(67#7oKh5YnPbNi(e+U3`F=|h%r~E zCd*SNYucv$D1~dBa;yczPg{XoP&u(8qAYG^n`Jv2MK#Rq!j{RZCZ2Tnq( zAs5O9PJoFB9!`}ZZv!eXUmV7b-vYY8O<{Oqb`$Z@d{O z9~&?}ER^ch?*Gwo8_AdbT9^wyH`S?&`$(3)AAL@mCP?of zID(-zmQGKiu#P`)u5jR;QC^9Jd(7$skJn2YRG)~cQ~EJH0^#WwCIG{0+}wTAlfG}@ zqAQ0!Hr-B3T|C~&)fV`n9Q@F>j>iiQ(W78tw##HdwEZE6k9*NlB}9BNd9tm1`bNHJ zCMEPgzA!@{1ikpG$qS1bIFT)57T&#kj9bZL;xb5pqMB*yfZU*1QzxQ|PWqOd5B!vo zNd}WZ(G_7pY;+t0x-q%EEk9Ox6s4_hnqQ2%; z(lO!VRsL9n^y@NRhxGG17OI+0$utU&>oZBGJlBC=9v%9f;MB$ASUxj0QW5*W4%cwZ z2gDGHkGFIL#~M6=TzJAsJiNM*_Dt=Q0&s|)O*wU?-c`0*M)hUETa#DUo&Jta+Jc2V z)t@$?EaG5BDnDM#qRn)EpyHh0q@eO>PZs)mK`-Tru6K*dN5)}NK!c9d;v_`+N6 z^AL98(#o#43y3bh=eEEHhz-M!AoBPveUJj`YYNqh)#oJpMvlO2L&^Z5Jdjk<lpQM;+$FWzsty3YmT=N7r(av?Q_8`$;;#iN;7;f}kVon_HTakz;Kl(OE zG8;M!Vx|nop^dTUQtUgpKjnkt$GXNTONhZr_SZYEG4Rl^9{y}B1;&*;xzBAIoo+vP zT_z^x*hkz8yVf2Q_xJffzS0gigWG}~?O|hH<#IkjbUHgdb-&WCdl+ogV1ag(>v6}t0MvHN>oDuC zs_9lNVYaeU6VZ<9+XPXQdW$eea4Yv6k@filaF}1AIXt`B)fSY7%7$czUnkN3thhbW^WSqJ2t7}5Zy`kqE z|0FCL4^7mW7vRh43z%2_Dw)0Fv2ihPoIDVGNyQd4J<9E-X%j2DVCGd?+H|vSk+nWN z^cFr4KJraI&~^wtUn!mF4aph#lB`mFvYE!%wx?0Q=T0MUod985WplEZ(kqI~Sy1F>koa)MR7fYq*@8Z56Qjn8_{gC)>W<@|b zUtuxsr|$6-e=4Q*wm^&U3Cb(?_^&EnmB)8AFSlf4KpFWvB`|OkHgeSlx<6Z=BreRTtdw%@zmxZj8W5uyYTU<$Je|q>R zPkSBgJ(%|Q`Kt&P`S!d3_V6K#UkB4s{V5W-MeG+_oMh56S{ql>39J8mU;WfCu$r2zZd!vC|Q>;97$nrsDYIaFe}Zs+kp zUtxoe^)}(Q@_@VO;P_5@1H7;PZScYURcg4q|Fz|HcpqQ$6JP0O40Cd~3w5xEoO=7M zZ)%kDKKg`PgPS(CK%w+%>+jNigP1KRtD?*f!#7T3z|9a2TWk1+kT4wCH@X%HICyhV z^eF*$mt=5^(P-bjMO#>-<_a;Rz0}E%{h$M{<;y;tNbtbPt_asih|8zVLUt(tH)T0d z0$vD0mlKpviiKMmo3v?D#2If{U;rZbUb|=@QSKAB@O)erI$R*Rpx1eQhFG!*s@y&) zv-JhTO-EfRPjxUCwrc-rH*oKaDA)O<2&`gr!sjopRqx8uP(2qOa8CR?*`{r zUx|^rB6ry;lX#fu(T_aI#Y7pk{4z{_DO+WvUTG)VxBJEnp-|=!i)^rPf3vwQ(hhE4 zj%9pMHig-Sc+zi-K}^tP!siKkO;SBM#EEXb$>C3Dcam(W*&N#=NpVB@1wjGN91 zK$1V~LIV z&q**;!-Q;`l^8(akXtP9&ahclfVPENsm?e}gKu{aJo`mI^`H>SF^&ob=0&F6fD>EV zlg&`Lb!Oj!_D9Zm$8R{5df$+8X*KxW9(G%%i&Yrxt<}dLfI+weh|(we>`D%gV#88y z%*?_fsEnAb)x7pd?*JJGVV?j?lFxjJRuMUIL*^esYS4S zeQt0W)*e8VK7U^qzUF57k>IiFYY6`*c{;s*`F#4GMX)dbR{59H4@%E}_;z}8!RrwD zuK{kPaBk#W$Y5ATLQGKMHvY&PW$c}xTV_sR)VEH!1Fvig7JkwuZ_#c1y3TeUAqj&y)8HP1 z$~_NaYq{CG>FYd`0&wOot&?P4PDfBB6JC0YKG)|>Uigdd=wqb)DW2)Urqh~7{ddV` znr+Q9zVJ)rb_B@Q?Qoqgoa^<54BM6mA9=Z?ww#2m(#+HOUnx3k-Gx@B{%yz>f_<~gcW|E+afV6cFi+B@B`pW8zz|@>55Oj*t8w|wf-WD zzW3(gd(ks@$!kN&-#ZFVie1wiK87?xlg`<#68?i~cN3J(W*NeFY^uFC8*WX&Hr@gq zSLfGZyWL&Emhzh+mvS1qJmyjSNc7_J+)vbBUYv>MDX{!klw;H8|1RS@rRe^?8HYnE znZKta7xee({(cbM04%d%ajfguL7&Bvvvb9BaZxcyL5h4ox4QhhZ1Fq}RTe!$87!Fj zwSSr$?j7Vms(2y_AKVK%I?P`w@an{TAJ^=V|H!&HpRTUnPFJeu`NgGd^i5T^htlOf zAon#s{q)o6>G$7F|F8e&|6}^@yKkq*j~-5c^v8eX+)ruAH}^q~4~~4#gtldx`j)>P zQ9OB)YhN|U>lS%J?ds|(KcE*ki*4K&$f6SQ<-SYqS@}MU_{dp!f<8LPlVtog#PJbt z)#1su$d8ZU!^2nI15iP^Z%LyoRljo2g7)E_L@$2%$I-Is|J*{IKH?q||Lfk1bllr= zAIlegLtD|toD1PogiE8J=r`rGd+xLKoE+yUWt={k-cBcn_opW(`_svO+91~uoLNx` z6#WGcT<5Vj&S#J{j$q_lv3SNdWFVEP9u2chu+}Hvz}t88ElXN_MjvR~83uYSyOk!v zb85zz*aaF}ID(RI@K$gw-Ze;ko6a`*t$yDNs_j1zv?u56lotP;Z-cw&jJ`%#^Pp?t z>rejV&wtCk2M&5wRp;0qY`!eQv2rew9PDK;qn@w<(ZUX#JoeK)ZYtM_-s;ih6N=Mv zF!RWWVdSwBj}t%m90OUL8qBVpxf_bgH|i8#Y0eN0*Pvj~z(phTzBEh-Qy%XyqS06= zSI`)o*kYFnLu^YYAMH4?kwcJYYGG8VUoE+`TWa8&)b^E=srywV{Bmzy-z1U1`lw?D zVi{U#72hx>htCHmwu4N0u7`rv#(6J0r$rJBF&acJZ1RT~;b>4!nc_W&=dgEufD4(gHnSe7TqlrzN?VQNFEh zYexKP=cp)C1QGzf=u-~yRhzZUC_-$wV5;3Ph97q($n9y)sdMPk2qJ(_+Yu{He8E*c zyodl#s_AlmRa5-*zJc5qUD`r9bib<3i7_Xc>mn&(aL!0Sru}-Mh}@b|wG6~o#FiZU z*$;m4Z)wTg-=z;DLP6`2vzIs8o<6cVeM5Uk*QS&&+3ZiWV*qC-b|!t9#Ni0qzwl9A zcmj;4njSo0(TjzdjE@;`D;xEsj{{+m> zQw8w=w}gDS9UM7jpqF~H&27{?;c8ax5*|eAW|d)*CO(P!js5Ka6qE9#_@x}i4wKR> zJkbxC*b%Q6u4+Qdgpa4aI2Yji9*c*X5YJ=Ju~c~?Jif@4=wsK@^!0drUP4xW@^m8; z+45mNIDJ~WL&8`4ppk@mFGh6OD)&gS9?hN{Zuqn=xx2(R<3foAC5K^_(c;~wO_kf& zBFii`D}36fgrP(D9YXbyDIdBOYN3KFB-o)btuQdDrb)?wpV5K}J5%Gk=5EcF8-9w0#dYP5T3n z4gO#=(%L13ag9c&=Z4yqIP&-+XB@TPzq;}(5Kqs}d_#cm?7RW$L^dpbJ%9Of z`q%&ZUr(=Jy_o*<|MY(|{rXp*E4JLfc>6{*Nn@!^-}yhdu2dJ=;(+hr3jg%=#q{#! z>*?jG((AM7)v3xlz4Vi1=+i`e2j@P^fy(B-8~0iGp>=*horNbBw)mg0hsQkKbvQkI zc$h0d<#a9x9FVssWtBNa7?lJ9)-?%zJDbj z#KseAEPS!Bwy#*|1^UMej*8iB%PSFuzp3^hHJ_uft) z9q&y~RIhzC8)u_lkRxz(9GzkUG7gN*_?$P+XVwco>iRqJEDug{yNxjWxn349;=ra1 zt1;&5Y2j-xeA9lDZrH{H)_mxkD@~cV4Mw|Bi=or`t}?B&L)PHy+n@atbc*lHO0y@7Ax7U625j;5S$Qd2GT$`A3{`ecK$NnO6<(Po*UpO@=H#?f%*MPYw>2U*5ows%5HoUL zoQ*)M*7D8zT>J=uwhzI8lLNMukMio=u}HxQ+$?s3y?vWynnrhSAH{PH77E?SY7#XX zxbSlTE5;sEZfn$iby>>dmk^#5ly8?+e!y9nLlT|TIST_WT96z3(um9p0~Exwv}=zK?H!Af-7S6LoVG#@5CY{G+qWwsoANZ;k#%BLP{?L?$GvAW|CIyLsrlRjR2v@&+kby)bebK9|jQ+C=xaaUa}ViV4U zgkK@$msi{@q>Yw^Ja9jTul59I%;uL_8IQ!lFmBqu#mJwovV_Vj37H(`mru;XsH30! zx_awLHx*#a`55usC%pVW7WG3Oe@tE|&N0wNY7alnEAT>~^837c04;o2M>%mR{v02S zI~Md*zk5u`(x#rU3D3C(U1nrNkmG|zFBY?W{L#_)Qf*k+;?;+=U4G5gi(~kr{orZx z4K2GIzXX(i%c~EIHlMzXy~`I)KU<;7%yAr9&d-SAcYab-H2O4n#s)qu@rJDVv#s&S zz}0lNH;7F<0WmYI44Y$4?N1g#sWCoESrC~LPm=lkp&T2M%JBFW?xKaju?FYVlh=toa3EVp*mIhMj;A;pJf0^{L>yRB^jGs0H2lFLD6 z!g^={k+dx-e8b?^@`9NrZuw4&#}q!td~kN!yLW%wntdBQTh*Yf7?f>CF**+?bR zZss-2Is*^b;BCR1ZhTB5zhRV*{D$WDJZjW4PA&Kp&y|8Z>o#+tTQ>3l&*zX2_9HZJ zlW zG2)BPtZzR9-N~Hmyq-5L*RhPpC6?$R&vz$;$g6*Qo9$bURVDLCkn8|-<*(v(vO;7| z@CNw;kE;1zdK*wi+9E}4mQ7mxbh-&7w@u-zlu@t5+)3ZV`623? ztIO%0az8C!rs+G%*LPvzKDQJQlkZ>Y+{E``Y%pU1i0>S7ZSZ%~Ve|2pFDStQA^r|8 zUBAT!J$xwf2Bm!0k3($mlY41=6Ucvl@$?t>4JaRd-($FfCw;}qe}SExocM_?7Q*;$ zjz``i!=l^i`Pua1#jEM{+4*#Kb}^lwUrq-HN7FBV^(+5R*Olad^vlnt-~8r}rt^!7 z>D8;V>DBAA>E-KF=PYEwKfAb`E|vIh#yt)ey^!PgRDSWzD;jz2q!-*yPhCgur}%%- zc^d10c&kmdVsTQwo=Lo>gb6YaV55BOW=QV8O!wY}A4Y14KHMl{~cgE}>+?sa7-QwKzW#k%C;8E1!5?1J;j7jG^WP~6t-hDe$5Z#tQC zM-jw0XsV(eaf1`LYgRtyO2i^%rhH(@k=aTcH(8_O_Gp_{1|l?qe(2IG6h64lZf39n zbIgDhtK72B0uyZ}o-$6ZI+f2hoELL}jy`SAO?$u*u|tU>H8FJxI zD_RdH8f3mmSQnly6rAXl@H0O`Tqo_kMlm#USApV1;1?;2DQ5V?1%!o%@K{KIpQ!MZ zSQ@CmP1zx(Q7I%$^P*SvbDa}J+ki8PVB(NA7O&d@yQ=R4w{=h0q+?b53Nq+sJM*-+ zN|lX>wVOy{p6g6vNj&IF2~;U8m8mxILR4?GCw{R*o%W8o>cA8S?-WRm9B29{07AY0 zAQKG#CmV|w)`HIjg#JQZ8~(+|3pi^v-5!=Hp@0s7(9iCBVpHCWCZ1^6FOvgwx}4~E zu?ahT4}S86B7N*aR5hyP-?yut#Nl7-NY{%V(sdt_O-RqTn`PW?1fp?|JHUGaDWfNA#Q9F*;rx6zv5>P57{7Y*_BaHTpG+Yu)Y?ZrXzod-_?u@m_GiLSt` zpoL?D=j44&v67v(dg$N_%;(>b@s*GZFIo8-VP;v`A9*W8!X*-TN~Ire<>LFAVMtjm z54Omfj(){ed%zk+I-7Tu@`=lZ6==g24mypeox{p5&@^FnA2i<>NVi8mfkrIXr^gqX z&U5U6#%0NjW$zN4u>;1u{WLec|g!m&rf{)6yRFYzh>q?!FUbg)9=2TzWL^h>B}#FKRti` zRPsyzx|wSWzohjI0_KqJl4YEMr?UZt*`6GJrJG>3c@G%Nnr+Ecoq+Z~ z`WoqLGViqSRItrvkP0V`MX?-g#GV^xR z%)^A3M;^IS;Ux)f*@7oob%vSWc(80OQwo%9=8rt^oR!vgGaeG{t#T)w^THhL`rWEvrE1`WlUIUN0Qpg271kVzZBnqzHjS$ z`Mr0S%Jbxvzps~nzQ_7Uo}3qfE?cx^d%1Vf-Z%~!3--Y{L{`ad9wmY3d2HpJ;rkBz zd78^leQBvJzWvAD-;1Rp&* znI1oWsPE~#icr4&L)yu233&DDbb9{c<@B7Vv|gPlmi_5hzxbunXVXUyPo^hNKJq=1 zi;FkY>+{R$h4h}kdOf{Rq8t{#SjeJc#CNH9&Mz;N-Uw$wF84NQ$~SM`c~R`_l)rs= zj7RQ=-1BP?Su~@L+>4-DiRDVMu=qt=C#4<9 zxsT%eQEGGFXK)`R$DVs^x!;o?JhSk&uQKR+?yInH$h|`JdCSfI(P52;zAwTe7k!$A zx?Zef0gU@z+$%a#H?Zi%0$zTMu4M4w2yJ%773Pe0&asDHPHmeq06g?4TgImCXFkY+ z&pg2{9N3g8xvVO8txH`8xXBmLV|^Q}%S{e)H=AwH@|*OK-Q;Cm$2Hh~<^QJg?g~9t zw)y|5F#6r*yGHGgf*%uWJ@NHtzis2}>jXaE)!DR4Mdra9mhm%*}ku0MD(c-cZn6?pfq+M{J*TZcL!!k$yRb7(eBypA}4 z9s2CK(cwo{MdhgqW929IzOf-^B=}r#5OROq+Stg4e<|V{?gCioi%(lS7L>Ikcf7>K z!G+8?3M{tX)5RhGf7JCbNOAnN1vkO_hCIA1u%u7iS7nE9E>6TrSy?ti=pa2Az`hOo zruhP;TaZ2=uN|MT5(jSEHyCxBOQdZDfawlv*FIw&DTa8>hW2 za2{!RTzpH@s_qZRMVzHyZHfZD%dy6yk8SNXb)Ju@`_%^Ogxq9ha*#H4TU5e#^SsH% zJf#Jf-x`;_K*-`+CK@bcQZBmqK~8&%XZ@7XY4+hN6Bk()b!d8t7d^tC5t#OTE?CQk$++pcdfSW-nVXo>GSqUW45gL3&KW@HgjH~1#q zM$1B8+8_&7cH^>G#AT5WBkBX-*Z(o5x^hf1nPWjKzgWt|&SME%CHmBI+VOz@n@eo| za&SKrS(2Y#b9_uF8H*%jDoePcwVf9*sjYO=_QkLAOyftfF5|_-KvPM7jHe#0kG*KA zxT)HPxI=2^j}k}-qOt|L*25ZGaCqjLCYI=EufiP;3_-4w3>Ir^7o5FS=yLO++|%B` zfN%pIcLwyMZ3@22(PrFaq_eEG-3kWij%@MWP&BrTHEq6z&veV2IrR!Zs7VO5hq|x} za)vK!%=T#^<0W?+o6ZKbZXrH5%x#^W^~gL1LJ6r__Q1dv+T5i*5+=Io{f@Ri1+tYt z>(2bvYpt|bq`tyvi)Xio*og?h-$EmcEqSU^jPRrK(3evqW%(PxdfUE|w$Yk*@JeJ_0WM*^*L zAagM(3Xh-JpB0mk*pYLvd>W_fERqzcGmTNfpMbE#D;C@wA}5^)gFH7h-n#p z8r?wbOQ+}_1HddJAL+*1zxn2dUvz2Cbz(z6eBGzrer^Mw7SOdIHVS%)DKhxja~fI7 z!-%}E-_0`{$p(*XOySYT&5LfAZ5rJCqRp=auGHTtsWT8im0P2EW?C<*NS85)s`V{H zHL-*jojF;l>us@98g$Sp!EzW{$#OIN2_Dth&h20N$Q?`3b8b5&Rj7HfLE_H!SiF9$ zDUnxNWc|Hr{WiqTJu;o4Dx*^$CiKOJI^{9^zYVQg0*Szsz#4k(7HaUR0DXaJN0}2~)w#m=y&>wL-kL71 z_|G&J8ZX`69Pix2K!;AEkNN8d#s;rDJmmF^hiZ3T&&Wd9zGB|j{CkgkV;(`a16dyv zzBl6bfnLT?1Gvj4M~~w_9%sGe_#%)02IJ-5v~`SK*DDxtU{hvGuxvH%8*cIgT=TU> z2Uzo=yM07ez6ra0HEfo>Ti0b3z6~tBL7{!yPo)n5AIi@*_`Bvi3txZw=f9<~HKcv; z8t_HZQQ?jN+CP&Q_!P)wT6sj_aq57BFHZjE+j03vnKb*x4gsf$aN?J|=-!ti8MwEB zhg!01!CY!^+Zc7SABkJT&^n+>9dn9lNn#!M_Jsg@<2jJ9w?}<4`ImOJpJip38)^P1 zv5%#x)^#tzgDA{)jioROl13hV1OsG;1UvTg&znqB4sh$_} zC`vqH$%R9FUAPpc0XeQ+7ooh}%T0rTgbYE{9BcR(MlW)e@7T)*+A8Sxg&{KZ<~UIS zqPz*z6`hz#H~PklFHh$62neq@v<-TqW^2>om{b%q$uVC zFCACGeUf_8=1kJ;lV8IA}XwZzx|mFW@ibW$`Wk{gk2oRvjH%$1h!Q z>Q9}KyKeBvD8K4p39|Ns+#CZj!?Pn~-VM62i=QtymA6UJ=2*PQtZSTO$3o-e>Bsg3 zrp?OA<6;J6;g14%g&Bp2j@ipD(5P}WIPHan4eeCmK_n;!O&JReZ0Yi%P)hKNv<7sY zv%`cNh`k|Z`{b=@(57D>tTCSKIEBc_#({b`FF74azET7s%$ikmen zH17nZ&_-Q|ZkdjInQQ{7q1}E(AwnaHZLUU=Y_8i3Du|u z^~JlZ>CMHf>Gg|mrysumdiwtBFQ%`)_}%pFH(yStuU_iQ``L7Hey($}u7xau>HO~- z4w%Xfeag7#dE@N*1H%~gj{!#AP2jQX@wo{uw`8*pmA?Vj`dp)om%L%EH^Mf0o$dnH z?26yeey-^i|EB;R><5311B35fG~8wuWP|9tHI^*!AgziFk^EcCe1^EHZQ* z5p$wUd1(ju2(X#`E2TXNV&PdA&Omotx<5+R{XOcD;tPIcf$)+mnPx{v)Sp|d#&eE8T8-%DtVv=M#YiE{GIYtxu}7EQaDN^_fc*_A`53~i;; zUEeU)Zv^+3>sh{BSmiypvn>2wkSlrX3A?5)2Fx*0PkowB45V)91w0RIy<4{1U~p9_ z_1~4s>P~4H|IpNeIq=nVpM@`;0DF@}2cdzU$AH>8<0`TASn0)-K9s zX}Apcz5K;b{9)qxHGaziP|2~A0wUi|;9dmx8(54Hllu%jjrHR7Yd_7!q7miz6@CW? z{?RJ;1pFOco9|or$+0)n>G|b!c5&tC{9{+e#rOO}UQH-l-r{oghX44=lUOW-vGDcq zk(z19QpsacwHiWL>u&?7xxhRm5}0;?9I%7SM518TGY^g8jWS@tT9-Vn4{YeJ@R0@}#Rbc@wjI>hw!ntI#=tJvX4`GI z3vQADEx*mj&0Yd`E$c(VAHrwDhxYAutn_1`p7{EU-^N}$E`siwn)nqP-~gr|PL#7c zyBwdwW`s|2U);;U{6g5{%M=3P&Z>-P$UYjxm7616#GS>9ZQ4(86I=v*!dEWbb-}k4 zDKSnuFSe;g);pcJgrH+a#9}YFZHZ)SAU42psafzBz` zwcIrW3F$rM+Q1i`=qmZ6%?|VtzfbTmd}Cb6lRe6(q4jau@+WlmOHioUpWTH<>Ze8A z_S}TG#FkvlkmG~LjBQYI7SZ~G5yxsL;sV76nv=ZpK0y(ell&4YuTkTsI;UJ+M_jMo zx*TwFPdJq3TKU403%-!zCVu+9IRGk|_|(Z=4EoI4@Xbz1SuDUq+mmA=seK4nB9g=c zFNsR|_@Q!bM-~I?qh?9Dj=1bg2+sz92rrTd$&KeoiFwAA_@6kpjtJGj?p;YTa`C-L z(f!Crak8Lfz8gV$G!|pjI?9O{sa^2csFRTX!=KM3v<>xOL5e<8 za^3i)Rwl&z{2v!>CBA>9#YC6MvHW&ivEzxanh3kB$-jys(Z{q|7Rl)Uj3F;35~rBd z)jo--{Q0$;@Q|wg0WW?-Vyhe*QSyT=7VDgOYyM}U244t zY$7`T@T9zApggb?3#T0iqLn;;0Q6e|2rHrY?ZuW{RSg@ytrR_TQ*Y~TsIarDAiD9o32g#qE$xVlzROr$PjkSBp@=!gKxZY`PG5ihx6|+b=HE=;e)YTQ{Pd;L ztLZ{t;17LsV?TZDu_cddw;vD~4?Qj$px5a}*rIP6(g4j{>y4@P?v!-B5i%#N+1!?FSGJsVX4%T0^#*zyZ%waLL*r|Cr%|Te5?}E~*{Iuk zmVp;-y!n+{*7Ant-NYv?-yL@A8Xps5%}|`de(}-TfX?w;Uo2bFqQ9BY4ZaEJ`V3-m zZ0n372)&fE3C!03WS#u|Opv+Ub-PVIxw5{-iCE%nI{Li`G1j^B@X;e4Xv*1?_ji>p z%X8?VUgVwfW5JY*xh>F@tyyK~#0JlFzRw`{92bFow|t~G+h>ip{hS;~a3M++;~b0d z;&0fAPltAWNM=ZPqYV7OZ5%ytZ=459wj*h$&r-(B$9ilpr}nk!({rZ*)^^%e9y{U> ztjkCo^N&77OI)g>UYO3yXLw1YPwk2g-Qz4g4|%cDAGB4;=0shHsqNU;HkL6%?B?;w zn7U~jeMq;D-*_32nX!QFu^oIYDI>*`P1~lAS`N*AGiz6~MhU&W#rrSNX54^9z3$$G}fv9p+Vh$9(VK zSDj?fVik)@XP1}L%U7q<%a^Cqt5@fK)gi5y@BD{yk#7;UQLM!9@Z@Ovi2oEjIYy$g z`IqywIzKe#$t)JW4i71hdj;H|k)Z;dhN>cn#qG9(H-fAWvGIo}N#y`Jb@* zPcrI8EKfdqI6Xc&m>wSI2h2e3ho%L&SK|AL=5enkKm4bxEBW>73)SZSp)w0z@PuFT z*A$|0KwSai{Eu1ua4(c{+Q@&~pbp+U*z;S3?!RM!RcY>D&PQ}2 zBLL2@hab#%(|vw3&1cqIaF6q{3oQ7oGt#BD=-&-*hzs~*nE}(q+HMtyy+ow0NCId(cAKFPEAz{yB(^fSINJor)BIT* zG@t?l-NcHNU3^hB?B&&X z1stA~IoTuaapir`Mdm(Iplxs6QZgV&*#KEe2{he3D~>`9c_WWGH&_3t9YbJNlDfwIB$e2qGtW z%&4DmLKh>IxF$=90|qLLCCZ>LW6vali70*VkNLsl6LXJsc#?Sm#Cnp;`NqPU_*Mic zTN|c%5{bniO=jVi4|K`>sJkD*=N-@dk?ULY_>~e1Tt22WDdwHpOx|9fz1C#twI*kp z5Gh?<@(P8-&E!ZmBXs-Y3k->is$<>NvSH|ZaQlu!Q=J3Ld;@glcAmZ5{46w2ITndO5L`-Wg{kA-QC zoF|GA>!1R+q4M_W@~z%_an|u@SG>hXpm?Rz8rJGI0Nt>I6JD_F7r>uBL;Uo|95WR) z63blgH^J>?b~#v-jeB1^_eIzn;IR}V)4*b9QgrN#usm%hq}5JB%RbPoI7E%ju&}KAZLr4w*&xTEaOpeb+m|U3zb$z)jd@ zzOKPqC&%>N;F_jvZ?b+L-#ejvc)!EnUCMc{dfuYDmVS_W3hv}*(79{5+w^{l?KWsF z=PMh0_p zkFCE&n;yXyE>HE9FlEE5Z0KiNZ4Jb<*lo7U0^zs4Z2;+cjt@DPBj(D!L+UYSPpfho zO&p6J{_pvIjadd%mRM46$X&4~Auk<3dTE=b51o~Z9zWKbT`acI3E4i|Pe^v1wgGLB zdN#BsZpzh8nCr0>u9rLN4~LmyDJz1NcnjRDaa-)SfxXKKx!V+kwxSL&kkNE}55KSP z{+cV@yMH*{KX^Fp9etGh0VwI?r-QCo2+86{kDG14eS$Uc#*~ADqv=3Ck-n|_ZC)(l z-h>iIF~|Qn4svdggfRHB&a9g6;;s<3`?dw=dptiU^YNqO>En+cO^+WwoE|=Uq;t%D>pgw;a(emd z)x;ZZo;*ID{`gnFn11=$CoYrM6aMh>wHK63^4FD%-N|1JCe`RnQ1A6`w*U!BSCr5Bo5H2d}EPp1F;AN_jzkN)_x>7z%7 zeih=k-@llC|Mk=9i|?LK-#$B?o;|;qp1*h{*_nT+O!shaf;RCvuiDz(uZ?pEIk6n= z@2ic}RwoaqlaphgHCS|etva1v@Ly&5Pd1df$HCcz`y>GOaQuVf!-MHa?R|25G##ot z9$dYcri&LkMx^Jz#Bm4Oo(SkY+An$S$*C?bnfQsuRz6Fq2!)d*OA$%w#;aB?)35B-Dy0 zk_kCFoIvavoLEKpqHD9*L8K+5!$n4CcTRdp=||^o2MG9OCtrOdyE?^QfFi9!`6MnP zXtam4&l1n_3#rJ6h1^j5E4tW|UiykQ-IehEeIb2y5KRzPM7=aJV*2amQ9^!hA zf9tZb;NpcCe$|twgOGUvg-M=t{X~%_4*Y`0izcGIh$Wpo!NsqF_@h$UE8z#6$KRPO z@(Uv-9eK)2seQ;FkLu$Ky*vR$EE&UI^dc6;&ro8=2IN%&EX4BbAQpnSAqf6vy3{0y zcU?2-VWEpfuPc7}Bl^;lEwwYgamvSd5>KJ+?eY47JZ;5OSiBFL_gzy5ULWWu&J-_C zU>%*D%rTj78M@Kq^#b<6ud_7S^rU+KF#auLG8TTG=u+9$Ry^^=gxOE#(H=_o{eN9q z6nmg{^}-fyC!KyhBIRchjCQ7m}M_Kss)4`xXsPc=O!;BLZ5w-hZj?uAZuJH{`h#8B=E5)S@VB>;_E{L{nM$yO`Q&a8?522u2pB# z`RR-4+0*Z*ufO=4>5Je0)%5K9ucy~9o=&GPpG}jlT>#-g9>2Us#=i*0gky-U`W@i7 z;yezF{0?KYOdx`?7^5}bsqIGl4ga?Qnq#^Ra_lYXM}h1-XXCgn=$j1h6??@nrn|s4 z8}?(8;F{i;?h0%DtvOra(x&hqOpU~K00Z~ zCsQdQ_Dzm`IrYBeB)*IJ`&iML8@1AG=9F-vXE8haWEfkW8m{r3n7b#g8nLsk`@i}$ zx|NVSu?5C*yU(M$;K^ZCZZ!N+mU-5490Y`0VHtOGnx(8JWp zE@El%V@a>q%3q(0au;dY7?%OYS;ktxieFG>7yPUc{n$K|lHE@$}gzA5Tv{ zMsIK0d%$AT{ppj(52sI`oJv2K#+Vv5)KW^Mn%(RMaq^Z;nZ&OL2tVa)i$&v z{~KmoIrI;XrI$8W!Vkm6G3bL&jiUz|NB5PxO4@vmum@`lG9@nuBAa7{>#ziQZ+$xukfFzba}HuIhg2{)Z%ZF) z*0btj!|>0b#8x~JNUTZ&iRN@_k98C3rN$l zqLjzNln~ikma;8FnKlAPL|+zdh7qf1SA?xc5WjrS{PJs53CoU+{_=5Z39aPTEC11U zeAde^U|6uY;$p6gI=sXjIZrS;Vi9;k91?E)6eDe;L`K<6SknLaN&B@v3o?x5D;AE- zvzql%h$b2=Ho=qJkDgNo9LBVq`2y}uK(J&=@g@-Bac=!E@;_Gesu+rIe!>S!RUluy zvS0@*V~JlUX;P>O9uq(0`gmdM{Or_EOup5mn5Vq>!&sgU<9N6@JM(KFI7T^s`qxw} z91#l(N-S>m*aKK}o{vN6y6*B#+{cGU@{@^I_|ZW|rD$Jv96x@op(pZLM53Pb1q*EAzbWfqL8JETcV`c)nrcCf~dckp)U@ypTwH>BH*}Ii%h0Dwo$!(xxt* zSf$U-b;CEL{5zK(It~C1dfGu5PX$ZgT*2bUl-RZwf`o~fn|B5Xj%fv{+zVQ;4V>>p z6~kuQIV9snAeePzFB|93+WEX{wNjMb?8Cg?BSnB;`jgrMrQ@=Kr^b{;?~hM$am=~6G*CGv<`-4R#a2Mv9&4P|A(B)i2gdIM+Xp||V4iX=4<-Pf(jn!qXf7v86nn7z73YR zx5FsCO?M6Nt3QHm?`Z#1$^kxfz1GrE-+hq-dS}0_VWYeqW#1apE%JuD>WwhkfQ{pA z!<+QBdB0ZX=x;|n@cYxjIvQ{<`2wGo_0g=5e>=))fa(}Z_xCm+vE+q>BYwL*ybR&PU_J5Yd>hi z%2`gE%@U<`hX(ZbwZa?L{z7BF=x*vzUUV9uQ(|D$pV18;ZDYjw5*KYc8~M8omGV45 zz~0~6wt)LXx=8IqpZ?ATq>VP3gyPv3zVtUR)&n-*UIK}6LtbEhFz*4%^=6hR=M1Kf zL=464{#ncn_Qq7O1k06dsYT*Q8NeW^c-khA@`2J?}mH!1socipNZHH*k z7sO{`fSc`?vbO1YW*qd+u=v@Gg}%sm`7z-800Xq|a7C=n%OlNqvv>M#%a29x?;TFl z{;|GaA5L$k2l`&D@Ag-@)8fS@jalDQGqjJcNS~L4>3cIjSmkXl`~VfZt4n@Fn{y6t zRypJcs(xb%Z&6V>`VMaYev?vsa(^NB2-P-3m=#D9cw z-{43-Kl|+C=~JE%d-PECLe86`vS4(sy7B5o;^S$kCm$XAX{`rplQ;Y~*yZ{3_;`Q% z?9-F!{@csx_3QKL<=NHr?TfSN>+fGpUq5|0ee?ax>Dh~ye!`3U55M`d~|SM_1c?G_TEm14>V%* zJ(A;W`L<6CT)jjq_x+rb^<05GnD83M<2)ibeU&zkXpsZx?d~EU4u*)|wtwNn)yC3!`XARr*N4QNs0-87JTXuJM?^X6)q5JK}!XF~0UGP)O z;)$<&|HJ?IKfjBk9DIFoCbN6(7}LIxRqq%FWhaBa`Q<}Oy2i=j*u+ebn4pGFAz2(i zHuyB4r~}&u@g0$Nb&!==KsX0{>*q#g3!^s6(4)MF;wGYigBIaW;Rck@iw7We4d2CS z{CL5qVvY_wRM5jIibP;Dm*L!ExK=l>5pxw6bu_E_AS^0ac>sK&ORU)GVnY}ELMjBPM(RR4k%)S;ey&9FLE%0nnwd)n3%a zl9)vSq|CIV&D{n*m(gx0;2T;T(e6dj^D7!iwgrOpg@pE_f4a5?1qGh#J^hI8J@xM! zaU~P&s^9~AbI~=k>=mG$EbW0lLzRWHj4#F}iypT0f=Pb)B0_`5PZg@HO!9C>Iq{XU zSSXSYp)Af+*TI@jcp#jwO0zm((H1e68l39phDgye@mcLnmalr+#IM#sQ$ zr}3|tc*2eP^%qYjUhq9>qdfOZ%8DL9K z&fyu0l$kcLL^{aO78f7J7lz8rL7Ec69MQ@euIy%QtV?KPPp3RFrPv@!q{|X z00){Dqy^EFuzb$}l9f#s7X*Wz%c}C%P#!i!gS&tjzDD_zNDR$W%CQL3I{`X{D;BPa zP}XgcO+uu0E8jj8#IJG!v!OH6h8Sp~TtQQP7cQ9FgCRQ`25|(SqirjV{4UgaF^gw* zR}x|XbLaNxI-6;Gx5MlkR&-!EX7H8oWWC6gmfQeH7ouJF17&rYU55Pv!rMg^H3DR7 zMjk&gE2%RWRY!co%Wj5$_RoG^`1-p6?#LAea6ad0;G^l}(MQuSe*K&2vtRzv^yHIY zO~3s0A5V`SeXNV(zPdT*@GM{ps_)~CJ!57?SgH3 z=5f3!<$UmdaM!YT!A;~ULUpPF=i;JHRhURa|Ghbf2>1!pb%NT%88sRp&?Z}JT&@o*zW` zmu|6VnDypzwn3F~2k0=mpt;-uw(+*Zb)8MyE^Vm%Mt&RUn3BIG=J$kK3~#z#BcUpu z^Z50L2h%;xktYB6^MMz@_~y)gH;y&ymL+*dJ(l3_)%u>!;tFqK0a$ps;$9o~7WDnf zGQYv)XyOeyv?p@(vdE_I0Mhe!daf(Nv+yOox)*UN+W)`JTXA@s42wCUSQnmo0jOfTr{^SbOK=lITjpm&lzn2wJQrpJ#@ zrjH&!lFp%Db$E2JKV8T_Piy_aYZ8_78pMwtA5TvnJ)S;#crqRCP1Did+v($n52nL= zY6JOu^Y+2?!|TiGtM6Y;zx(?6^yRlNrthA;m|ng-o8DYrPKW#Vra$_{N7MiAfBPG! z$B#~?7q8BzZ@zmzef8bT>FcL2rf+_DIen-6#cS^0O ze0Kvlg}Lv_CO;I0j@&Y1!68}(1Yh*+d5{B5llvZ%ah0R^+djO-ZX51BxY}uyyZXf6 z^&VuvO?1bzhP6##tmh`|;y2tT9|6sq^ewx)JHz{we^=-+^JC!;5z{XCsb%?9hyUbH z|LnJnHVtDr)QO3M3BTIqmnb3_hiuh0X(WuSXuV7v>Zl#;IpJ9XjUQ~p^B67nbMlcJ z9JN$1_F?K{8=V@%v>rQaId7*qDKuE(yP%O~k4 zM`Xk{`pi|7PsglXWrk>KGgI2i@#*A-hgY=4;NjUf{;;)u<@iwM2Is_Ll#>$*Br}Yg zgN|*uF>Q7^2*j>VEES7+;3z_~wVxg+R>4u?NLk`p7(Wee@$!#e{DLr6q6gm~I-=-% zVL=<^a^F-ft?b@5umOmfkYeFz$w5_?}Mc1F; zh8(Z6+yfA9Ha-&g9&J$Vi62t{J7viGIJd7E7atSv#DggbN6zAdj|EN40GhF0P=`VT zp45OY7t$%mY1*)uh9F({=!+L4`ANJ^DB`#D1IjC&ZfX0luaYUt@edt;;~W9L z{gqDK4g9&4Di+HsHyYXth@f&14uFo5+hg?2Iei&38|_=T%T_X9J8b(r=D7_U0~IJg zF$~i7#s?96i-fcHICab*WhdNYNvMm6$hmjSYmA4SiOTv$p7+{i8Wf?+r~O6Rwepg9 z%lHTfaz^K4Nnjt2Fmh;1F-Yb_7KM<-14)~Q;h2a;8u?bp-m(^tL;;8zmU?=tgotHdZs zPv?9Eq?A%9Xlh$}A4tp#beX$gUDi6?X5ZlPUJ39#t`Z}!bXPSJKkXTM?d<7dm2DnLgo6VZHQ?HT)+vRIM`H#!d z?aT*e*}wxv{!Mb@Va&W)SD9(HQ5FNIS=IBLCM;QK!D!#91eGtk^<^n6l});u1{ByB(NuxuaA54+^p1Zg?-a@{=FfxpP2yWrbs^Bhad zciFG`O=n&@%ACy9HEiI;*PzR6*&UtnXOmGrCySiV<$0!EvRSVb@nt>vbM;%Zae7|OVSdgcW{NMVLGj8}k zk4~hu)qI1@b>LHV@jbM+Spee)yS(y`MKQmjsTR*##yu4Ni|VKr;QWJiMa%zH@%^9s z4cu2C4rKht75{m4ad~0MAe6kS9+iLt8$6my9v!z`*XYpnl|MdoaK;phg z`w-C9O}h=`Bkiv?P8SGI`*S`(w-?SC3x}%L!@~#D!CuCI0bkCri(eezF6E@`S*M7Z zzsdpd&wY$2@k^fO3q2=aD;EDFta&4S7ySk9=6?;h$=87PO*WR@ z;u4)P{TNvLSf^WqxCP?l-wpiKvhu3K|LOmxv8MrBCsrTKLfW^QMLdRe#v=zQcPTg# z+X6v$$vB~7?2Lge#A2L+C)Zwh%FQZ29Od{HJ2z_tZDzdm%8er^-#%6>HN$wYlm(t# zIuI0XoyZNXG@?cZLFL!%fThv&+3tH*W#_hL(lcufHi>^OdNvGW+*@2O+LP63%hG33 zi0{6@`9$qZ( zbos>?g6L(@ic%8an=4&_l&2n5wrq&i_V@*4-dwspSe){>R{K(p>mna41|>X=e|S0uIJT+Rl_qqQjxFG0R62f7cEvz7 zn7FcNl}GT=&$%Jz0%<8O`&3N$r7V|TF#s&EL93#Qp}174bIO$u+5x%a#yTRU;Hifu zk4nUW2Npb2Un>Tu(H$55ah2m3pJeuDeX9j8zziX}2jT7XCTR5r>Br0B2i$!OPd;r6ijkOklf2Wh7>D+YznWgTY#5G(_K+a9I_Ovz+r9@aU{uMCRibA3hL%uVsRpvgQLMXEQmBC*{%f_{k^JC!hav`uNFb)31O152nw4`RnQA;YYeY9P0ePuj3)tGIxKE z{cGdw4+AQ7hGonKa=prNvI}mDa`V_-!2I{9<1Rn%1MlPGeal;Aeij`t|@r|6EYKHp1k+p#m2!|?|_ z@;t>63@pQ<(>Zk>kKj$;+hCM$(}g#(qjS4WVLSEbe2_KN72W5+Zm+SN5eK$CF@=t~ zrQ72nRPCcMr?uaP`TO?(8@{kppo@7)oViCq47Q8<0;2OhrN~(wByn|V)-42eo5*yQ z4{+O9Fx@;H&2snyY2P76A3+zo0e<31`P=oAy4Wzb z^o?_5ZS~o(Zo|NK{WReyOZ_@7_ScIt*O=R412&a!2y+K)#=fnM8?KlAe&D&m4RBBG z=;?Ho#1E-ulxXg0&g1XNk-hcPM0^kCZ7lbvH}?)?3l5-Dc3|?+KVs$SF52Jsz*zXw zam&3ie$aY!bmYYM>?;<1ylAyNodm>JzVl;?4hvKK^#U~a1N=i`>G0Y@{^RTM!;|Ub zj~`CI`usCLrFC|8K0ST*a(eap%uh4*|5@=g7Yk{W$$y!X`mH#=FZm#T87nTIzeP}0 z5B48S4^_@1mBVZNc-`U4S7+1f(=)$ChkH~<()owK`Nj0V|Ihx>^v9o_OrJj7n|}G( zN7Lc{;q**#{QjF~)8BmcZ2Idje();{pTETZ+~ph`?oFS4bUgjTUq6}t<3Ij<`s|a( z{=x2r>itr-yzY=E#lHOZ`Sk3?>*<`=6sj#aE*!UX`B88G&^YH=7SvcEWU-9D0O5zh z_uWS<0J4xqyK*0hC)sEN&h&JJeY)=%BfQ@5-Sp|B{pqtu>cc&bC#Brn5UyOlGxm~G zCwy3LejxWr#4B5%<%?eKzqGH0S+91XN!!a}EN{Z%&sN%P`1g+eX1NU;x+^*N&(^Tb z$6b8yg1hK6pm~$NWp{A*K4tEL`1t95*6<->yA3{c8GhpHAOG23{8mF;&c#vEkTA|+ zwGAz3uJc;F5+POyvuNjuxvHeiueY7;&$0L(DZmX%Gh(9f7JS?_(| zr>yXln+_iyd+KV9I!22!xE;jbXb(H&GE}~8pq=w*CNyC}h%d+g;=_5{co#e0a4Xp? z635rUnUREV`!!#ggNdgE)ln2?ME=PIoY=fz1CArxkTD+QpGGZRl;)dLA$lsEaQ)`1OJeHmHJ^N9b6F zXNSV*$8ZWzgj#rDzL9Ew)|k^WJ^*Vv4^K8KCv}CLMi$QKLGQc0KT->9V`cW4BM%=R_+kmA1D;J=$!EcbOV(NRz}p7X1vIf?J{ zMfq@E6JHjwIDfc)!l|7nO(b~AS@e>Uab*6FM70m+nD|M51353%LYnwFH_>1+;Z$Qk zL+h(gEEeCSaV2odx1InT!g}!CTXIC~$~5qnz9~C)3`pXG#;OGFRm&iiI}ume3d^;u zfG0|=VkPU^20q-fFQt^@JcN&Xcw*YG8zB|-ITX9LwOS_4;JI3*4#bRpwVDzc(rCi- zAwVuxMQ0K2*=5p93gm|>(!)StDL$d|5k#KYOD4d#H^|}vo8=Y`Sg#ZDcB-uS*0wE( zSj}Kxa>@Xr(#Fb_b$rHy!F2o-yHOX94+ersw=qgS8rqoLc-N)N1C-Yoo9k&1WwK;t z<`_)3ZV5I(JhPNDOhCIa1hFj}`)m8wAy+b4xOL1(&Ja|V>qi5O(9srNat|9gl((ow zha85D)N&~MqfI>P!iNy=FaPo{e}3ZY-wR0J2IxC(wq0tDb~c^9dNw`%?#t<$uYW&% z`^^{1znH%N{+sFQ@_gD;|KI00otdv|a0L@W`PHpJhAhw}!QBq-S0y=nZ~yvgmi- zI?-r4SK>+$^iz%)mN##dE%+wgsgEsG!duGr_>56f`A9y}BP_Dnmt2iyj&sZf%BHp| z*}NoR$=Md!^^}mwJ1uQ?J+5%`kI^6f74^N0uJMI~<=*9g7UT^s5(aCgld_3{$MC>S!#W4T>SUp+A zUqf86ICsI{KwK$ZPN(M=UaUG}!RzeIuME5t|NQboGTtt5<|od6`T3{Q$wS=a)+aEC*E`kF(^ zy$ks|V1beQH@uyP`!Pz`s=2HyT$vzoaqlBPj>ctpZtl7df~uchJKCR4_>VQd1K}$> z`&1;ALofcD2e|CYjWj;w2&`v%u{Y101xDGZI|C<&vg%`Wb^^N6Z$AsZz)z(Y*b=8; zw|?LzIg)GTlWwv>wp%>IZE@WN;^U|LS;L2j?Kb$(W$?t;gFpF`zxeIqmJ=B{16()< zAB`2nIC5^faA2av29rSz+7LIzKwp`TTicGlqf$P^pMO9MuON8omTbPZD$k)6hE*g) zH@-XP^gnwtuQ`s#{LqBv__UjSu&bD1hTnd$f@B}OF~`~UDQD(~W1e-pLMF7cjUt2w zw_a_lxX_6jve=cl+8HES{6+4Qv;j20wl1H_K$`E?2`+oe@T5RV*QAOAsTf?CFhd(1+(_R% zyG%X(GzvO(Aq%*|;!_s(IFLM~!4nM%m%Z7jct?sN{w;{40K0Gjw})UZYut;HwEU_;$@rsFzpjvp-$zs`d%sx)ymwK_d z1+UK`__t5{NFDu(N!x|?7yPmT*xTMV@gu}-1~_EWyvw8(G-Tm}el8H=Fks2&V_Lvi z194vlF>O6^l6%Vu+4}lonRM*ln{WwxaU#0_^-15m$mkXwMNz6RxHtPj10A#n8JMb4 znB@R_^s1z6aSYHf-SYfcgF>^EKQ0p>W5Y7 zcMu&H0Dth|m_Y_!EajW7m5a!;OI9`oje8{Ery8hZVV_vD`BSNODQECo-0b~HZY%;p zwNvreFzO|_q4aU>g1gUw?B{GYCLd*EdkubO--TKNVYG4~)N^4}jtJT4yY21Fs+Ixs zF+4JXCR%QE=FWa+|4V!P<-h#-Rfm7KAbqr?5t^ni`}$D4cURNftBdLM<;&^mw_i=) zee<`|x8MAJ`ueNCo}NAZMqSO1pw#bg-}vT1|0u#E4;TD!pwATpEG7Ops6%1_@J^ek zq3g6!w;Q1Ct-C}2PX5|{l}1~qQg7K^;F^y++T9iI>KlpEpj&5|TVd^Yg9aby_U()L z4KVAiU>9#pBdq!C=QPM>9nt_ZzhKl|%YgQ~hF$u=HrdDPL3nU*iqUCvCRvitjcm-e3nbZrW-KZ5}%1GYaT*zX`8;r66Q0+Z*UPZP80PgHFo^ zK7?_{09kaW-h_L;8k0?(;xBc|{6B!aWsR3j#4swAj+xDBIyQ@KbO7rWIqF2u%!+;C zXO6qjj?ZOPC)odz7QH0E9xT?b#s_H}pJ9*nT6`oS4<4IEwm|GUMGhZQNa=6bk}Pgs zB0P%mRBHx`(MEBUFja|%2=#BKIA{p-pU6HV=7y9y8hnL;2n3hsgY>S@lkvDsex>!F8Vj>2Y}A_Nyj8cyMoeC_g6$JXvOq=vcLN&7J85 z=UA8An0S;)UNWF<`nu_HHS?2Oqilgiwy8Tq@d4Wn;{2X`00Mu@F8Nm4L)=kS@`~ zR+^N!R4?NuHue!R<+F*$1rLOanAgjA3TCb(WyFttq>;q!3qE?pNuO2xKG9;+{Lk%G?V#KVozew2 z4~5Rei*I6uttw7KTVSkk z_!t>=vL}T2h-zDCzZ^Hg&@(A@msUZ5u&c6(fq2RvJ!h{8LJ+T^IF5?b@*IQ$am6Y( z@mY9`qMyBB=&q z>?uRmII$Gn_O|GyOy&GQfFTT3O0fwB?2K6g;=<0wwFvSg=^#^=RcY$qoH>F)R+hCg>X&dyY>3-0zIDw7t4nx|-8)4=zgVggF z^NR*rZ%ntrF5O-H5s=I}gP!Mi@ooJEmd>d`> zXs57O{)={AytU4p+&<#hm|xd{B+iNsjJ)QPg*G|Mwxv<-zM^dA^OkMumOJC~xLfNK z&!3_hALg2_<9bL-dn3#BYLVfmZIt8KyhUfx0|&d_e~WyR2dw#s%3|gP-_#8h4zJpc zly5qNzV$Ziu3h1qem7-f61&Qqlgm__%|2YH^-P!tv*lw-dwUF*-PR-+&oe(Ixts!V zYM=aiYS<=ATDR#sZL>+*2F#$jqn334o|181n};lxxw|3$yEkHpuLIUUI>&=>m(66! z<-_#d2H&&euRyZcgiraZdkKC!lI`+z7;lB?@A0OQ+a+U5hRP52_ni0hX4ZqeQ>&Q9k!E^j!g7 zKcOWnPZ7^m4*!w%@kfuRlcVElUp~AjCqHlaUv=x|xaLEh{NG-R{qe)2XR0<3U-$;wjl89-Yr29p58C&y=@@|*4_C0w&sYv%KT2@6X#?B+EZ}ohL4^~4H`rNr zvs>%jR`y*Xem;z^5k6FWH^EOSqia2;TKM{}ek;%Fyy`$5Q0_b*yeM+ApaX=5;nM|q z)7XGys{>LeBpeZl!P0>pFP^ne((t= zpV+~p@~DtF;)y|cFP_-v%ugGYwPOJ~R@#V@tgaa}m`}inxbWoS^G+vM3Y4t`PWX~t ziesUN)=JratsskEE=_*$O(-5m(ShL;J4w8GQtfM{EK@)|Dj8)lU zD(H)_3UC?rfiF3~s*9q3Rf0&n*tH+kU3$n;1`=>x%*f48JMw`?*`_^sX-Bt?HtJ?p z;_=QJmRbg{$}x$uz^w_NzE(E2fi-C$Orao+(H_yOq73Qh=td74jQV(khD*FHFOS6T zO~{~+Q}ZoP+x5azd?1LOL$xTL5EEWi0e0l&JX`!&PYI*=s8NP*(-4(Q0Ubwbl8o5uoG%JZU=CT{*Um;J_uR~ASp z5_xRX-vvNWOr5`TUZK?kA5aL z1N{!fA9&k}VSS?#*sscquasikbW9wCFiLb^dJMEy%9!;)SoJlCFFM`q3P#6#k~+L? z3PA18Jne|r?v%5az@EtQThXFt9Zae`*TzC@L2R)2v$D}h-DuIoUyh&B0YL4$V~C(E z+SMF?bV@I($+YXP%DGDjHaP%dWUTCpE{^xfv290fM?Wcd{E<@z<)uBM!v;W`r!j$& z`7^I|i4$~a4~xN-JiyQbI4_cStjU=JR8K`Uod+c}HfCE6QIv7?Qj7`ly6wG}J#}?# z=pt_;fxiSZ=IzcU#4YumO}r1S)NKbBhI7Ybt(2?1%Y>F+^j)p4j3v>J4A9-FIJ2Uw-k|)9-)(*VEbS z=ek~AO;?v^J}w^Y^TUn&Dw*@U{d&Cl;M5k#F}RGOhUWH2i%s+v*^+L9n-*PegSE}J zv~D$c9|G3pbn-#@9?VW> zX$12sZy0q+*Lq_m-vH<>@-+>tc_ZDtZP4ZL+B|!pNUxJFZCk#ynKV#K9Vx~DJb3u;*@SPgxKez>wLi1 zvfVtsE5lppG1g9-Hlsc%Z4ut0*Rbd%@uNB+`tSol>3QNVy6S|Cc}RZ`F>mm_&8Nhh zG&(~Yg-5>WQ;2cbnPi=jUv#uL=|LV|pJmJg0&&_RcUTX9$gPuT#ne%3w%rK=NJb?qH7_<lg_UdhJ=5GP$RgODlYe+Cz9UjW+=ugDCa8mX!VB0xJe2tUbatL6vHV2V z<)#0l>*Dgl!C`}6!2dTU;CN;Miob54*7^U!REDy7^&pFJl+EIorPN6|i*5YJ82QmY ze-|Nr+w98^y4-J6UlO~Uly+g^j@K|A_$f3Nr+6*m>G{=kR!^&;i=V@TJ-^EE@Gy&H zv<-`K_NUxq=s^|&k5uME`FwPI=vNgU^SZ*L!|715^Yj~vCx)X^G^SFFMR#kpZ~TGiU!E#_+UUVs)W|y;-Xb^pXzLo=rGtb2AljVv*NAyY1= z9?O=(Eih6%W$1E0p6jY>FLf$fJxJ z48lCQqAwLV$5-NTiBZ8svW~$#c0p=0YOJ63vk#AB;!^IuvcUeb6-(P(w%d@};ZRAT zkx3)n?Mg~&F*e8$FmW%LGsRr`#qpJ|jtA}cf@%&4}alMOTo zew3M2c}5ikzN4^=&&0xxV-~drMw#mg+xqcgS)*OJeOY7njnC4KZ%Z2rSJv$TKF8TY z{5s~J7ry?(0s8yx^ycz(I(_+UdiKM2(|6x|J^k(P{%ZQY(&?)g(>wq9`nkpquh8LV z5E&z$XKFBU{CaGA3mtK;t` z81-$l18$OSgWLR#fR@WyZ`ehTY2@$1A(L9x z{FcPTkC3&B-bbP1&uk z>&<%6Au$GsXTh6q9nTsf_qjW!TjPhf*eAhHR`jY)=E-63lpoh+JNRt=nAW^C{eC>x zYKE~rL@8fvB42FRDX``j+x)Sucj<2?zS%_0fuL?a_?X|6VourDQ-81CW|!n5R=jO# z(HX&Ic*X#@B&W97cFw(f+B{a*kUEl&Hl1=mEI4uSF>>XiG*E848)1^4+Y1=l<`00sO?o6I%OTpyL0uxL@F> z*81L^^xs^)nNCm7r>jdA^->QO*p7}=4vTD}c@?AQh-wQwvr5PlS;x}h)rOSA|ADb+ zcYeYDjj=dLd+}p?Vq@_wPjMa8>kRY%=vu^?fF;gfIq#*RaYUwxM``USv+$YMM4@IjDMC1le zX+>Z>2OqqOQ5$=wd>m-kJ60`F<`Ygxvk;Xp2)BoyBCu6rLk?eAPLlCKjZGrc);IU; z&Iq!!1%z>0$)EW1nL!GDQn3dq<|eN|a$?}}XcnpDE&{xNogo}vOyBwf1*dh}CAx3Z znfmZ0M;AVF$+@7RJKqSmUJTLmFVIjRvCt(SR+Djl!4eba?Cd3vJ{Qv$DsT3KRCtL2 z^Sd1H8iyU*_C*8HU+#lAG+(vWu8i7PnXOr1br&|DNP}nWQGb&a2EI`Pqbw^%!P3&{ ze3l7>y4{4jo}$V5G;}P^v_qS5MofLP6zFjVji2JCJY<&3yGig_!@S`5*F?$@k;HR* zq?|;mJ#|I74DCa_cbfcx^KpFWS6TMWSS!2cp-eTn-EQ}mQ(LS@o)SAg=0%VYybJEw zP=XlBsU6$gZ${KA&KzyoqiO>XZ*FrbkY~XwJc(pSy|APAQgd(itGd`#`HKkxYsQ)^ z`bL#f2eXwCbA%ZV=t76*u~)SB$n6wDDGrseW)i5q7u92f%ylu2EdFdliAIpSrp{fS z{6gW7+&m>>PVu41k@85-|0N8v^sbD#p+ zyaaQbw$M!x%W#x;EZ!g(4AMctZPTd$0cr-}d`R{azbO+@%j3PlE^HKe?W`Bqp~+Bb zq_``98@uiuZ|Ez2`zyoQchMgE2&t$`Sjx1chl4FzM6jjyMHr%_4~h`F3w&kolfWHuj__FUeDvP+Z4{W!vgJ%A1~HB?Fq?&=YLq0i*s} z4z(d0qb<3aPF0&(9-U1a>%iYg;gJEeKFw-=Br{)WlWv@Pu4(XY zE2RxPE0#_0{%&Q`H?)Ooo;9}%9!hsk_L=$k;uqdP5A8YgY`5SQT;a+q-PC3zwx}#| z#;@6hM>ovQ3k_yy-NoiQZ%im`(g64vN3|RKL3d0eY|1ui7(LEzN;m2Be(n2ulHv{+ z>leCh)?;v;to{>#ImH5N|Ha*rw0C^hAyR%y$$c7Lhsb|`$p?NP zK0Nm81nt{3&fA^1zeoA6&o8H!uP>$-rK8GSaf4S z?O3|xJUK>v{U2bm+ph&M78m(T3V>Se%h$uh`_suGPnJ1E*B@Aqo#3IHZyot)82JJ0 zI=`+5*hk}Fe1`Ej>Z-6p0-LfGjki@f4V!uacx%3&fGgN$GnTQIn!n9Nu-(_qfW=LA zHHKA4njMBu#3#>&hg_EgsfcvRTC$+ zHZZ4jIT__Og#ecU0cxg!*qDKSu^?dk0?57pRLK6KD;!igI$2n12U(yJGbbSjLnhtg zW9$p9ME=!;f1QE<_~X|f-Ijp;>mujHEAhFIaTCK&jG<6=`al$Kk{<2BqS@R0Stbg6 zqG+A`nuR!Eup@3_tNPLw+T+LJXqPcX9+`a#_xcQ)jvf2Z-ouhRPbBbZ-$?OMz6I}a z;sW5q#ZSty9a#HEuYo=)eS@+kj^yyDyE3J;KRDopNMfQNV6;2s;VcY~SLtR^Qy?2^ zgTK@SWT};Nv&*+~hi?xUBK9NMvnsHHn$mkpT(#MZ-CX+5R z?xQ0HJTD3hAvDJXzvT1chVzuwHB9id2Tno~kJ+=1c!Mqe!`4Pw5Vg0HvZXw#-NzM; z&m7^b8B0-=8H0cOY!eF#x&vsi(vhqT3dIcs2-b$RH?Iq>cf^B4W|r zjR7C0@N8hb8VIGZ93!}LVkvywzg3m2(>~bas^skP+j4LCZ#!-AUAi8RNV0P-S!3BR zkpaDruZpay(s5>AWmMg*gt6Pd%Wr@earhANV6To@64#CKQT7pA7qoE%-izsR2hur~ zR<62RC;l=PtzrH+rU7I?N?7thIM_CHB&{39VC_u1d5$nx3vnDxSbvsAPTY#w9-)b~ zWC1G`9=3t=H8d@viG$~`A}u*|ML@Hf8T*|k@1j@&$tfsK)9MNFJ4clubxdWo_{}m z^VRRCzxk_wJAL!@SJRuTi|O^t=aQdI``id&9MxF!aB3F?9%C!m#{0VhV{80W=ysXg z=RII;yUlu(H>~NK;4ZqYGp03c$cxu7%I?~>tv|v}9+R`a*cP1&=GmX$b zi5LD2x?AYG^UNw)XvQS@rrwgGw>xRaC$#Ia>8oMnjS2tV&f(pp8^vw1b&5kWJKRXt z(csiRde>6G^WT*%iEM!`FSz&Cxt=}*$W!@CIcs1HrB8248uQ!u8h*K-#<+N^#1moQ z@09TVR*9#F#Fs9w@|%B5E~EaREbf`PPsQ)QJ>mWZ|J!xtC$=uU0LJSIui#x>`G3N= z-{vx8>?gu(U;ZRx0qE%Pa606PEA9jMW<|hnX;KV4HFb1+>;)q3Gv!C`@22CUBfnOV zZ;okK4 zazR_L_h7tf?wM`nD$hbUz@n6+)t&ceyYpS-o5GMP%$f~Pl<<+fbRdI z3Qyi+$&ytLjJo6teqFCA^NU#P%)nqQ@O^hgoycb0r95E6hu}84;U*t}&2l#45udEO zX9ISXw+rHKw~b}*;qraU-v#mWVSJ77q2e3igVnjx8ocoJr+@kv`HwGD>gI%Z`f%a! zWUod9q8#F(m}JzYUM`~Ko0FpLZ`Oq07%T#Vj#Nvfs zE{B{hMd70qIsR}&!$uBBr}<>&6<7c-y0$7F0Os<9j6NKjX<1pg87uL?j!(dzTbz8^ zIRmR23F(+g<-5RjLPZL`5OoMGD+T_DvEhMEzCCI44f=|?Pns+|;mbF$rH0Czcl?^f z1(i>M7k32W<(C~wx^TgB9|$pp@6yAWFRIeZFF8<4Yv9d`W9VUyP>_W+KGLx){Ei#4 zF4wY2`IMJ&K)q0vt;+NGfGzNZ!h-}GZb%Y|q_$IOjn*CjE3rP>7Lgril0q{OQOb5S z^dSndc6^OHZ&Z-uMJ#xZ0XtAi1l$tyKI3EY;f!_xG2fAjMLg+egX2|7L!~_L${#>~ zxgl~4r#>Qa4&S)cAlXcqEr8QeT&XzOQZ?u-|Sp<_;k3xo{57ZbLUBSj5)v)Ea=@B+eWwzKjL)AgHW;7DSy z;Tv}8HOwStwM&=S_H*BqZ%a^(xS%b%UX7zzx}G5N)T^p zrR>SuPspF2`1%h6YCO*gAZK3HbOs@R&dz^+@zmGLXHTbZzWUqgi{Jg5>4)#WoK9c- zFui{D+&5|RDjIG+;ctt-C?{+LpG#HocpYcCjnln_z7_ zrdwfcQ|w(Z>fQ!^Es@}^`lIi4x(U|0jIjPbG@tSYXuS~}Yx7IidRx;_w}zIjVYay; zZG*eYwJXkb*yUq`Uz0K40KK7Jv;GRU$wuB<2AHnSxvm$%b$(!zUrfQM$9_{U$#cSi zw(dZ0<1cu(P3Yj8Hr13fEb=;kRRa3E+-&b;*32{i7TU9hfhN&}*LZ{7y6hqcx)K5L z8F<@#n?Kl(_(*r|G~>!GSY##(U-Otile?{0&PS^t3?}AOKea_AV3}D*4+8v+V zN9F0S2luX~z5AES-zbDDTkr;!`+Iq%pUnn47Ie68<$DyOIVboDt+!X=zj5;YH6<3s zkcDRlNfjF#KV0X@Ef$83j*q+u#$pjahRwAy>V6%e7moI(w|>Hmy9K=3aBq6BPdlmr z72>MCWzmcUuzS-Zp8PsF^!T7MyoQj(^~bL(yttTNy?Q-;|LoQD^u?>`jdUJAJefZI z=y*EZa}mA|i7xd%+~4=Ym!Hl$QmkIA%bTu{^90z{+jr7ey5e5zJ^#-av9qYf6JUpX z_a}wySXop%=fA>aM@-x!^^;wSmvd(p%9f|`=o5Nn@BZ6q|K8i_SdMr?jrzOStuu_9 zna1bBbM8h7tYyLqU+jQUZ`OoYM8;m=y4{*yV4;`T8?O7=gl#Htcx%48 zX#=*|-2`agWMkPKTyBf){Q&#)XZ-vWUpK=~i}N~sD1WuVZ!B83Z02JF85#bZ$*ys1IJpWh-vDTX^#)|Vxn*)V0A(dl za~yns#Z%0}vzE`!py-l!Y0(U2i|9Bt4_4I|acy8Tw5}ZaL@l65>)BCcIwQ?;+YE_} zK&-AjwSXpmay!tcaxrsrT|Q|NE2TYLp_rS;f=8H~IC2vJTR5_InIv=4hz8>41_KwH zoNyxJ2`ZN)65sY!i3Keo@g?A-ZoaNsdGbpMJA6sz3AA;%sDeV{B7TUM3y+`tlI&hR z;YGB_T`oSkXuIs#bMhx-+9SSD*G}z$2N-5^H5DQ)3U~7&g%&E7%3^%6DQ7GOEH!49 zlAB2EJaty(bbsaJ1jj}Y+QoNxj>8bm_5tPCgoG-Y6Z_EaKKlvRda6S%u8D>4&~Zul zmRj4}MBrZsQFm}I+EJS2HnP5~Txfg)>BI6{F=rQ@Y{(D_F^DIeC}_v@9bER|8;_wg zpz~Bpw4B(jb;{awG?$zAky;KtB#VK#w5>&qb?4!ML{~YuggIBG?i`qDM|Ax$SY}XUZmKf#BO%#Es%OPmXGwXmkk!QO-ewBcH1a- zyMtRT_Rwa<$DErdu)jqH(9h<9quRO!IS0h1>pr)KL?zWmzbA)-lH+!L#Db3q4QNy# zwRb+WYpJEYwl~u|1Sw1Mw(t|%Ay$w$W*1fii*okR)C9WoD$B4~^td+=pW8(q*nx{3 z%PN)5f$0Pdckxa0B4QtR$fZHuz}v3yCJPhZwG-8DLrPW%46BzvgBhh$hAtnZm5Sk* z3qWQ9G>jEnL?~yCueE%v!maW*#PDf{u>R%G3t#_%z&HpRZyM-99$@^wdv`TmUA&&o zPG3#Wo_;rd_2uuTFO{Bt|Lyer`P1q3s~0lkza{QD`JAU~ialuzLVJF53-q~g9mC&c zaINl8w_T8P(2_nRysy8X5<}bG#eUS8ZMN8L)0_400Bf60YuR1kHvOCAa7MXxw&{)X z0oJ^cUdw>yjj3T9uVIvN1UBwtR}3tiir%P8y=V>q=VMzJ@!Ld#t zEa-3^>3ed3&uP->`(*PQm@La#)VUQy$0zf6boo&`3s>*Fpmo5)7Yjm1JQa25#U&QP zSfJv6u57C|<_Y~?2;yEJi$?hNaqpBj;P4|RV)E-0_wG#}JwBO^kB{As*z*5hyh4%6 z@(RaGrPK4b(~DQHrx!0@xebmF9!!@Pr(R?`J~>f2{iNG8@gHIjdFqQ-8T!?S`-xM& zamuR>@yq>C7Q(163w$h+@ft&3m&pHkv1rGl+UePOr87T0Mzgt1D?#TW0Q!OZm+B|A z-@f{8e~%H$A|DZ^oq^3feNVpduIIp}KCs|xy;%c(5xaB?%bw$91*6V(+fBS-8*jbn z1zgwLET>@`Zw+_R8R4ey4EA+Lckf&7b=Y3#KLmW}az2zlylnF{Kk=0t*rmcr&>1|~ z@WmrvW>JOYP$3}UvN}c`m)^a>@0@p>Oe6Y(+;n;_zJ*p56PF}5o@AyYZoT$ODwfU8y z1i$>i>vCMQ#fb=+b?gr$JWkK#B*L&=cKQ^<*z8brI6BW3UOScTXr;rLa5+l!L2iDF zBO-iBSTHjcKDxvU_+sY;B%~CSIJg)&uBiFM&IOlx=P5K6&6J^{Jk0@81|{eVE#=xD z{;dzLGPxMNdm|PXUyCw6sFz*9vA5*n_l4iel!zRxE0VQGoX&XaV3}0_#8Vb z@e%0Awa3O1SnLOwfI>vYl%ABO6CwwA{g<#P6Hy!h6UKY}+{niw6Fa+I9PlZ^my_SHa2 zwl$~9Fb~z%1+~EA36C%%i+!J80v>^;Vip|V*1$*c>_fZMt7Ao}Ja`;Ig;yG;$XvE^ z_>>A^sbwW-+z9$+L{^fZ;M%BU@#pq)Ry@!d6STi#xeE-@%2}esaztAPPmXV5a&L-( zy9FQ;vx~6-Wk9?3@nO~Qf~!3`W-~yAyAw!>vqa$q$%noshi%bfn=*zrswkq0j+xFA z_rhzf;4?e9cFt*!>UW@Xu$0PPIr_72c9D+wED~(Ahw!wA(2}PX2tcuoR=c99_rS7A=@yK9N za+|hqN0U$DGbRL{4B`FDzx;XO>pvWz|E~kbNF*L9PK;Y$Zw=Dmhgw(X)A{KO|0mct zU;dTT58r(;Js17@3Hoe>A0Fs;ZcJVg!hq{ciSw6rv*~r@^>myIpwQ+1cQq#`Oo`HGdrhf359`ZGx zL=}5+s;e8>i0Ay$wDzVWYdU%aY@U3XSH7bcXu5fxKiIZ?wN3&WbsN8l=WU=p%N%Gn zU~F$7^-KzVyKmCkzsOD6zBY4UkuSO}AL(Lk@Io)~I%dm?t~zemv|a5sWqgWOpQR2f z|Cp`pY+C~3&PN?&*KJ4}Wo}7v+qBiM9V4BzbJ`|L>{Mvo^bCog>^+JbQf!J^cq{}W8* ziO0ebPeZXFbg-XS`;oBm(@rXb`+JNg{^y-VsPl_@wIcrq=J{FdSYYC*seS_OVDDgh z_~@Y*toC?~pvpQvX7S69N=<}-XP(k}eRe**Iz7|e@Xd5~dOm&k&DUy&che^yKk-5w zPlQn|UWrJ&Cr2z~@ruH|X^;6KZQ+Lo)Na1ts5U044lHz`L-}6ZQ!KpVkVUOmD);%T zQH*3NxqHPvDu;ABaz$o7>yUA`7?y3je)yD`o$+p3*zV7JmeapQL*W33) z1OERIWqc@~c-iKOg|B=6=l{$9!f8qe6f91TIdgI23*crBC&W03RFP@-u4HlUn;6>p zdIC7t&L^;tZ?$9I72V>oH*L=@*D~$kxN-5zNg4w)>!Pca$OOuCDv}ca?Y7dvGnh>XDsWY%^G0lEi`~$8YAV}!a5E>g?ba(gV1e4ALvA%^3wPG zG@(z>{I3`|k3F-9#Eo-b2xR9+s#AbtH72vGtGpwZs444>t~UAqpIkUC;me;P_Wf%N zmns&1-s<82(kE|xzL9Ur=VIf2rpl62x@|F3S(Fh+^6PfS9~T%9vkYY5s3F3v{V+K) zPG~B}qsH>`UCP$cK4V2xIc?u4^g@Q)1a<9j+s9YTX6eiW9G8^e>fp3q*&xOSaqrcV zs;5!cwf~Tm2?W}01^8lHELtqw^lv#(S*fj|bjck1!U_VINPlg%N3zseNrY7e9#7@K z=O3Y=8Y0Kv#4nqKJH*o4#H%H$0ESMFtp>{x@)RY(5GVZmj1Q3tV2RHqSDQ$u_A;X{JH3;DlbL>m`BGZ8xOMA9^bQ2`OqFSi1*+8xBqP9{Gnlp^k?{A2d;N_ z9i1LKBVT14ew^-sHP%GW%L!)T?S4*7kh&*#@nbe9>9kZ_=CX+0ak2G^~B#ew$xkgJ|30 z0nxjzJ3AR{zJyLZEh){}at-k@ z`e~p~w(+k6Ls`l@%doF1W8J5~W~~-*`IxzY1^T@I(*eJ<*Amm{I~a3dBiF$SH^(;4 z*?m4%>SM0^iG?F%nSe*2c|qvqYo3z2^uksC2aCIl{9l&laMFMC=5o5aIQMG?Kl}8_baH&;R|@(`uzk(n z-n^TBc=dXE_Tts_^3}N)(TIOvU!;EZIgD z6aRM^i&u{y9xC?zx^MGtdiDBpdiLsKdUdMU&M&9e=WoUe$C-N zvC8gB&GhW$>*<@P&!=ydcvp~sk?zEg#-PG3&%E?!H<|DaI@ zt)71KrW{yuS|&K<_QGw;f#8enf^YhprSOVqy#)`9ICn5M7K{rPow4jd)4TXHx zOD}M}JYbg%eA=#$nO%U+oj__g#fNM>|J|f}H`rd^4+(!L{~yXPUbcDq?Z5c1@7?>K z{;&T_x>kjuWPCn(!Y418cGphIF_J8H2^uBkbR?wh!Ql;JL^jjTx^}V@+$^e_=`a~b4Cslz>1q-b!qe7Qu*k~DBM_RKle${4QcUHU*%jM zi5!}(PV83HhZ9f!X!4Ct09MWg@$HpVVuyd<#B%*;qg*JFA?3+17N!ym?T|$)76rJV z5gvb_3FL&1f8r>*^=0pqkUsqJB|1K7DR+!a_$0HA;zoyyq6@$e8~%W=|^`SC%$aZXfZB7QFD;6#)njAKfY!5OY>*M7d)woy0%T?979^ zK*neT*vf&xu~wZT7hV~OGF%&15}k;wg3LjraJd{p<0Fju*bFex(DT zlU?Pot0ENX2e)JL}gY`N;^wxy*BT*FBN6+we~}~ju}SBEZPf= zL;n)KvH_51guu6~33l?)`ji2Xp#r1*jxbwbYcv+{(--jUVQ6c4iki@(UACCbCu;}x zjVwazDet<@$2h(zBh-ekt+&TCxHuWN~MyQvkg7 zUAGb1`2a3qEX3}#vu~j#GfuwEZ$a81F=wuXu2T0ArI8s2tT|^ub;Sav%cnN-S>MVq z;vHytinbC6+yNyX<_)=u1=_<3+QkSnuL>e-Rzdo1@oB6{6lKRSoyV%7@MbCfH~;NF zh5B~|9mvn{?-leA+17o?lr*PhUi)Bwe|q@n(e(M}znGqU^2_OyU;M-A^I!cZ)5+tH zrh~%+&B-6+rjaJ}!@Vm(4ah2k<2yGPbHihVo6Zq`X!t{xJ!| z{*SHWkFi_Z5DT!&7yNA!_-(s}8{@*?P4X>poBmz=y-%69jf)Lm!f*0@R~fj+#U1po zYg~`Pv_9QK)QRJIUAM)Ke3vY7rN8-(8ZOW}UEXfsrt@_L`z@S&DKq#;qu?9xD?b}L z1#8~zI=kD@I|o@hgIdRa-T(H!w0ZH9cUt(scH8kA&vu==FND#bsn0c)Eq=#^59D*b zea&cyUt@y~^QO_K%dERU+hAMyBT(jC{>t~#BY{m>>uxI>{-TSQ+u{Ij(y?ri^Fzqp zKy26J>iRMJ%<;Fb@7=(y^1f!X5pnG{-fZ!0u&J@WY(VCFgi4XH>uFdk55C+gEVNAg z$d-Qu+ndhc+?%fM?N4t!56}HP&y#8qjNzKvyzw}i+fq5NHRM%>=yGq6ZxlQcg{S@f z`_m)Mvz|Qpc>46yPp6MRdMy6C>Gbuh>HPeBI*{$j(V_fg(TfG57q8E!=PypD)ALK; zKY8##-%#{r{8)M)KYrxb3SM4ZOlN1ZKiHSgM_vTuJk7!ri)j~EdBx$==dY$0r)Sc= zn654_E&tW0kEdULdNQ59{9*d~tKUzL9v)5q<$v*?O@H*8-^li0+H+Z|(_R+kc)j7P zvrENwH9b>$$&*``idSXOPWwD7-_vaGxkkhh(Kt&SAAE+04LCa1QMS zY*T(0Z)OHFv+TQkGWclwgdv6x6!fA)*7dYm(Jo6Ls~29?Fklk2Jh3C-Dv!fuLoQh` z5^WVN1jH8I0OfN)>zIo_bR8oFlqUWZ7gUFpn8hR6SWuaL6xuhXy=Uk09H1^xF|cQR zMAc}b1bM4da6~LnA>(4eNunp@j)8J2Mw^vyzNj*(WJ@_zCsN|DnKt8e0JicAPMG#W z%)a4Fx%i!7VzwlHq(p{*^k z6%6xTS9pvc`V&gDZN}CK#y*r%wV!2S7Zk5>+d<5Mq*}8ELKU3$P?DbYv-788un9Uv zBsFV5ZfCaG(+VysaN9KNk zhrD3M23|9*7n3=LoM+-2=F%Q1!%)iM7p@!|KU4-j$jIFuWdj~zgS7(#+IZWvyBQ$l zwCg+S0SkA5lpU-`VzZEeF6}{mis!xf)X#M7lprWnJ_8qZtE6otW&;RlD zGyHU5Trm&4n%=&-n9fgMPS2ixGkx>*7t_~YeKmdc^_SDP-+VD$p1qtN@M~M?b3NMI zJMc{%j*(5s7|u0R+i+6?;8^qzB^cQMD?rNMOl!DJz75u`@Ka!2{+Kq-v%rd;_1+UU z%D5w}^&8*ir}?BYYG}`KR(zoKw?fI*=_a^M?>0Gblg^q4J=Uq~xz&CpTYDd6YZ!T> zPUE8-*x+x-R{HaCywsy*t+%EZ+^AujY@|DH+?7}IH8>Nyfv2o=XB#n{ulZYa!^dD# zW?i;5Z=l0l)69o*P7A&A8y3t;g@Y6xyK3X2lQ@5lwDh9nO$-QUNu^`nl8-68PRqGC zcsvFTZ7?Wg6?;LXcvAe;49De~PZ?(G208})&O zHaXA>-?_g;SR>n74zhwp=Xx6D{!TZ@B6nd0o3fS*8)#smZ%cih$Fi;88*GT5_OdPA z3|Vx#9v5)UL+Q+t5m&Mg=I`XLyyJsCzY1~x zfov5Vm-(x=Z~O{C?0K5YKW>+dC#D`fiaoD4+{!t^;grEzyDkRC)r0Ie=;2(pC~5TJ-8c~P5{o3(eDqRt$?=R+FB=;JLn*}tUR)cqT!K)50y|BlE*rnpWk~%F-rD;cA)BR5K z(tB?&)Hk%hOzA9;((7|1iM9kf2iCmnvbI~~rbhjs*Ysv+9Wvn?vVw(oUH-mw!`<|5 zi|0BZyGh<~7oBdCU2rEKH^SXw{m}5C%KSscj@NCT{U2X{@@IekTMnc?bQHyWGlQKm z6OHR2F1n#EDMd*|KK$ya@)Id1%ieSFYA;97zTu%EZE2*mx?Qu=o?LvI7+KN8>~<9CS5FD=eqqCV#&nr< zW|inz&wWz5Abc>!m;KR3F=XRI=)q%~GL=;dRq~=KGciZz;-Va`+^9NbUT-*$$U;O3#AeQiqDasXVJf9f{ z(VmPgNaRl9*>E6UB__a2ryG z?(Wied17|IpkP@1Wg!=D$a1^@q0yoo@L0Q4*QGe}?IKDF*AnFN&GCZFI7~b^2c$2Y z&3?_c*Ft4!mxBJqJqfI2=>D?r zVp|V`Y7cg9xhlh=_KjGnkKdGEQ8GTP3$7zAOyhuM_7^YaqD!uQsW1IlcJL9vPg}cm z^U@x1;@3AKPyo$K6Lguu`P5DsIr5@~r?2HkCUu%f47Mp>LMg*Bx@}4xByLTR%9^a? zAdxg9G`nCRE!{9I80@KU#WYJ4K-!9Y@a+zRPE2Mxh5mWr>u2~WupCDVz~VUN6+7pr zucqfuznY$Y`@8A;FaLV_>WjaczWe%%>EiOj(^0Is(c&9Bv#**9LD%&@nhlL}9FU^B zEtU@ryUOVDcg1m&oFBUN(fRKLIMLk!cE!A=x4||$V3%$4?y3*8Y(BG)Teb~v8W?$_jQuvgkPTYcOfUSj>p~aK zyxnx`TB1Djj)o1J0dD~J&DE0kT&MXCzVyOl?y>1>jfYtQ44`yK7mGJ$i^{sFsRNw_b04ocqAbb0y4Pk8a#L0oV z$B(B+#|P8Hqy6dO@u6%ac&D=Qp+w32R~QRlD3uel$}p+uC8<@Q=L(J`^NWkScKbC!k(wj z&Q#77fAR8``Q(hw`w2WqJ@)m&LVdVW*8d3iMQlAxAwUfnDY@Q4_dr| z->^fcVMAB4O?r`&?~<*7wj5!*-gSQsyZ8XIo8%35(V;1BE9nHpadvsta|w{pl|#O4 z6SK|D1;NU(7_}Q4h_qzNL=u=`A7daU0b9mtZHcp{WzB4LX-bjbp;~3v6+Z^+MM+*{ z4AQB^v6zJRTX&!Z+18rp+`Me}HbRZflr-igCN_`Jx!a~~hzi`A?VLWZ6sIWxS}Z%q zyhY-bfh6U_;)t4z-2Atwmshp0%6R#9f>SKJy;rU)$9Rqzsor^cAj8Auj4%0Jw-PuH zX0^<@j~)6@9j3DCg>E3z@Ppq9f}K{=v<<*^W0Yow*Qn%O{4Fxiw5&3A^HfW6XkGOH z<|A6IRhReaI(D&Vzp9vdEUoj3(n6qI);z3K-kfZWGCPOzdA?E~VgloCq;~r5@qpUK zi_Ug|C689NO6YlUeyom(ZCN)*>-13TrQey|HKb1GlgilACZah`A=zxnRxL!rfn>ht zZjH{`LP_g7V_Y0+6{}oiU;*oHU$r_Ywe>i`m`LkNZ!-Nt}K5t*!NC zDcfmdY@B2Vv#qb68||ApjjgZ!TV2Act60B3($01n7P-T?+O==xu5w1bwRgK+w)Ulu z$>tw?lYN%=*=BiO*hRLsT`t!R>zL!G-HqFgX}y=#?%61ZZG-<0w9UW9Xl3247Cv|7 zN2;%1vh2pUObB|~c{y&gX~(wJ`SHv8@p)l^aH8)0X^rvcR%CZ%ahe}q;Tgr{HYcYb^P(I0=;55o@llZ02U`au}q zDx*Mt(f+xv_ntm|J{~`L>W5j6wY)gW{UD}>`C~i>(s>AX?b=oE3eTP%ji=9^`eC5| zy$yUutok)Hebzi0mtVZxgRh(ikJ~}yj$i%OW`4wDyv8D{Svh)A7^8CKEEt{S$%wId289i55E3S|K9&uALw(C z`8S9PoSLo4PH^93HaBK-40Bjz!RHg8B@X=f;U@>Jjm2T9ot=1_?2IhIec4n$wiC0~ z><|%CD=d7RNbpflaq(3#9*s}#CYgtxXga|LS&Mu~Ipz{)yV+UyO-gjKyzn=&$boTX z*-v2$@K>BuhC@A^IQ^TIT6{rdqM4GAO|+dgEjfGx-?`u*XlyjZnU7iA$`v16y;11h zf)5bDUny35z#NLp7^#O7cxCmzgB>JyWO7ln{q&_D^0N4UctP=4s}6F~pC=)9vQdA= zE-Nmm*5oHYU%OVz{{!P2UrYbAelwA%4M(l^(5LuWnjM){n)G1Za&=tn>@#+!^<1(q zp<@J$VV2@gzVN#aClQw8#U^~>_}hh2WrT~*agMSQnO5bc!sz&tjNHpsvZ=r65Q~0V zrt$VBv~m+;uYiM&Oz4c=Z;h*RXDUn*-?PY!XsFBQl0VMai1 zUvMx6V(gSoty(vmP%HHWqW^3ay< z6Jq^j5Gm=q<2 zW5AnAIeVP$SvGHffwj4A*ZD{;y-IM8mg7fHhRWS_3rJKw+foC1yfoIGF1+f+>t!3t z=c>#P+-j8vxn)H}uDHZvVx?-je^kiQ-A^G~B%Iy-qwICCdVeIRUha}C?!(UTEh@H@ zY#xj>a7?g@F}s6WYy>4xs5xL^tST%ITB)(eX_{-Uf*fwI?LErqD7|fLXH|~OQIP;N z8m&yT5s2rQwzX$t^Q$xuvNf3Gz%GffWgm7>Wa_DU%Pl*zp8g{VJTV1MR{AxWs2fujzjjz}E%JKZ@>3ID4hvSnEe>mR% z(VvVz`R?zHKmN||jgLS4U>rSrI-WhtpYFMOCBI4RQ{;} znf*Jw30vRXw%pj-^7(E>`^_mHYfEk4V2)}3!kc}wU0CeXGGlAo>is#?ZTmEw<+@#p z<+6j$VH*@9&c$AGx3e8=^?45Ei6Gk&tNpXti>;Q~Hp{2k=&t45cs$O-wtNPPd-1KD zw!sTGw$^LeoBwp(wr-bNvY>0L+2_TliYW(Un#R~m{JZwpPS*MHOLE^Enf*Kc^uDsx zyPM137(upw&5Nz&UbdKhEbAUaDE!nn&r>g+AXq#0-CQir!+2^wv%sBoIAMpFdui5t zDf?NzB|n}izxya4X4&=kQmj*aUk;cx`pCVBeM`^t%PiGNfqZj6QWn|z2IQc^b;(u$ zXa_t18%O>I*px+K6pKZBo16v-L$GF8={eo=E z)3LAL9mste=gjyMkmEfyzif{4;>+&i%gRmGeVP5>>)-u%dGJ+~V$tN3QmeN6t`P?p zH)3Pv(Cfn4%{W|pcZ;=%ZhR!#TFw9)3+}A++TCeA`RacTE23{W!CrhVVD||iZwlFw zsZfe_q*x(XCYfGdG9brd=y7IkORd#f%!vr4vI;!7q7B>0%#~gjspuXbeq0Jj&a`VT zVdr3$w{D0fWw@*zZ=0J1(TS`1P}@~IRx7u>nW(G&wiLPRbDsSD=L?AwTRxv?qj|-{ zGWy6x6+SH*Z!Q3N@RbVvh)Mz%>8=AB3H0L4$`|ht<>)c_`U!&27mc*M+3bBbtPIhVBELvq`1dq!5fSnNo7m7E9`%NEKXBdg8vLT?3Z zjw4TTE3RCYd%Z}!ywrSHF0YmN7u_SYd0J68R3;S#{PV?{cwas=~Y@20^IcAC7gJb?Pc>A!=-u!)WTi@(Q+S+HERy)4N zY-@SpOnT>nA*4rDCpgKi?O%d?RMGPxBAv5Nv$nzSNl{;LMFXA$8BxTG$A*y^HmJS`kaR`^u*iO^0HLi zl4q42u=ul(aOD)wX;)5cvy7jmW9+qW;n+Xv^usu;E5=zS&LR`qdATwzel5Ok!+zp2 z@!bQa>SNz>ia&d>u-Mi*q}I~C9M7ZGs(T#kBIk~Nd?9@8uR18bIjetnNlhznUEFV` z>6mX>cJ^s4=1=-5OFm6(udY|@i#h*7^ zLMK4zJ%o^iw99vY&YxK`Yt5XQwfD2n=1kL?!Av4)C94xgnW%fI7ctWS^mV`%HKe76 zXWvYWvC|GD4yd^`{xt1^6W8-&aTCO^P{UkGVd6teI9hv+z zWi61i#2Mr+p&}{S2But;4eDno=Q0p?q>m6?)c>& zVE-*Te%9PcF;20uTu~NmO?6#r9sQ1FP!aYqK|!=B&9wGu0g!jyWqC^L@luJ0J@*o> ze&6$eN66kwR$bSYjBQufZV!BKu~!xityxeXicRsw-kj%Ho(XNNz&#DyW}ol{{SuAw zx4B*jHI$MF-0wfq0MOF8#Um65xvyD(lWK%H{jBeL|31F!YLyLPHmQrfkeJOIaIcs* z8K~NscaP=%6c5T(4YK`yt+VM*K7a5xG0@C&@9#h18z~ zoIr>Gk@1_w780E&OdrCn8A6qr?By|4OZ|(yjS%G>E!C#Fv6XZG5mLgGl6o(ZpV=i> z?*hduW1~Jq*p(Oc)izfM+&dcVT6A|7Wxh_P%oY?_b5H zVe>{Ai9#yip^_@={HQ^Y+^T%}N~NP?BK}%>Nd~81!|lqpqPYs{XX%x)+}qKiHqu2e zCk%ztZ%cWATQK|M0i!2xrSlq}pg#8N;f}>Sne&w@dd~Tcul2`(j7@Z zj*mP@uCDz0pwjnv+}nWb!Cf}#na7+<_{tZuUSOLhXlyASF!6ch3*^O(f;#G3RZ8d%(P7oB|^;(iH9$<}&OW>9zm zeFZAIrN^9}s!SPRB+KPi54u?7)fN;v#id~r__024vAZs8bLsH4pQF){99d#sFc#=b2)(rhhKJi>Lk+ac zJje!@>~gcBK>0`5vS!4a0dq}kZglm5PIXzvN_Y;eM@MGA#>RxK+CT5zT)4aF zrI@DBtD}@xhzrcOIoc#2tYylmK-C7NAOyW(n_d1T;ML*!fh`Mg=%}8Xc3+ye%Jye5 zmM~`~G8qjjGH&Z=H)znDel_2FD$;0R$oA3D(n zQ%6|Y-n2;nT6nwe4xiseY3)_$0P20H{ zcw5=SDC!B?ClUsQ9)QeKa~NfEF~s*Ap8fedJ>UHocm=u8G>EM(Pv|#(iBL?L1Vxx@fa)IHELCM;J^$JXom45mmZO zk-IJH?{@8XYk$(vqdCwi2}n4jHDr5Jo!M80GX*S~@)k`nk!9;dO>CNEPwLlYqS>M| zeSuU>A{8d%xBwB?S-++fbCbc%A>dk>F6xqBGiMo+z<}q665D zq`hDo9@3DI1Ot(wYi!Q=GBWY&09Ya;2{d}vEB)eDa(uQ5;tu*NI%)#5+!1~XX9jhi zNYC-=@)3Xu*rNEPXV$pn3xA-8?&sHE=CzC>V$2B#Ef{FnYvNRB3C{oH_Hd?Wt%iK` z=Zs%O?aXCTPiOIPs07@a-qoN;CeV}FETar|Dwea3zJreni?`gUtja^vkP2EIP8)`B00+Zw3pEr54^<{Fnwc@-Vuc%NCF5ppLH< zT!L0goje*bgtOMbF{IJIE)*>3UNBk^a^zA8FfuW4@5{5iGH$qmbB20zZkM8FMC|2 zp7!u_sr=2c%yps2MMFQm?YSqhfUBof6NbNyhA9`g!sVYU^T{w~m1pe6G@kvy%zXf_ z-c4Fr2Q~M{l-RUCfsK>r)?EJM^9g;N_9|fWUU8}L&&M?$=$(7{yAw9f-SD?u+G;sB z)gHuqr8=`Jj^@uYAFTaY){MO~GS+aRKDXp%(e7!?NqY(f6qT0fW$Z7jUc86TIyRtM zGj0X6Y_#~eIDF_6w@ogNW^_?8}&n_zN8u>Hn7(HUFEa7AZETRYR_ikth~Wk5zr4 z`3dhmOq0L1782^8g*bszla;^TqZLYeT{W)QcScK(d!*bl4+SjIUFOR^B3bxt-Wc@A z2%ViQepl~$2`EdR6;EU#>)WmGxPfkOFMT${#;yE$*?%&iQB8hm>_-2tNkHrUQsrO8 zGG8h@AN1S|oPGYES;*|IMEC3HCf)l-Zf5cMcAl!)>aV+R#g-_vQOyc}jD8~p+$^qa zto`C5ARF>aRm^Le%j-pN^CgR2d6+@G&;5=Gag!>wCjouZpS8X0ahgBx++=TFud%P^ z?3Xtqb|@l{lVR$OD++!Z3gQj`%Q8CvRia4;!JdqC)rPN6`)|*P68marL`Qw6mK5g} zCN63+P{cb%%hMfHG0EljfM&*}xi74|c7n~a@C!n5k`I_$#2VLU;8gU8!D>krN^ z3#}hRHE-0J5S0|r5h~d|;hZe`B1EV|r}+Nf=F5)WxoV}+ij*OR5BU<-bqG0 zal|j5oCw?8B{F=cHSo6*#@xKFa=S-s@ma_A)PKv`@Wi>glBv2|$i} zk=XDHNeq)h0KwGFdqAskOuPMCd(pH7u8f3(`RqNAGDQv@p)Yi5XY~OuH`F*$(UP z4nLrE(8yGffFX7Nk$Amn8%f5VvN+{DQUX zB7>(IVMZW~@cwY5!_Lx(>@#h|9+7H3hkZYT1-&q7k)OI3)K?MAytrO8@e01cYLvui) z?S19#Bo`tZ@!8&^Ia=4VU-lIX-bTl=UU+d|jS;PBnkYd%67`=e4XE%_Qv(PT`Nya3 zz8VT#NSqw&d=dckf~#7uAd?V7rar7mOu=EjW5;!IyJT|X@bM1j z%z%frjz}}A_D?jeW9>+lG*Gsc-zhrdhvyr~@z*7(b?^m>X-AMqx1H~bg2k-k z$d%>*vs4z}S%Vj-nH?YGZ7FxT^()hp_e(t*-d}%z&92Td!d&m1eXa6+d0y9wol~f-v z%Z({C%?I*ECQ}Dn7fH{cz5|D&{$LebYWisTdZ#nKB^{bUzY5_y`&g0uxxlkS^h2g( zfP^=V9wbzSv&CS9zC=3Uy{n}(cTTmd(wh>`JT=ld>Edh+aiPul(*9Ncuut(>`E<#- zg<2z-p5Iq(glY1&>ef|sQEcs+^zfzfd(~Ypv=8+RpH`)cO_)gc)SY(?))qMNV8%^Z zvL)Z%dnrl?ROhxMe{b-A^1r!kQRCY@0C@~pauN3Nv^(d)vR4~n0)Id~dO5ZB?t~{Mob;%{) z@JlBX{lxCeausT^(`## z0}G}mxo;WLVS4t=9qrZgOeTQLZO)k`+^g#gE6IP=AoLI2qQze2Nz|D zx4%`r>~o5VZX47zm*6$mqK5{kNl5I+ib(epn^ui?poeta=(x*~+$8k!JolU2>f5%Tt8O|h9 z-aB9P$m4xpR6mt=`EGT%y@~vhES8K7?n67us?)dp7VbL<<8I=;s;KMch1x)``d(oy|0Da|Kk~~3=XL7~jWWeZtmmIt^8AY>I-$NWofk>RtA`f2@sIYtP48 z+pu$>@G`TS&VeioMmD#L7~18Ceh%3YMu?CO3+ijq89OK~?Ha$TY{UA5cyI~{=<$v#W zOMNAuLHM~OgA;^1eT}Qd0`t97?ZFKD*t=V>jW5YDJ~J4Jc>8$rMJ~j*lhQgjDA`^h z5&1FdNTuMOUj77b|G6zSAs@SjP;9tf+MJutTf#fHMz*|vLyMKtC+rhn^3JE!ndSX0 z+F8S`J7{yJ#b!UBCV#QLv{I}!cE#Vl|CZs(0>6+mvZo=huw*^E*su4K9QFi64n>#z z!~WqFI`1>&?uI!NMDNykTFiYFd?MW6&&LiQKv`4ea1=51l>Vq3V#Z7}aLYbiX^YSZ zoC#ZQCjDC;z)=x25{(Rq1R?h3+=*?bAZlB=yMZ=s-c78~ofO#&Try&(kXVZ#tK-Zz{{tWp zx7j%yHZs8!eCW=SCJ7ST&5R_@r#Vq7AOVUXiV~Olaxj~VyE@rGgJ9(T)GDR?g zaU2GK!|4p>>H8-sCLP%Kbls!^-VUS}`!Ktg6`ioy0Q<6GuZVPXE-Rdn+4?^reu zrb9nIY4Wj6%d-Lm`_=d*gm6Xu8N zsv%w)n?rlRfX<&9ZXNK@RD(mwI({>-D z8!cZ(8wqKU3eI^Sx6UsM{jc(cG1u6n!Q@QlieR8gTheKauoTaA4p7@$pJbyb(PE7} zu;DfBQZ>1rgLi(d=R0W~2TnU{2T&bqLG>x%v>uvpG}I#MQscUYhaY%WcD?ESFaCPV zGT-Fz8~te6V@g7$&ZdycSm1OMIJT55Zp$o&Q4rg75w4#n~XiQKN;s1*_5b{QUFQsu;l(3%Zx0hMIQ-!8UY3-Lv&is~um z&6~~G@fV7^euLO%{VsOOJ7Fhd0y>RH$bEnprU&V&|F)~9i+BQiv*Bue$+CDaMG6}l zEgkXXdeSiZSN-n!)>&1s{kYRay$nBS8)y@jx-%V}aRm)2PZv^*vnaLU$k9O|n-Nq%805E26L6t23_h z?kGvU#JiKhVC#Vv>US~&~>S} z`lklFhUsr!pqTNwfu|(GDNckQ_>0vefrz`mtOA#gKdE9A@w`KU5^Im8=&luK{jz%c zM(SO<_D}z4p~YTLCwQRQi`rZ2?WC_w8z z7N@RkDvF~%V4Mo&Q?cAf635+59K;W#obe;fGmOr%W> z1*BTW2rc}vXt4ubv>Utn&@o{pqcf6?@ z!rq}q1~+lqwv$c4bjKzRn>SGRV3?Ehn?uyqs^{QJZ8%kZzg}?Atlhuc)bckVNM23u zyK0(M81Rfco%(#ToVXh4fN}I@z=geGz45FZS3qxJqNg{k&xmh|7E$Z-&e^WOb;74N zo!gC#>A;*1@=5jfX5yzGi4{C4Jg1EcmU&kCgSaeSV4hmu9h9 z8|*CLZ-+cJPr6YVb)WLRnS?p-S%Omu2#txOT#W4$`~-6t@2AzQq;!pnBix-jj0BZBGJwr?M3 zr7GS^8P7O_HmU9~45Wo#(KqU?D7{5vz`2NJnad4ib>hUOzOMMM{+m04b&=aibR_(MUPqnn^Iz{5CGv7; zrkzk$H9;IpZsa)qPg?4yO%ph6Bsx)=_%F3^jqyVJNzbzQz%NhDrU2Ke=3r=3fj<8& z#4bBI(Eg|9Fcnp7se|dTFO4qwlf%dI7Jb{F;q{1cO&i|>X>{2gs#-rj-ifH7=- z45{PjPmy#{9>i$ooru)(ek6BO>$MZ}mxDxXG zFMQ|qL|E-)rv{8z;RMXGHJ5E=$*8MYq}yS~%G^|#IG9#Fj8>2i>nen^FAuaSEW%9w$;%R2TQ600m4?mA@}fwa zav@FT^=Wxk`DAxWQod7~eLUxpI;qGwEr9PzA4L7s!dD57jDDOY&j5F&-2B4tO zucca-eW}yvyLQK1L{7Iy6Twn(Q>-=2hIJfD#Ol{VD=nXXG*!$uik6gRPR9>0+98n<{{*KG*V5K~R-y3}fvM{=taFStv z?QNHN)8dz2%#PE)39<1NQy(SgFYlae=z5gUW3A>NFFfd1twvn!-aIj(H6Gmd$0lF0 z)>YVc(RDgwum1@;%pAM$`I4BlBQ(j|0_7yfqogS~slhUTD;Xdl%wKs>Ab_)c)W&Fr zuj)OeS1CR(7qIO@JlOYNe+u@CL?yo2$JaEcWUBqHIUK zcmBf^=!hX*##o~Bnb+*a$zOD0LDaZAUe&lXEKXv$gdz`YOF{PFlJsq4XI z8aGWl8WQVZ`Q}$|Bl{nn{)lzzsU0i1JoMrF#pffkIdAOjeFi$5%{S2XX%g8Mu~6T` zA}%T1@Lk}Ycv+bb8{OLPhhJFYijSa=q9F_vcG?>AU*NlPl87P~;P!aA<&JIb#6bC! z(00V;a%VV!hOZ0el#(dr9A?PQj?X(kZo_Tw+(`Iyi_xKliLT>rqAaHOMinp}B8~y= z)G6lkvxAnj1Yd9xEPqX=2)-vEs-5ENEpCklS>%=9PBPw5<41UEnVw6Sy=T!e5c;Rb zJ$dLalZ>CmuWxWqzV}Iz;z$l`1~tB7caCn??;<--<_7W)L3z|K|Y z-D|d7)=^Q;1>$C!RyD$wsXA}odnI4uwZzkNoF+j}rGfObfbdbwPQ&qn+6V~mZTC*R z+WJC1>{G>(jq%!}1Cz3Z?>8hw*YntQNyXu(OI{2TvL_?Hzy0i-eR*Tyb_4Qd{t>=M zf;tpMep8PGi~4$qSz{Cs(ryh|EW0AJVla8fIY(II3`vJqW|Ag%6g8`EP(?LZ?6I%8 zwc4Xo@?1C0s$xG>S$SXP-@gX=a|$lfdx(!p6}Q9lj+-|bZZ0;{0s}ERk3W9T=q7TR z&j;Hu`^Iy;UY%N4d}HUw;yA~&>fk<8b^hVnAv;SnIN-xhG2;a#-v@?XW|OoVv9sN-T|m(jtTG=jyW#mbjgm z*6l{SoY@$#7>60m>7cQx*lh?XjG9;589|9$PGmF)gqu;OE^fb=YCzoDnqG>0YcCR$ zf%K}^p5b)G5V6d1b`FU_pnvsW?93y@MDDhcxCktjksYg-9*-sM{8Jvls!v>4*wjJ_PR~b#`%a&LA%qP=`TZ*r)N33vV>xHG;2ANSbk6ke?J~5PO0J!mw z6dIJ~81d=@>u|`r7(sV|*XzX~`Bfpv0D#q|)jBzKQwHyMmwWE?r|w}#6IE|MSNv>s zdt216kdeXUAzTK+@Z*0f&|_|o5i3C`$cb>n>oUBVKz!!8{k(^>{)=KuQzNejxYJKO z$tp(Q`VZaQh@N`BI&^~8{`|$4@YZO(^7+~QOcKd#Z`ca>+VI)>m8_T_8mpjf0rhM1 zQT|IE5wl;DOLBYY=@ai291X6yTHLc$<`S&;G2#{&57qNNwJgJBu_blat=c8HFT~so zExOk)Z884wWaV4nsa@?I1aOHpMo#_x*PHmhB^@s0QV3yO8){Hz zTt1^bz;M)P7AUH8J;O~Lb>RGJ8>Ml-r`M!L)CqFzd)L$9aU3=oua+bGZ@xWTTSivYh_-_+ftm z>KA8Ew#SpnT=&h${Y?^;;(|?nlTljx+*ob&S(RvcR8rQuL!C`Uo}C#p_B7Yp$HJfD zec_U78e7Q&g<8y-M&KIRzbn!D$8jvdi7X3(wABp^>eXOWX7-0F{~quNC?K_l*SLbH zTFX}CD&tYiQWH#``AVM4PrgFOA$WJAM`wJ>v{h$Z?Wh9<`l5gLG1N^;!LV}*W<&hg zcyS{kaZ?MnMwb8Fxj}a6(N_J46gd2QxcVR2%6{#l=q+~W*-hzD1xwcj7*;ojt$E>S z^ETIO#7h0idbAye)uyNtj0xr33Tl7Ahenm@pCnN)sKc86dcPNX4QX*Wd$&gnvQhY_ z>Lpg^@|APN-I&0^7EAv(>X!aNXvNo}e#A}@Ivc%an6lsZdXf(qaqQs0y((LW>u-DH=n>quTr_kA?FAiG>r9h@G!gTqKD@=Ol4<0i0T5lxco~!N9NeUjY&! zNukNqeSRb~UM5hxDcBvpIUU^DC(6W@iyngLjHQt6bqK)n_7>nKfdPQe9%O+A%=(;N zmi)-G#UTR8s4SSFydow&H0|8IB+%sdno!=zj6hZQXKaH*y@21 z?qTM?qF5*6_55yc1yB8Wc`3+2D6SY8LtY_v3%LFDjQ^y87Q^ zw1gPy7o0-+How&@oEs%yHRJpUL*(eFo7AS9(?+aZeO5P@`l#w>sVcpOw_YH2Rq^gv zuHhqfZ|7rm7mVK@odn#WI3c%l)K(T?V(pT5Y;F~2;l9XUP*%U-)vH{pUbGpw{==mP zZ)W?%qxq-`GU=u*HSsy!=bVDc!j9B`#Pcyx{m#RKyzR#{l zmIlOC6@=DtDZx-KcEj$Xc1uwMbJAiVWnQ$`kK#6mc=lfQV)^||?Q@u!Uj4MqZsNN9 z!|yyDjDP>-Rb+PDWZ77pTkkV}E#^5mRFnQss_I1t=U5d^@oLREeH*A)k$Ky>m1*xI z4}NApZZ3a#d2~wADv;dnsC5L=QaS|;Hg(s^$*Jv zPVgByu%CFrD!dhRK)nQ=|Ee(~=43uGCmTa`#}b|hEW(EPH)*P;LcljX0Ny(I z^4Z%q^-JB*jR9x!qtpv-OJTvFhrV+2ngIO-s}}?1nEyG(k#qlW-wBCpA&y<)IEpAQ zt`Wk(hY;r`iG9IXB@8>_(~n{z!mm7Ber=Zs$AY=o!lc94**q&JGk{SoNn{_OfS3VKsQ$y`(?_!#T;yBP^Fp9=$8|C((v!% zkiK!zYTQ!N$bJI-;9UkCZM7u?;he5M_snw~KbBrRd@?psEMt$ov0k^Z71jz8ovr?e zv)7#2)DxSpxoJE*;fj9;2X&ymAfY7SNIR)HE<5#0$xoQ3;W=g3_i5^&3dW9`<$#?V zGciAA3OSaTIH3kI-AA9@S=K$1t6>thgWA)Q+7WO5I`xOm`-JB|=rfm(oN)L2dMdZVNZJGGTyRU*H6zQ$G6YqR?<^O6l zrAH>o_$8Mnhu#tN(mvXJ!f%<`7$H7-F6-bm6C^2#XqOM}TIGUdyL(~+Z*9#)IK#<@ zGY`AN4OaKH!>WO3ub>FlAu38w^$%SA8~J{xEg2*Xh}?~(Ww7LbNt*(aZPlSkSh_lU z>3_H<5EQxBPB=z%7(yM2M15YCOliS!evK1I?T9sCeOO3`6!Tv&MulA*$xOx_;y{Ng z5Pf0DpSnLyGQ!eeLIfKC$l<@|t5qg=K@1Ub6L*XtZRtI~<7~R9^2qxMv|{J)^wke3 z`FrV?xzs6BJs)jL>wuq78iG$n3ad*0q_^YT-FwHn<@IuJzm+GZ-%76iowIdzY)6jl z_>?w%)VN7@R&`|aw~Z9uzFPPB<>Lu6RrPVDuOyD6RDw)?Hr4NcywH(Rp?&YE0>b%N zAs`{Pnu)#;nwKrK+hrqY(DcM#ccJ`Y{6cE2Cgu38MKbb@AEIO2BimAOn3q-U_pz}2 zt2>?ROPP7;fYOBztGrrpj80HHU~6&yHRh*zxcc{o{j)9p?3N|L>^r{ly+Lv%tEUA6 zNCNFK(~KxH*%(}^T-Wt*=+xbPWSn|I?!x7%g&X^sQI}KvAMjiwC*Fm4<+-+7*TeKs zIu#zHFWdKWbC#7Vx2A7qy;wATai#Y%efJ#d@o!__3!y>Uk5So*`N&50%eZw_b3$1wk+VAUk1i^He;bEc2fTE(=*cDn0<@ zGv>jCeA~}@C{#6FWs5r&5bAQ>KPm4@zPC(=wOHdynKZGBOTzo@GYcpAN)!9Mwg#`b zlOgig^yK6C8XbnAd?%$*x1YQ;bV1D5${<`yj4Qlr2X^V_PsI?MW;V2bxD=AC#=%!r zmODCU-%5nvTYPxANup8iesWeFS{``wO~!Wxo-zR{^!Twyw<*Nzn?WhRm6U;}ZMv5& zCr{dyto6lFLCa~sWR8ev8ijo^?*9%MP<`$Cl4E%LkN>1WqJ+DK|9@L`aNpB6AgU&( z-&e~SIDGN+v8CS(j+fE935YNaBU80DT z`}27R56z@GAx9l`z>Z#9b9Mg9eWZQc?ZigjnLYL2n0*Q~alLkHMRT=VW3NwS<|w)6 z_GI2mo#edZpu&+V;~My&CO93|o{?a=>7GQ$ST)~8UJ74|QuJvI#VbDT$%=sZ*-4XX z@fl@Llr;tRtvmAuyimN?MlntWX=GUquH> zzhulLBj)TlzzwPN(sI61``jL?sXz4&7Kt_n*C)*BSSX*^Fnfg5GO2pLg?YRYW23h8 zdHQthTr18=^^eMOz?6cN7)#FYtia)tivxbg!lf16fulWZ?|lSufVY*sY7r*GVWN%2 z2K$wuk(BVuB%gJ)CyZmEAB#cDpFjf;DhlnJkc5OSyUFjXy5&)`Wj9_nt6f7R6n};F zt{~K-;<~j@i=!V)=H?o08JA_{M09_obnfQ=Oou$)r~gK#t|q;T-NtS`FX|ibk9hXB z-t4ZA*5l@l82dd%UDf~)uk@`vkFFEAsEAN=-UcF|JlWM2WCfAUj%-Xm_ zF`jI5WioyAJ&+pEyz|(|{$S>F+Bt$sC47$*Tc?ipvI7v7-(0HuP!Nx1?6pBP1UPdRfW6Y`@NNfoT!Rn(bDWv!XlaVJBuaz=!!sLy$e2h zZ%QcH#BT=tu%hYB&f?u?*}Tp3G{grRldQ~il!$w|M!9uIsjt;@yGO5q-$Qe|2XE3Z ze`w^wx56&i*|bs;tr1bWhB84#9?DS7EQ7)pg@%`~1@q6=ibM^diba1T~CFd;`(Y$EO`~qwgS9pDAZG~zc@FqE%cXl zWyyo+zGFuVp1Zi_7%!roME-?-T{M;6g1@44Jw%+V3iE$7K(3PiYQecN_eEZylqTn5 zUqyWN)^AXc4YjaS>HYN?@%XQw?`|FEvVjnI2leqU`cmFCe1gDj6O<9x6z4Ufg*}?RbWY;-#=L_pBQJigjgK%pT}=_ zxzL6UBYsUk@&Bb%yOKW=gH`qYi?51%z~ccY_4X z-d&Gb2?fl}XOX?RKK-oQFuQc3=%{i0iEj_um!N3ptIxn)POkoYr=4uY?z&v9OZW83 zYE%-+sReU=(H>JV2oXi!mm3=tefdVuXYi(I_fYr zHldN@Y%_A@6Yp3}*+MbA2YKO@T>QO^ZZ&W6F&X7BTB%VOtB?mmR6K=l^w@q_3A^`7 z%r!;C%OxpicDIh)8BT0%3+~KgK$EDL{ZbODJo1oE3=I~Oa1f2LEQ{->l+nD3taA^` zS7pX=Qa$MWLB`a<#}%)4miiD`wf=5KH``MbkNsS^xBR6uD4LPcauy|+)kY3b{K%gh zjG0~3+0K3WLZR2Zw_mL+q-YisSj}`c zUgMPvD_z%6?zP`|@Ncg>eeNv#4_pobeCJQ$oJL17ai_(!MxuMAJR;pTj={ip0=|=h zp>f9}#kW>-P_wQYyA$JPxjKXC{;T zoA;EKUnYuj-c)&YMd)GZZ?7N=SSha{*`t(`sNY1gM010kQ3fvUkilj%^Q;A~nY^>FC|G)YvwED_8|-A>$Qwqk_{Yyn;@yY?{fK@bN-?t8;` zSH?qnkyoB|u8)={c^wACiY?1%<);6*4+}mG2T0vI9lYR!7tHsZqx*^o=%IDX-lw%v zIq<1xQxHxEQj~Lm-3JSECa?#!owiUNG1L5JA=692dUP7V0ZiY~12Yex>==SDhY016 z{V6++ho(SYq!$y)&fqN7`BMf%_V-A2uw{H*5OFDlxj?7QC4+=Gdq@_WmI~&iV0D*{ zz02>3*QRAJV*$DC>EDS0`PtK%I~JinSzqbT2gF7-1oR${OpZwpq3eU{#V0{b{g9oP z7CMD!gj# z1(~Rfj31YPp9rAhQv$QOXDWv*77rKw<&9YiM80(z?~TpK4eXIG{@W7`h)Gq#tX=Y@ zq=|;72y>48{w8f;5nHCg3Iu6473>*%CA9lpZe0;w9D@%He3A^dxYv97ws|!mldk@* zg3n8_tmSq6tyR0O*Y@k0{dEqzC($AQi|)M(BWc{d(*3K$`7&N{x9JbEoIiiJkZUtI zdn)SseF5+-%`mn6c;dEro094J7S|Kh(tM&4`A&(#sl|nJYqPtr2^VRACy2+_wZz~O z>F8okQI2=-W@Sp+U+v@b&N=(^eO~A(?X|<| z$QCj`+6#R@Cp0iuyh;Ov@NSL-O0O@Wzb_rXyxAM$y|Q2YRSdRJ5oHcPg=#!g=$-l5 zi6~lF*&cuC_NZK)a;?11c|pmm`AwE+tV(>BQQXVjONnAQZz0)EtEKKZNmffa%}T3m zBeiYlX_Y=OBViFL{5o1p3u*SDS~+8rOXCn(Ncz5c*}A8fyyU#UO?b(nb7i>(vbE02=zdQgrD(~Jbkx2qtV@b9rKB{T-Xe#x)+&5!rMIRDW51tb z1R9jDUi&uKZSy?H>zz*V-AOBzzgvaJY~#X9y{0)s6JPJ*m6bG4n;O;$9Cl8Y$K9K+ z33in|^@N`&Cvv|W8F-pAVmJ>O_gR|sX9k`z( z|HB87s|7k)%BXRfc_m_OcTZ-La_{#KXGZ(KV-3?thId21{8T;BnV)dS1@2CpVLu)@-5shQeSTQ zUHN%w3UG3C{S$e#Hkq!Uu-z+`N*EMoTK-zqt}OK5xmC>&3MaaFd6j|pVS_6=3vV~^ z2m0uBP`~#i$*KHcV#eU~!PVd<8wtnzc0Rr~Za|OT-w*b?{d%z$0wr5ZjeKr1H@ETQ z*KRV(x-uDHi+FPdkXyJ^OTAtD2^=w)a({y)Pd(}OrvjTkj_zJwr3%FWB2L?&L(AjQ zJ0ABY5|g#T7q9VpmVLC)lCO+-n4jX+&0_T9(ZltXU(xc^jX}a-^K7JErHhr)@VPO~o<9|v2GJML=O+~`dI|K( zecf>FNF+hw&1UF`bLA(Bnlv)p!tAYlOixtiJ|il(oc=v%!fl~I@B(ieUW348p4b0< zFyu%JWMA0B}C{Q6l@-5FobJ;r^RZ0XD)E)b+~wc<=W5APFnNZXJ}D>591D4S2@?zy^>cO1ST<5IwjrazF}FJ-1+4jfKR z#;UXFU`8P^8B6A3<;BufCpoBL3*49+Go^w4Au{&o#q(*XhaSSm1kAEn3rM}Py z2%GB&NMIfL@$!5qI`!JN9=?KPKO98`2p(-srs=I8#hYeyabz)CS^r)BKQMeYp(je z@Bx!UaJ8Sr+Yu+J$Hi<@g~}He`rC4}&DDp{D9GAM*~jCePqjCzA1nFn)!Gk7W^8ep z{Q^x@1xu*iMLyeHN^C(_SzfuT<)*vmpeg=6g^d!j+P&tY!VdsJXo_-3^{d~_rvcFL%8qR zN1tKiRh;MtkCr~tQ{QD!`AYoetM$&YXr>`g-JrKNDyAWw0|M8(;V3lm)CIAnY|{C! z7GYs_bLZDk;?SjZ!KTHJXs%Nl~tIYYr>%9vVJ7 zAm?M?kV!Ud6ZrbI=>SGh2y4ePK6-hzq`h8gPq+&vytJ(SecS-RU3gFIA=9@_=%7sF#yyL4ZhXg5C2WRUM1nudGh)q&R@f>-_&y94osR+y%N2w+}j15 z1_|5AUI6-7=I}o@Jel10wC=_~Js+3wPg49T**$77_smN5=gNmwEd^nJv(LqqbyEIy z&a0j>`_?Iu9CH#IdN=x;jS(;Ztd*A)v)xi+65m2&MxDJv?zN3Bd~*^bFcTF9*`mLx z@D+XDy&1wV^D%JLyLuh#{Wtyc^0lRFNi)%>uBvT|p6)|wB$~}gC7JK5j~?T#{$PF2 zcGB>p)|GOBkx(R&jDb{!S$|2ldTfPzK31fC$X6w%Rl z-U&&KJQB%B^k;SU`TK?FZ)b_=N(0uQIv) zi|y~o!L;YN%PAK*)|HSD`FG?UbV90=N$%&)#o& zy*`(oYvyZ|%Ck?Iwu)c?jRZF>quye~{wXgY?$4w~>EFWJ6w5?tW&C;JwY3#GNszQ; z<`z~CoC?|;ZtjWKOqNy)S^x23nH1uuz3k7Exyd?T+-QaUXH6a+{(i~{&vo^&#vzQV zAmBvL`knA?&$BQof}v3LIi(G58h;UGnO9`f(#| z#H&n88j9LUmo@!An$E(n2{+v0Vj&_-ML}tlP$>b45t~IQr6^rWN)DJb10_Uaj8G65 zOhiPayGvr!Hpww!#9#wPj~;RNyZ3Ydi1&P+_j%6w9%<-mm&8iS1GX_M%oEM_un`~= z@b;DHhD|KX@3T!xX$OEhB8(DweW*pPl#OEYnK-Wh?1}!(GnGH}$9s5A(gck!QXT(l zG*w<7)x(yRtnxx7*ALyKe2Ti+jgISZx1f$9Q}4~rEMG_OZhWDxum4#S-z-^NUl(k? z5aMy4ALM6yIExFh4O+>FB<*1G8K!uiu#-=ldy66=G^!?e|2@NbPa!eFUuX&f6(@$v zgrhYzdpwmGlm!L%DF$u9!dP$qhv>cOYx^6T;F|(Rb4LvR-G26l;}jk1cfbHcVB6@V zsbj?x3JG$&ZOt#uUIf=v&3d&mfm2mg68361X^kY|P7aw#k>JDry#*5DD5RTTEqFPQ z7e72TIqv)5Q=2k>O>?TJoILHY-AH>pn&TvT?v9@Dcyi6R=R~gNC2`aT&gx@-!ZvPn ztlHmU*J@Btmf(io226BpO<*7ZmrN$!yyh`16H^>U)m=IRje)I3|UcSaCKY-Wb zUFJlz`IA0Lq2Is{fA4wDCA(&0O2x(=dVw)AVB|c8P2tx!H{4!M$&Sb4mQQm@#hf+d ztnn~uE~i6<#g7UG$FXmu`1i(JRQGInppBYVA#NtgXSy4r*5!$mpfH_)6PCx#2?wIp zocsa(i7yiN_C!;f`{xx^mR_D4CjS)^*+HoYEBY)6JMtrc`dEK{?l2$8H0q{>@5MRohXztwE8kGNCX!dNX)+ErKRa^gsv99)9vc(TzIag|cElcj_P{@GM z+1L{9(j1&tk-tsfXEDML$V-CmztSw*Qo5}Z(6ie<#;Q@kK#>=$^|i-%%xML<_cE98II9XEok(HkAocD{}3(>fkCO6+NE5G!s z;>s#%qfgygw&Vy`W9}58MG~HINpKaPedevBtzT$%=aM*EyjAK>5#!8u5LA~5nNMPL zPThT9Dp?zK`{@tOXE2XaTMhM9Ki7ZDteTpi7Ch|2!ZTjQK3tu+eEMsfLJTXi_}s%- z>YKaS^d~sTmGjy^$4BBVpy(>J`twgeMMn(c7oPC$o&_}Z*V?DV&%90jS1WF<&FUH_ zopW73y6tmGn{<{>8MbUFtklLSu&kF;xKk&p_LJ*L&W20#&i@YN_GjvY)^=zz<-lv~ z?s4PQ?g(>VfmmN6{ZliG&q=E}sk2apG`4L{8ko7x_sZK=ojIkLDQ;yZLoSXtP+|cb z7}<8%9V($yF=9N+}qh?9SZfl_`?*6WHnPz7-%RVjEwpA?}m&KN}b|RCq5KpT{Uu4 zGUtk!pwHwdxt%W(1+_Jw?9*3ycoym$mc0;&d8Mw>;<|P(1e=m{p5hQp{=sIA@B*Y5 zyYPN)G$q%~^2|5?@f(yG^sdDYZST@wX-(+TXgJ+!?mx487$aU(-E>Uct4pr;U5%qE zy2tiL;u*c8ZH)UT0vsp{I#^Da(c#g{>@Wqxi*l#ghTxSwv22aY> zXP%M{r0ul&(HX+FvN^cX%?#!>e%}y8GoRv3VNk;Ui`l9IXPZd&C(T8<`iRa~-9fA; zrL*8;#^~OUM!^|-6OV=yl0X~|wC`up?4{&B)dZBH7h7-FxbQoBIAsSq@f4TI-_nHm zS9z|LlR{w|trFTF&1RF!rBq~iTw#pj4!Y9rUK3s^50|t|pFY+mM*5$qNn^)Pf{7h; z7Yn-y>j%MUFjTne-a%mVYWcnNn=>6EP24@qxAbhxHaa7xBrc~ztUP9~dGeY2aK3`> z7A?SNFJtT|VR+A<{fIy_-Y%p=-jC1D$lN1|iSWYNktEqVyMsZ1%PoH;bpZz_v@Rn0 zk79C>cu3)fo=v{_=S3cQ*go07|4~rD zv-N8=a()?_*~xkNacr{k{Lh{X#PtJ$*M6@ere1%a7rKI+tp&X9yaNJ=JV^1_oQ?r| z{(cl-v2Is-rz~KaIm1uti=W&_62zf<6+m(j7bxA5ys0up-aPZ*SmKtyEB?-cz}QRv zBEF4W_72*MzMo*kQ%T!mX6se`>)qrg!Gy}N&!5&{n!GrdKXU8coo(iQ?SaS6>=|gS z=Ju7$3uc`CtMUS*Q>m+4=_?;4J)LweBL(H#mu~R;IF*g0wR?E?L!`%OrLmw^|a9w@jbB#qW`eW(U?BgDCrZ}J~ z6R^T7>nmHU5`k>G5VrV8tLVIvRhjM0Tr5wPlZg2%Qym%9y}i4QupKn{C~U+>saw&p zVXnCPjkye>e5EP@=Raz!!rY?Ab3E{57$J~fE&Zc1`YW78Ck&rxcv+%wO-2mQmGBJl=m z^gWZR(_`HO_|aYBnvgXGRY3OuP3Ql5&sw z7n&K`QMRpWbe8n=x#d42J+k2VIqS6~*6+jkAqVJv9%XB8&J={Wv)A}X0}UYce9SOWQ7W4&WEU%>|v6f#;-P9W6J1=KxRiSz#-T3ZBCO4#Uw- zIx^%VlI}s=D>vcd8+WSd3M+;w=}SthK*T!u%AO(Yw7AJIjhefnPF2vicoH{w@NStTfoDc9c7XZIJ6y*p z%wiomfmKY$cM%YYg3-=u5M(V$i7j}e>QV4XnKUwW#J`a|cBPR;4L5{2;sCwX1J0Kl zuk0Y14{!c)*2=tIA8^oh`ZshbcT5n4Q@_Kf1t!8UPLg}Wyv1SiuocnKB&-Lv>Hf8U zcx1Ydp3R^#N=`Lq9#E$n3afNQUwI=Qh_POcZ?KT9AdP7(ln31jR)EARNG4b>qjB%e-1#5WmDN$H~^=TL6Rw9TfLCjXl(^|hi?dKUj==@3Yxfa5L)d+0(!9|jnyJ@*tvAq?sJY%>Qud*=g*_S`Dg44O|3aiLW$<3G0880x zf!ZtV;x|)F2y~&xs+@7py7Y2{le--Ob;A2vNp}eUwBhH7kKRKw`ao^_vR92p=~VZM%g8U7*YW;X&+d>mBfY3?lZQ=Bcg%c!j{Ahf_9(}1 zVDr;2AdLekHK=Y%4lSK6*fzlPfz^7;^SY_!FYAQ&LLKQ31nm6Qhq>-LtX^S%dXR0Hl4aaUxuUhB6E7eD-n4(c1#b_{NTu{gEQ=s| z4}qFeT2!X=188-eWx}P8^q9+}xFk1|;MbCtuc$6Neku)=9y;;w$Bw;Qa?HO!Ax6VsG(i_9{^?oD4nxHv2 zelP%2jx2XRMZ&J+lK_f5_+YGSym5bD&=q50f`gmRGD+ ziM_ZQEusB5A@$PGlP~?c-gcGrzn__`<+E&euQnj-iI}(%9ftJ7Q z5wD4}%j0J|1Qv@Va+w{-beOm$yPEg@0~MU}3n^*QHn7UPXzrYu^7glP+jEcG9hF*- z^fA0AdZA)WIcUKQ%?DBiVU(rRjQ-cAuN( zI*S8Jq#dn4OYGA>YiJ}~Qb=ZHbIL2@rr5>lGRzFcM@#?9bx&bi-jrxmkz&@8r2j+q zlGc}WPo$&7%@`ZV!2h@-a7F$m;3}~m>^>FT7JMxHqqtP*41L;~{&>?maN$eHBag#6 z(&3&{yL+}(-ua?*{Z@6Tb@+)onYi)U*NBWAUaJp;LR`hRLq?Ran`e}$@-5ME_AA-C z2TiWp0+Ty6RyOoZyWT+8AdHsufkb`y7i)|%zpDka#Luq6=&Ee}g&VToRp&tyw2Jxi z!HuWr1LE`p^Ug`y4W1&`sOTqCbE9xX&{bwv*nUuNwc&`{g$ra57WwEGq8J8pc$KRa%DE3VmmmaiM7gyQ~P$OERHh&_c$-#7V zfo8sx=QEDQzTU0!5!aIdL>Z0wU2H3 z>zy~djYekkJ!BlnbH1mw#`B1QbqsU)&P-}ehrk1O*AR@mA;PhTra47F-djZ-d#I{# zlX_Yig0oB9IXO=%Hh~=y{ue{QBM@@nr+TnV^V~b!*c(gt?VQ@{*zK$)2HH+EbXvD? zlm1JWZVbwRLJpty%1NW%?N29ZlF;CN*TXr67CRy`;s0UT9dVg)6n*}DtRrc?BcZbZ zrVsQIP*8;Upj~qPh!;x<;Z<(FZqoxI$HO|VRnEf`mc(u^5JzTvmIyw8)J;!2r0+kX z@|1fb>&fTMPe91X!4HAl^jm-?sj=dbmra5eKTo8&!I&ofP=TPM$>tLPRAFa78IH*l zDug3n_;LJGZZTpa&kHUvS#91F^%CHHkpzufP5<0Jvhp5CRt(a?x`|MqJ}|If{dlig ze=aYCRbn+e+DuUkZurOLHIH^pa&+C?&ND)L1b~Gq`{BpGfp3pNbhlC@AX#0aenwF# zwBVgn2!BsSp^G+nC`Iv@ozbC?t|+ z3i0^|nFcX+&ukbAND0E$?=LNuI|i?NcQHHfqxcq|N((@ow@9zOWm=}@MUt5v=DNcQ zR>3FYmk8T*rooRV6+%ZZ1a;mk5sEKI*_%qArT@4uFUuZl)B8yaIdxy{8sQq%q9uGz z$alFSZc~w1WL5ji6O4HRGG~Gg308OJ`%U-9%nixT=B z;Eul|*$JmaA%8M$j|vhJktr=b;{AcAF0ycKa-ZuWm47CUYx93-w7dFsdCatcWhmQi zZ0M#(*Nn{gt*f=XVX=4li!04A+_v*uNV77u&>{fg&?o>(zeeea%sJOz`$}JA-DGdP z|2HoOdnv%dtv?z*%o%9j3w&~GGY%l=QYbpE0{SNSt1SOn5w?HXS(~r}`CU3x8k2u^ z_IY*3xs9c?FnL9u|cOEL2@*zx!ho>L4{+j(#v#kI3)>n*6uQIbFY1a+3ozO7H z^sdT}c(vZByY{|9yuu}v?M!@eVyzgBqftX4vG!Zl>r_^ssw}*um;(`P6h4^uj;pxV zd8`FlUCqjsyc^H0|N3xPnzmq*JF%`FKJ$@rvW)-zmDqR3db7izvPOU)Joe<$#@9%g zAI3n#?7*k*2lrcL+FvVX5fi)X=cHtz=F5AcSDvm+To)5Wi}O@wXZr}ONU_6n?`ed& z3MPvP8X>Iz{Tw9$RhcfYd@1RgF_)Y)xpYC|VO_OIa-M)r)mNKoygs2ZM5`1pOHnP7 zPQQt~k4bb{m7q;iw^7PL@Mc#N#HTm;sIz|cNbQvWPW|o(m+IBnNJyg`(SJ9c1ZP-4 z7>pR+>a_-$BFn}ss*7bgm0JbB-#r5cTGj@wZg=lF3e<|4l@#GR&A?k zWmbkFMg0Io73ztNiCg?}*!j$}ywcGnkhCuxp9BOY2ab$`329T~j&W;@;kf|CLJu<0 z;~CV`=^g5&n1Ql;s}$FOZgOK&5=&!+EdIt*WQ+G{+~3?dRz~}Df#jgivf<*kHx2#+SK8J_LOzOvmb_n~Y(`v-Y|=07J8!JE+1-pew?k-o=JNsJQm_&Psdn-z zpoF>UJ&;OuLs=~JaqP~ML9TdQkR_{Y;lv~s-QRSGPEdwL)VO9>p4i$#Rot{Y-V^7! z+zN|p9a_3z@s`UY$#gxrO(3{o=RIdNSpdg#M}x;5K5@<#*JP7p%(IMOTQ59TwHRH> zZHrB7_UADp%M%`;=i2I|=MfpR(Fmr`>|uRRf>eVKTrKLo?g#IuG^rhrNuMwVXriTv8ZRPKO#mSP z-iB%L2lJ@~KOi=RKo2JriQIrS;tf1IK4kZA?YHr0{f_w=ye3MGVSo^5I3etHqY<5G zL}o0Sk*2|ckNjdC^$&Berf5qdocJ8)+601e!f#cIz?+vOiMS|`QP3`cc}I)Bhn z*wjD&TVfZVlPh$3Lo3IVAGx#lB$kYs{_SJS?zw*sI`|u^xV-c9Zk<;|{Hv65pSX+5 zyAl7CPT`r~xr-y(bjp6pKk^#6lFs&8;h;^bbXVn8qM}S~)`G<9py_8Jt4AXrFA8RF zo8^eI2M^t+nQwm8%-{ZGqG?|KCALdc1Ijk%bDqljxFx;XRBVZt`}(F1KD}@AeBr0a zm(0wOMfClCIeNgQ=hJ;7>(GRcg0GsNbzmV7psRS(tdTL)2+$S z&p#Ads#pP9C9gtGti|*)k9WQtdK`jV?wwZw41QzPBWoH$PpU2)2j9-IK7AC@a;I+7 zLAyO&_aS%@KVs%TB@L95$N`=fE9zxV1M_#Ok3(x$Nep^n-WP@6?lEmtV6p zmfh)N7U-{rN(J^|k-AJ&-HGq{jFjfs)4~$?<=u#n-Zlp_!!|VG4Kv4hpM(uUyuS;0 z>ig3Tli2Q?y7{t~#aYLHxUiR!pX5*YA>?f}f6Rw+3W0FN;YC%lw>wwoHoP(Sr)7MS z#)@+mmjmA&0_x{XC}&Os3`gxOViW$NhsxMemLuYxf3heP|J9R<7j`J~^8?3K1^Tpo<8+0|F(%*} zo*2L11=B#Shy0m8jh(j@Z&OeGqWo-$iQ*Qnuga6<)_2}2;cL`GN%AoXcjMPA7jIP> z`6d-;%|%C*&OdnnR5$3h_Ags`Ie|FRyhXg=)AgV)NYT2xm6B@7UfU@V%hmk`S1L|z zQ;rC=2Iq#upMI9OSfwsrkQp*oM!*C4sz#O)o?#DtjH6cuyn+3zfkU-Hw#V~>{n7OoE8B1y`i=R@ zh>suRx}UdptkZs}1?a}J*89;Z#G3A!YdimQ5>9Z8!RogiN6FHvOW~I6c&~mnv1B9R zlMPkJc~Rq{{7}iM?DfVN!DBYfXFDqh*C#gn1;k3!YyC4J2X^UHM=1Y%?u^CwdwJlZ zm^OoXvLi?|tX9~5bmAZ>6ICM2Q<+MFRR*$S6MHagX$%(9m(^G_cGeGjwRK~{q1EBhSR zhVitdK*{_`a8A9+!R5$iiH@d#F6(sVX|6>EfL1>)$U5G7wD~_iIh0aV6iK|{yE@5Z zTufD79Ah|TIwjGJC_KUMaG}2jO6~Nc9%pz`512CQC&GFUQ`=n_`IZnH9s$_l{@#W@ zh+hC4@Sjg(ac_Z^%fNpIJqX@R0(6$65r?Kj%)h7;g{bhMbdqxftih+If*Pc7OHA{U zTRO$TTIXLGSS+(8K{TVuaXh&k4qiohsw&vJAjL*p7)ssmp@%J*Wk~nnhT+b3*>6bD z(Rs&HJa>S(7VN4ht{_1h+uFVrq2>9x7dvdO+UFLj7$GAYmBwWSaz#5v=t&jw>Oii( z#yaoqpQk7$j|Z-4mU>Ak2z!mXL(UDw@!5WOmyuTA7H8}Ee%mc?jvFO?>2ciZ__(u7 zZ+v|FLauLgQC_~o3NTwj)Eqr0A)$H%34|hBZ5*&r8P;A1o>I@3}EsKQ+`nCZ}{YMA1&_ygsU9 zM;F>iEs#_$`FFlA1c)5h(WnREy?>vGTDxwvun3eLe0NydI&(wi>lB%Og!cFB zK2~;!bku%8ZIt^)VEZ={Ny8VY&gGw5Phj`2oypkhgZqsZNQWFpDF9<$!sUhkx`+rr}JDID*P;gv_x)ue`6QI|i_4Y6fp$y(RE3(RPPTC=$L zPmx!T)<3^S(voSH{+Rg+0byyc-Cn%DO@Fgwj!yB(GrL!IRCB);%Bk?MJ>$}3lwVU< z@7yRQHS$g&f(d(9yC7JVxvTw76V;sDdDQmk(eDNS&9mC`7Zp7p$Y@r_!mo`4>biJt zR5l#QxwizH=5)(pG+7!e$Js}AAAX6Imne)XWs|=$BEmslaifBi-nK7EQV<4TgYrs# zSH+J{_@8|5sQWQ^s@hCfj`IyPPTgCuw2&7EXJc*M%p;SPuqABDoxe3{@v_Z{b zT>dIY%h^}+1rGLXU+OxGZU(+q`Plhods~qqkn+E5$*QCKmww1cdZEzVDS#rlxUqX| zdi5Hjnz(=9w?0zO5J@8UF25?{2{*|UZC+lUeu1YR2Kw52?e+5VkGJjGdj)xq0uh;K zxaLuxXk>;_xno^@XpuK?v%z&0ShPzR^vcLZ?Tf-dDM-HRZFBr=WYfa&w4bt7w($R-%d9T*GM~!hs zaQYQT&p#)BJoeSme+e4|J^3~(h^I}Q+E(f~6yKhq8g7oau~{1JzN=CNE3X0VJ>Me$ zzPF*Adg1lHrY%YUiR~&ZC7D(kdxOA7Usse``1AK{UK}z4xNs3R}N8CbwT~$ke z^e`o00)bV#0B<;0@Z4`r@%bBhcQIt?8z&XtYtarFzBlaI6{F&i_`?aEv-2QgpJ9UB%J;(ZT+NMJSL==IZ zi<;gZH1T@jUYgEtXm93R2O1y_VR=`{_JH5#XU~}_&v{>yE4_Q6N$jGPMFiDC9guPd0MBJ2HVR8fEsfl5F;;toHn%C0HH-@A!-9!CtpstXcev*Qf)Om2J2^I7xlnK{vO& z>Q8!j9{IDbIrfsNr25}1jZH!_B>vIX=t5$r_^a#EO|z=fm%FvumD{>%M+m>>%0uHH@H2+d;cn8e zFUu)I$s1!uUwM8EOJAdNomPIC6x$`01G11iv=Nd--{Y**%kG$Dy?%@MI>wvVtTtGF z>ybq&Z_*@2<^xo+SvR~1^!s`%u+CYi+uk_l4ucSiW1dPYgWG89e|C-gC}8Kh{`6n) zoUoOl`?*AO`x<5)K7E&HF9S$b`jgq)Mzypz;TLMGRDAgpyB~tmUR+%ZGFW)S^!36} zl*U!poTNxKcyqq){nZ?!qpfq^ovtq*b{9<_r3dd{>28QWE5L$nGqJ4B7|N_edYQ^N zyhN6j-M8`@=Mm_UDE@TAEjRhSRX+AbB1srJ_FdYFyLvu43okM;_;9uFWv7(_tw;03 zL}a{2NySRCG+2;5=6t#B4;3+9Uh;J}OGEccGf7D)u}B%H0YDfcK0f0QZz~;Io4&z1 zg!(I9=#Mo|j@#b(5yF$C5<)aGs154dlD>C2^VLpWVQ;4Lm7Ld@l~|?WOH-Xl!4m15 zlC4j-G-O4MikK%$Wvc8dX1ON^Z9+|NSHw*?-MCHp5xk}=d^8=_^5X*HQQ^B~-*2Yr z_@|04Q#0YlTo*INmwg0hyb>3*S2M4PE5uqKRa(nY#Y4q|;P}1Xur`K+%$wJ$9<(|U zY^xfyx5I#XsF2tycLkc{il!RUA)%JFRfj)#Bi~_}x~FMR#m`~oLFx-{c0A!v|23bD z{D!lnw5!)lGZq5`#mrrjJ^hR|8KrZ!SlRa-rQ4Gjj8!2Tuh4|2OvnA=NPeoxx!ys6 zou^N>>XgY!%)L#cqk6r0Q1l#GM+O14#_sDt4N&H^ovcpKGEUthAU0&a;IJy!TF-af zZFq8xdd3wRHdu@H?34O>kRMRYgN7n2R}l0dHiEy?Q2#T)aZtn^0^OdFCtg|DaMM5D zdxGc@Yt_3aQE-?%GU24+uA!7vs$hcmy{DylSa#dDX!4!X;hSyMA&ZQBgzW+-F}vS( zvPmE;ZJ&eQ7I@g%P=w3KC;b86-CyRoF0Alr|4ujCO^84BfX$MlQHBW9#6Mv`Q(cUUW5pv=hRIWP>(Uk= z*w#DMfWxN(B&%4ead8|VWHV`lIb@xgG^j7II7ac9XxME5pg{)$5;{y&&X3UawkW0uY#|Sg<)#_cn=PdTp^2j^19aGzSHXpBx<*OAuA+{*k)bS~7 z&rIbUaracy(aUSPrkvSzI0GRBia5Uwii%y0etl)svw6R$fEZ1sh@vJ>E}z} zUATExuw5YM-lud}gKYg*LK&s(;8Yb$ttXp}sXN0_>whnv=LJxxh69~t6O$3atnXYv zaMC;dugwt~6e=(6BDIsr$G0yE24qNWOj9@C@+U7o4vjQxNcG51I1$jW(o>itJ>mrB zyAb@opA(zfd)}()KTzV`c3TeOM>(oj`qWs<{qYN$+v){;FJt z^YYgOQ{jG+Lx1KYI-h^hA6h873BydA%&iuY`-5t#oJz|DVX5%$NQ~m;&z1HVI2&~U zaTc$z-&;P!d@CopsFC#D{GN!KM-X}^_5>oD>ZYyJw)NQX4f_VsYfP_b(0?Kd)-4$F z*k?(BP5H~;zq@00j@_PJ;TyXr)n;sH;NIBL9V;V&5A@ zNCc_Q^Z`Rc3A1_v{lT$-_ay z>4(pkd5GJ?rOS|+h<<8pR1o%B`J+o<;IHiRsre@&>aW>{wI=i&YTX8Bd8h`5A0h?t z8kfSijae?S+fs4>q1rwu!P_{$zt8LrP0^I5c52u5M1u|7a)q^d%unvgd8moMk$d^X zLsK^=*KBplYYh!!QyNo{yU_V2VMtq%X;GDVs&JU9LE@i+_7*7rV*0+v-(Qbo=Du~! zTTLzWu%=0Ni{~@RR`CU18xg$bG}au~FOxswAnjAAs$n;BA+wyMPY`A<4sv!s4R3PV&VHNJ=_Hb zcJULLRjxJaDw(kyg5GVn^kH8}PG5@$* zeHPB7W8r}D+3Fm>5$b3a23uK_ioYOj>zG9x`YXL`&Fu@B;)j43X#++$f*(|)$ls9V zlI3Fjb;m>1pOHyB-uu6+|02oJj)zhEO!$vk%@1ZI!_Zsj`x3S456!d?dh?KClfnhx$y2b@*>sD5m5KGuZYdQ& zuC6&%6mwdoO}s<;>C|-ML(uV0-kaYKG`_ENvG`gp-!Mo{+iHsf!FIz^+Xrkg7?u1_ z>Q{iLlHpb3uZ4r%$9h*!j}`euea#rdd?k8w*z%KR&pUgX;PEnJ0{Z7ZyuZ#9e>&3p z756Ka4a4|!5hfdPWQ{RbTePv7U+ny{UD?~X;=aoBy>JJ@!ADJqLtZ`Y@!H_N+xSZ!L625f7oJwl*1Fi?GkH0$e+%h> z|FPJ1yc*@`o&lZV(5J|}9%;B-sQ-^)$ZXSABR093zlOtOKzLW{0Jdu)36XtU&zX1L zeGLr%YRd{)A4(1W<7;!R1QKYEw9K9U@cF^bbi2EpE4ioDwXAjkyv{*=fAi(F8lUw% z(S4;|opL&&R(knDH<`$bH_LW#NO8Qw8H@ru^Fe-GeJNhU$(1j1S#m-7cfV;eP}lCq zz0-lQWf~>9#ICyHxOM&jVR)MKykdMZ0MyqZ>)1`+=pRwu@gPsUZB3Ed?X$qUBzJPh zD9XrBoFg9Z*%$n=p!`h$j}-iV>#cW(f5Gon<ygsOK6L7GD~ z5`Pv0WCfBF`yZ%xGocma?mhhQjJQ`88naCO?D~B#_G|i4(~_*vL~?w+LjfOtXfN5- zgw^3^+-H>wDz*N*y$U*DmTz9(0VTJ!1+itxWhYC;O$@fCOGBqID|_t|%X;gZ#zmF_ z)oT-czH7}uV$F$%Y7ot`5`r*i{IVH8?YMkn_l1TQ>GE?hchZX<%BPhXx@_b(8)bN# zzKV#>gd{c=CO?-pH|$AN;pPgU7M=}EeEKftaI^t+6XvsGqd-T6`k~Kv>9BiaNwKSoosv6sq*70I;G_na_unU zL;}l6;PTmtRCU5$#5&7{D3m)k&q{So(shr_A)ePRt zL6*Tb7jsE~CWfym40YHJ_}Mi~`{k~RtSO#7n&Tb1KoL=dp>SG z?{E4#xL>_P8a;5}^R!+L9^csbK-*fWWaMRAeZA(QQ()`fW|ne)18YHgfBosfhCzl$ z7S~?OqpZ14e8GDM%qQ`_OsLKG-}2_?{tSNix!-KffsXsZc~pxCZIEfjV6IKPVxHYU z{&e%hM7x2O#N`1zH^E|SLbSFas5}xx zzWBX2;=o>bT{6cn;MzE8@$y6mr?Zu05wW}RGm8;O`O9On&w-4ERX5l3$MM;#Ul6ws z(;jiW3(Q}4$T;OSI&UPNT6?No@)AqJw9**I!x-)1KijCPBsiGT2}bliiSGkUEzCla z_?GPS-9uP)d}=19w<69+o3Xg(=}X@e0yUTZL@lL2Ts=Qt8U_sXRrGpa?QK(>vJlqd zJ$SDBzzk@-TdW?pmGSiHjRn(lak&E9c|c5F>TxA_AM=d#1qYxkocB^TAA#8dx%Po| z3z!WDrqJPkxWur^nwl?2h@!Iiz7B?0$kBYGC&-rSk7@YM0l4c~ve=#9A)WOe+T&2S z?IZn2yK$XMDtPH%qQ4YK0o`t=0N6+N0nJtQ8aW7ErS>t$zfeV#7PvM4B>63JTb|yY4-kT01z##ZD{+&e474xr zAJ&yWOEi8uJ^F@UO=F|n@;V6+d*i!daBJGMGzKY2PVdxZZ6)bLTV zFR92nZ-l-6x1gj`LACDBfA|3ba!tV0mJ;m!0-aHd{y(0<`jet-Ze6$;c>x<~dAP)U zIR@z;RrzaD;ongN0nU-0a8xKe`XP;GcA*>I^=B$w1#{8Vz@zWCgGe=N+swnaiI|0` zcVLfOh2$G)Y1X}<8(*`6MlLg0cK|$RofduFSH&1&>)B7O)Zo#gSTf-0dX& zwPj@a3zHj$Lnr5k_0G~8eI;K%|BZn@UgfSeR=6P78u#q#)N^Qr`dW=P$vAl4n1R~4 zf1Sn{JYi?o_zN{&qL8@z8_NM}O^x0ol-%C6aFP|&Q3 znsS$g)P!hAt}6eyi1d=XR%My4=(9ecXae-m+g&P^uU(EZQ^mlzlIi=K`4L3d+8cIX7x_ z_uG#@Nqw_Ri+c(+;fafx-8RT5!x#)){uRfXqb_ey-@7#hhWV-CEd5diUXvFXa(F<$L%PTKX#8FOA zGpceK{&536mbTsJ`T(cq=XJr#_QT*Cae@4HiKngMv2XL#;bD1Y&gIN@leJfVN1!Sn zt2nR3=Id+V&^Fp3UA^AgcM`nPx$iCrnT?KcJ>O{D)pS_p9i*t*$NS2ZfI+b@5~Wo zBu!|`&mRmN8hHCO-DuwY|39qZZDvc<+k=vpKRD~UPtC!kks4?u1UAV7QT20aIKuvi z5rOQRzmYI5TF<=eG?RfJ@Lt)x6`U zS$oDx4^x01MCNb`rW#T}iBgM^qvOhP$OlD9v&oTfnm!NwrG^5z#SUuqu6VH-Te6Hq zrOximD?!v2ns)B;GOULEV_sygy8%H*d8D7Cmb|3(@<@CMgap#J(&$c2m|jr;=QVG6 zPx#7)@CBZcdZmhXC1tO5JJDPn-GA+`_>AdKpeoh&!`-G%jmuCoBdx|a=EVrnjai+a)vQ^ZP9Ri+Iq8t`UvQ5Yf4ITtw8Bsox*Bs zT9#^L6=uCr>n$u^jxy@@^^yq6Wn8qNVJOwUve?$7l&3j=tql}{U=-wexvji&+#bKb z7Bs}+No;ypBRw^vesJ((V{n-+v2_e;3t3tR7lOSPUL`95Q{O&%mY%M3Kk+O$*A%)v zc=8ZLt$Sy(C|(j_hr)gRy^a)LXJCMTa}k~-xrZ9TyzYMAUX+6P{AmsAXPvC|ub}aPCA-2c~=@ zEk@qabk9>~VDD|3_fo09>h8&G;;hFr&v7zD=)O!SbohxfZJRvPcuub_{u`^-5OH|% zbCN>#$8Q3@LPc#6!y4n(FpZtC$Gigu=F70b)Z^qc7NX7jLR8ERs8sZyqvaQiup6L!Z@{N42Kc-+WXRCy>&S8YG#f_Z6*3Z znAH!qO6Rkd)^0V}!NPai&)V+`^dkX}9Y4GaZZPBWH5CC_a2NiuGDygTWH$O?l|H{@ zEJ7Ea+%D7AMLhYA+7c#&sb4_fB2}Fg(~%%&8)C!*R5z+Kzj=sPI)9OjNJD0MH{7au z6Dm;sk{?=^siC`e8d^E~%?l;<+OsD;t@hom7}u{o*~7gg$48wJCTDV_1Y&;KB=J{9 z#fh!f#xVuw-QN0>YOFKs`HKBkNTOkIY}QkauZj0M3YCnixR}o%w_a`xpT>tJHmjIm zZ59omjKlMSOpH|Q3aJ$?-?>_KAQu)tlNFg>Ub0K|np3#fqT4MtTGq@#B}lYSq3=4Q zd^sU^j8xB6@I^NAdCS7ZyjX#1o%azU!5@!vw)Wdpoeha$DcQ;fQRpuNwXtii z#kew-2LR@&6O3t>>o{IUlpQciKA)+g$6;T5ACWM|%aL@Y$EVO}t}pi?)#m!-Q6Bj< zIxuQyQ4Z>8)VIiM(%oGuDM?FEZu_;O6lt=Q**c~Pb>@qt2V{{Vb{IYiMkQV`KkVPO zC$}pA@x*eA@$)U7;{MO)=uWI-IL)_L{pgd$@cLc;SjGcpJmxjVwYhlluq72(8&tH+ zx+;A+Sl>kN1Ko3(Jahig{|84_l7)3lP^yx?09PK#&{=dRhI=Ez1tfN&>c8tbmb_a` z+dfwX0O++n^LGPdeD#nift+gh)AtC#Qw4B#bs&G;}C1&omv34KcY`^N9_g-^l>$W3zk# z-XMDQ#Nfd|X1q z<940N&E`)I8gF1Z%6EDk&zA5*{}}c-K}u_xIUfsHze#Ql!n&aZhW4I3Ocv3={C#OY zGAzB^W4Oy}4fq__@y?0IWwqNs9pgjkZB&*hrLfC2Y?*kz-TmpzhjgW!9m~(NbIDi5oHPlI9_OYSN^{=~{Pp>zaex_r zexmp0MxxTq0KslbY(~1AhnTEbLPc#t9Cop*S`%vH75X4U`K60Q@v7UBJn_ee?eNdZ zO6AiZluj$lWsO};Pl(@JzQ-KWiTxB&9KG;LmKTSxB=GB^(+Cx(|lA8 zX+_TYK+m}XW!q1G5mKPT`#qclFJ>*n1%c{llWwaLeg4HLNy#Z zoK>6G=jy@2wFrgz?8o{kC(BuZ-!(dsD-U&pFKe>w8Nda8don>=lory1#p5D+ZY1=c zoAWv;-NW_Q0u0~pw-`B!8Ws1+`QLvQTHWV1FCunYW4@|DN>#we1vO6{y_axuW`390 zzVYe;t7qG6j_%XE3jm{r@~oE8>~`g zTv$jeI^K=j&XX31qe8up_=q7!{+?^bKJBNzc){lFu;w5-BKwEr;>Q%O|EHN_liI#C zjt*;rjXf&G?MP`s_njQEt=<`lcZ5VoxyH65;wYO7wb8QsWe#jf%c?EQxS?~n`Uprq zyWo+(`{1?oK@&k~CNEtP5$vHnLu4}ZtbW_$c-Iqe z@+RE*D({ZZG4hpU|2fdCwa>OCUs|LdSKBIb5hvRQShL-lQF%Nd#+>&M#$~_GE#@>0 zVNdS1;0+^d>}w1yklg`Vm234jw~>8?J$1Ft9Qma>c4s~?z8JsqAH06>^%}47(?s8l z$hmS04$oRHAC9ZnZ;YF_?u^@a-xzPc_4V=AJ6{`j?mhH_u^av-*ma-#`0+VP3!ewh zdLVTk_?(&(`-wQKpHm-vfvWk-#LMKrXw0jOf!H~EzVYxyJQUi8i|ilg$@?mt9^=c5 zdtXl5&JllB&9k3l;UfGk_Khd}*}m#0<+6Rh%h<;CjCTL6H;e1TZOrkyg8jVHv5&Jq zkIrCK9C~y1bKAE1wmh&u_GI`Mk~i2s45P$l4$VKihLd{T%Rk|`T)DJs+?-=yz8&n0 z<@k9w556W_`TZGUgJZEL^c{OIEBXP|zT99ZpGdxAwQEYtvU6;nkPz(IzPmUj_CyeK zR$TU&-f!}L4LUaQJ(d-#Jlju_XXGJ`z=r`o!8A`z%d8i9(>CS@Ckuz%{sr-syZR=+ z7N670m;V81YnGTD8=tlCwLP(SIR6Xm%HdV-1D`*Byln6J!5Xo-|B6hT-1b;0y%rk^ z(P{H7G{8A?eoxvy`05tSvMZC`rd=LmM_==-^>4YeysK}q&llTC_WjuUoZ%Gy4D-%M zJ%;o4F(WZA*`e?*OFGO5Cb~m5`*%8ybD7iAIh{tX*%_ zmj@3Vka!qVqAH7PP5_Eta!|F`oFL?L21NCddFi-{DIx3POE$?|z2P}ep@e1Jjkar9 z`Y1%CvT}56lRMbfY)>Sw-I4sf)MD%Tz|AdEr!YVCtfXt>S=DyqE4{$q(jvbc`4$np z%nc{-XGhQSCk&ONuTk760G;20xO|ugN9i~A=RC}k#!Ov4$awq!3xPKR^VF}%*!h!( zo)7c#|H8a|u!-m2JdmCTbmBkbvLk;UjX5&UzT|KnJzlKz6^DkR{1mIj`__T#$4?6V zFt3hbN?FNPi2|mBep!gC{02ER(bVNPz&^3~Djz8blE+1*UcR3#l+By$5 zJBitD*}N`OPM1`^l@TCYODFLsaOIJpmcfGXr&fvQ7MqD){p|%g`p_4Lt*vX_8U$&N`@uzz% z$qJ*`X{m!Uuq=uFs(h>x?T2PiP$)+7)Vqvv+v;F>E;JvZu%a&KS=K@C`&ie_rPvH2 zpkLPqGe^1I_OJ2gNX|SEM!n4;z@qzvSD6&Y`vW{W=fx^n^S|#*bbpowzmM@FqidGU zX$AMj7_`qJ=Uftg65wZ@^N7m^%n|1*CrdtZCz4DB$7;oVT;}`%BV=0tq64}STNuPh zhuZ$QYHU$fpSbQHIkxmgSR9VASPtg9by!NkcCkrok6B5U{h?|`r{D0BADJ^ZLNvim z#dO!v)KFt@RT|cvb$3mZ z>T3}ve#P$OZa)pHWAg#*j1SQvUg>Au?#=`7>A-#c;OjMB<7WZuVc6%7oIBe-A37Yn zSH`vLx5xFH_r{$!?vFR${@S?z=G*@Bhz}mTId0v$I}Z4>=i>4UV7}g8QoP(@=(^T2 z_u|-%Vc#73V&M6BxzbNX=J{-#m$whE5_=Z*Jw(}ui`4K%JP3Q4F`qXE)@j@mYub$K ztcSwquIC)QlQ{dgAGX{d*y60dw#VQODz+KN&MuqW?rYan{cnuITo-cAV=K1f+>Qfw z+d3A#SzG?@c3XX09=_wYeY_R>eEYUjUni>=R*?myllwf$ejIyqEZbM@Qh*?F=AYEp zf{Dv)=dY*~lsDRHWBk2Ece>qIqipMz3szp|S^e$n{HGq1_0w8ouIVh$55I_hQS2LQ zBX4!57r`9vyOE4#HSgwVK7G%})V_yM4fJJB@%h!CefW%Dwu)oz7%Tbo7O`cu#RdJo z9-9__R-bLbNe{l9cd4Hido>lm%#(A&d7=4x?qBA2yg%RQ`sP6AaF3O1oycn~i8bGP zje}RqWw)`g+H{DgBAZ_{rVh;GzZ|a`+(`ez7fA!Tz6M zVvyVYIUR3CjI%%){)vpkCvtKZp9J=M@?3o)FtWHmGt!R*_K$Q)vP1>_+d|KelE80_ z&Vh}w(3K-qgXUj3Q}LQRi3R2M@xtNZDHE3(^l}Qs4y_o*W?S3m+(zaSn}?%B9pkY} zPJNyQ2$s!3(pYkH+-AF%KAT%E^vtI$it%<-yu+=#$x8Che3UK6VrTZomM%saU8Q7x zTnIcanhCHHUaN_Smhnoi(~ol$eEgG+-0a#(?dTwEw2oRlHqQMdj)*1R99iV-ZMv{3 zu}fd*4zONBTH^AH2Qg+JrKdIcwE5_~V3`lSIB%5^lIO#$?tDSTd%IA3YQ%02I{qr$ z^U5KDsrYcsv9t@^8B(~NyVs77(G6MrV0o!ib)v+vmE49y8eZ2HO zopB4*G|vVHFPbyA!Tr{}`fOjW#8-}G-h-twx&2-%L{DZ4^%$};--kIhFNqwylXu0& zM;fq4@85zo9ecG+Sz>DcFjwR%+elRvgdMTAG4tU45!oF;kzPDNllUavDc#Qavi;CI zyn8OAoe>Sf%t202F$?9zNUR4{IiZ`(c;O;z=>%#WEuu~H`Ot=m==UqQp?Lhj?y7zn z9H=I`5+cwnx{M}gN91&4yiFPM<$=*jNxjC%2`}}Tg zzREIj*S=z(eYKrbe`EL9nZd&%RVqnKXckZE@3=Jxf7g3bj$I^fYq#dw_9Oh~i=TGR zVeg`^_8E?q>sU?FeTS#tNCa~xTKYX+cawJQD{o4fPj%k_k?X!dVK}~;FX+LXZdY)Tq$&_&opjzr7))H4O{;dyi z9_`%0?zKe6%<%-Q{RjTbP0l2_{{@V|XCubt`>P&%J>aU?-F~$owVzkZWw)`g+K)f@ zn&)yJ&u*>>=w+IHYoFAy=4s$RmP=T_4Y!MZ+{W71F80Nonup~SKd}FF%BeUj|2`z< z6*?7Orr(#vSJ~HT=sI@Kjl0flrIOx)S9_25OVT9Q+|6L@cv`!Aguw%=%rk_FHm3vf|+X zaJYvhSLOg8I$^xc)@e0{5)%+1bJD0jg@uBoS7(Z%o_bO-s@+LbHdf4oxn;6sANJk; zdMvv)u@N(uj@OEmarI1D;kv`6IgjK#_!6t$5c+}9&Q9mxnmety{`Q{+B$glYXq7jB z`gRsSvhn*X-br<0%x~{7pV=-Q-`^lRxP0gnXn(_tZ;8q6nz?Lo8Cs_{`pp9_#@9CU z9iTBBd0s>PJ4kS@C~`T(ieZ zfaX-e$p_?@?wj=;R|`mfjfVh!Gf46Ag}*SZN|(QLGX_Q(#>BN9ZPgQ(KW@%(fF`M9Xcf&b`*kM|^e0y3Zeeuqmmh**4aWM^n`jktmiQ?<+C*81}UkzFIhr zne*P2h~dGtszIWLvccM>=UKOOJb=-7ADOG{XZki3o^ zn^rpydnWs05Xh12TH{i`+5R2t8M2n$$E4`R%G~VM*vGOt<@5iia}xOEv1Hw8VO7mU zA|?$sXRu_gsPVI^YGlB_=D}1p))v+=Ih2+8)EATAcLck=&KUA;lQaw^=MVX0Oqa=R zUK4@#13Vx-X*LYGF>}3e{7hkd)b~x+~;^mB*SA3zz9x;%_ex)7Q`|b?87~{r1 zqmnhp?^A1X`#3oIeA=L%{-%8Pi;NLFEv5LZR5f`nEdeu&9RGrHk&SOjFP!SjIoeiS zGT3h5lTF57{gq!`&0jt!<27F6H7$k??)$8NV8xO~OU;DWsnR7|ZrxVUuoSitY^}B+s{5IIn#9>U0^Qr6P z)7V8Ge$CiF$NO;+?rFG4o}KNs2ic0J<5lWD@4TM3k5}PgJMTzN>xVHd-%=pwE7Y{b zNu2$5Y_VI~!-?&VJiT)&-$Z7lk}BW%vIeE{Zr4_yB#)|VsOa}AK%eXVDiUErPL z_SNRkhmv#OW5)h%xNAdR_2c~g=iAjb#qR4*>c05K>A82YYe$a0YAE>1cthM%Q5 z*cMsK?o{q5hA%m{{Z?Lo2ApDM9)0vB?KYlRuQ&Tr^Oo_|cU=wr!aC~erTaahYR^FN89iNUYsphazONP-ruO)ld@x@#~$G~U#)v?5y zzshdw9E!I3utf%K=b_hfjgf%J0(KsJF*f(p=Vl?bgxm4vlzr{D+LEpFn*2-u!fH>w z^O(WD2VWfnlCN~OiSN%G=aeKl{cN$5XTlft;Ad=$&f?%dopLJ9%D+YUuh3!P zqW!)KzRJE%L)WoAKhD@!>wmobkFWOe4zJzZs*j0s_@)F&O7-#3LG0j(aX3r~eq&iF z(#?>K8%*TmM?CnBws*CZ8QnJosfQB?c|tee3<|Q1RRzN1H;K`RFRuq7U*6mTCdd7D z8h?F(yx}E({J<&n;}{H86E#=*bnGyNMtKYZ@;5P=;l2ja@z&R0eK`06*{mM3Y_SBuz%RzmG zH{Z0%|JFKs{>&$T-(r-{J*vAN13DLf@Uz1z6Xo!uJlxO*`QKm4uY6ooF8!z|`feV< z#Nj7rS7%MOT#&lA%s1nbjT{)L1&-&IoX9n1a%7(-MvbFvMG54{w@ISn!Jjd+HIu0u z-eeptLhA9PcA(|#M$RHr`tuD@IcS_)i+$p;oxFc*2|FNN?~|)ls#%e$Q}b*kubSn( zOR}c`np?4`t@;D~AfT~O^^^IN+_Cl|hvPuK$ceCyK)Ow4*`9UTt)Vmc(jA6hLfMkd zj?!C;l&q`QbKC}R)Nnwhw7+dGTPyx?>9XIjKgJuP`0h(`=kN{kIMhweidSl+FLS%> zdsak_eaRDJbcxG1y})8@cKE4rs)tf$=iL8kP6$Yd13=NP^EPY(KhfH<}3 zt9xIvnrEq!RdsP_C-fPyCcqyaNhCG>OVEkaxjmk6QPZEy@Muwx2@!|02OKWyn6E25 zsFxuR>Q}x6*%2G$%(t&dmhIYH4+B|($ATVd+6>9pv*B8tq&*1nS|o{rGbYcDkdDxn zNODk*^)TD#wUmBOtd!=gg-NdQtXY8ksJ>nh%C%v5!M0|T=D}H6x=EekF8>>`^b(_B z3stKaGQ?tL00{c&nUm~}x?|A(9(%<_fgp4%*p3j=q8`I+tv0W$mbh0FO;jgXG*zDmXH)iYtN*u|(OxwIwPMk`ZbuQ<1>fRCA{?H(_FA zo{xc;nvdj#tX8^3+hUsMc$NdNIjQbDY9ye~?7Uj@?6@vF^|6%|sl)Ljglg|}(@N$#!XW}q+rG*;rS(wHJ zX1V8ei<9U1WV}qwX*h4b_1Y|BA*x43j`L)>aP8#1V9a^>7s-1P7yD^h_Qf%O$L!>3 zoBRuBPyCF1`N3KCY{KcY$pkp3^}2m%Fyo|t4Y~IDmzrt;{h49L_957E-l%%G{F$TX zzPK!!_tp7$MDG!8>ucTj(l$PD{6QGl?z70zxB0<78#s@hEp;kyziV&IaT|JUTOay5 zgS$w-70blalzrI-lCq6gOO^?H`bcW+x4zB|pS*Jv2fwkh#y6o73py56lm1 z0NOSORokZ5?g(wnP#I(BXs`SRLt-{X#trS2ybe1Bk$RomNSjZxoI&d%TWD>9eK z17;Z@J4^9Vw*Ix<%>&l^^ucKlzP7E46Mvc8!YWe}IdAeO}I$EuZpj-uhY)NhYtz0iyfU2QBATq~9dNUt}$L$fO*ON5VmD+jx0p8@}bn zj~2(4k3O;ThPK?;b6~^Xhy}F%FyYzl+@`HutUNC28}hzEZ<$!emy;(Y`%el=_BW&S zroaBSL&uXpwYYvRA}Z(8r_U7kOg0jR(O_Kgm?v5^UwjVUtm;oC>Ls`9aAbw|!zuUQ zPTFet#+m!l%l{9IdR3#pB*ud!k@!=J>}e*+XWp_c0AtDAV{v-BsMGF1vZJ!$Y~OJ+ zH*8N^;vsKIUYpB6O<5~2zw-*_RTMQ-N4A6wu}|^oRk~A1_E_e8RRJ+FS0zSgp%1qI z>RI8rhY5!hf|FGq$xCl-3)?<&CSK|iw+Q9Sd8X$JxMp`a>2AYGyRyBeagJ1BFDoXm zJIAX+J4?L^WpyGDe&&>>Vx3F68eao6AFBJWoLa5(!76c!vxvT!E|+uhsyu+4yYtam z!M5f?=PntqWq=)9=Toz8yPiFu+>G6kENw3kk8Pz(rk*u}qifzUcAaKbZhw@JJ!8(k z;QhwTAp4yx%)j#S{y|?MVe?vXH6Qu`9wK6li;!~y+fPgpIMz*oR-c-EG+XX zPs5VyS?i8XCL20(&ElHno5zY2Ib6WdTgTUG_CvJFC!Lztp1^L+X<5lua|Nn&B>lu5 zseDLF(#~J;3Q_)uu-E6~THWGg&QMzIEiTy&)Sm zxaFsMD{HEoZLTLzacwgsn?H>!fVZ%WHM7H1&+G-AH@qU@I0eLjR12RFXQ}+&52)Ro zMBv()ieoTq;j_-Mo4l3T<6h4Tg6BiLJ-OH6CaZb+G18q^@dn7h`uf4wYrMw4165 zJJP-G;pQPp!E)-`G0PMcd#+EgLGl?!&d%N20KHQzeI)h51(*`Ci*2o_TN~#zYT@3@ z(wUKt!k@FZE%J&SL->|v0)-rCmlPnK;T==1*KQu*KC1=ucxE2(eI#m*T39vnH~GP)EMYbz z=PuR^?9#;d>7~aspKo>`bGCD-72E73u6fLLo2HzRxzE^rYHwfM8(9aU8D;bwTjqX2 zt^YzKe4ww3ItSS11rFu@hqW!g`&(-Sv%JL@@!)G8_q0A6&U6OP{N5;wfHiq0r`l=2j^urn#!z zh!I2~)YoM)q-P6qP^UD>Rfg&$&JndvOdfz$-{gkuG+5LLdM3~@Ng9q@n3gTBE^?Av zKi+V%XBv3ZEHZ2H=(jPaC&-sX?x%rM8Oqd=q~L#Vd7In6K1AyIB-UYCEf2m94s;^R ziTnA{kz531KKfx5E2f!;Nz4T|8vVe`c^OUY{CIom#K=Y5dNC>nbJ+6>M?TLB9m(W+ z>cY=|T2YR;xmnG(rW`h&@&CnY{5>KX6BcBwk*m=@!}ug< z<(T5o!b(16vQxSn=F2KBC+jhqfT{G1Z=nU&W9b;z0IC4g{O>tQylj`vG4S;2I%KmI zhhlsGcK`g4pBNXT83wB=fhv ztRXNKOP1YO5nMAZO4pdase>7cPvHE3iZ9s&VzNz^RMOoIi)qbO9V8Z!YTBJy3J2Mc znmHmVEe0HwyFg@9dOkY09o8gSEFTG``B?W4XDhUn9Hu1clDqfmMR!aQ%Z{bTv|F3A z9-EKYlL8@gL!0gD+Tp56_xjQK+f(F#@+Ziv&h7V0v`~D?_cx8K#D>uOp5;VH6u~w` z2};s=I@XPRwDz}dBK{>o_#U?nT1uj^d+FI;-Yp5UAE?d#p>u#qU2}L51Gu-P4;bF|G18g^b~Gh?T1`z)uge%R&t zbrQ7WdB8rK=Tte`vdhm{S@z|banb{?#=e-?PO|S}YwLMF4;*`b`VRKhavq#CwzKfE z{k;l)8hxG@FH>6{eEt33c=4Q_vQ9iXLGeJRH;WJT<#fmmkmY8MjqLPpDz>>xgcf8S zBqk*5%G%XIM?Y z$Hq|{MBs@md6`J6<;^N55y}g!xk>I=LAoh_@p5B|H&dw&vg+22R(2IEd)pF|0WLSO zlG0+{c(}oZiHA)N#9<$Kcwm)pR@toiIv58E;H~@U*^%?Dr^qD6=Lb_=GjRvpHpVYq z@mvT-%nZS2NiACHf`U4L?GY{WP>mBE7amWaJ+;%nk--L~CUL3b84u^=a~|U9Pj8U@ zAaAL^_Jba`r;DY8otw4hzzQ+~`4>2YTZgw6lNZKKeK82qd7E{og7cT0XsK%WvvHmP zbY#7JL!P;&CB!Pcq^Qy(7$}X{mJ6h!bS|q5LQ+S;?fFQr6$CsESC2BSLDh&?gGo6v zx4oT1TDrCscs`eLpvwS_$zcwBAr8B8+0HBRnFou)A_%i1v7Yc{?6P@mYm7ZmENiXg zeQ|DH)!AbS53|Cjm0Y9U+DE(pob1JNejvW&Wa-Rix&_Vjsa`EUhnp_J z^97@UpOZl6t6XZ9hdz!;9h7FPYa}AQdo0C|tvl(Q1cqs!=UH;)CSN?2u_(T%b2Mv? z9*!9JNy)M5vy5|Ns|RFK56B&>xv5!PHQBBf?4!x?Kuz`tRZEH`K1sh#YhC~R4b|LSv-4k+bq52qh3(~y4~g1vZiek zBI7G1PBmKC2c-EpLPEjrv9n07Ye$@GZY@h5{ODc<%Hgr#){o!&a1*k@Iv-_Nh_Cr9#p5F1D7PA9<+9P*3RM1uI#-5bx zM0>RX{gh~wBI9~}6P#Z2t{-XrMclxj1!h~zYIbw0CJmJ%)AA;d5-;0qi=7&_aTE6W zV%xQ2TFwnd%d*xzmKi7K-H(g$`FzZ|c=Ai^`f_c!i#gXSueKmM?#%ff$hkySo;f$0 zBaGDsmN}aGo_jbxR`!O-QtpHt!(o?zde@b+}nN{$2eMSp+#3dciZ-o!Ol0luyu@ZtS(yk zwr6SX+}dMZ*Cn$bU+ZmK+AOOrb)g@N(d$^DT{ zXlM40&WeL~IbUrcEAQkXo7X_>n0}+Trp7li`@oi=Q^4y>bt3HT15{ccQt%hH6_Uo$ zH%Z+>gXa#2R|a>~y+~DVE@al8V@pC18#+1Rfl3)Kv*t-c!=biKj!4uJgRtaTJzZ>G_gbEOwQoJtPJ@Gt4Z>w!;HJeQ--r_YXZQ3MH2 zGCL3U)IH#b-P(Mw>}o(Ckrjt;mMS}G!H_yHOIf!oEBa(Np_tDo8x2h zT&qcO`ho&icTje>EkmJh*CRl!#=3!&anOhNTKMXls`@-aEw(sNGI_Bq7hBjC5$kx-PLrM0 zxpN+bLu?R3hxMGN(y}FdNxAMHYIskJB zJ@%s)ODmUAA=Mb!1<(*;w~YaMKClWE&|_=8BYPGyA5DTUdyz69l0DF{d)>zY3+P${ z&zjm8Id)tgsclY=&JWa77ZnjK@@!n79m0s*D6Dy39w+6P z`vE8MUbO~CSB}#%U8JAA+?TBXWyXzfJAc3tQ=G5$CVkGh&ENW&+hwZ@D~C2RrsSGy z*tRQ<^|OJ!`}$@ndwLV3pP6rupA_=lQvd)TYDq*vRC`6U70$7FuDG3eiH>Bxt*<`Y z(e*med1mfmUkxYKeYTx8^4`3)-tkF1DKFTY=bW|`^x1bx(BLmu;lAFVvCTEd?jpSK z*KM?YaJfMCdF}&rwsADz@cNuV?sm<4!ETK$Z|3$G&7O1a_-EU! zw{2>fmE8wlyBsgkBmU7ZUjjrSy+G_LdFqWygl_-XWc zUhJ!_&oyA5KM%fs{WrwoCacctTJkNDDWG#mwF{rrHML-B96Wf*{TNQN>{4NyFGp^2 zK#+|C%YK%ux#@wF8#we>%rf_nTJRHA?VsjHA=@*N1T0RUBhYzC` z4p_By=~8RyB4vI#Ie2ZmxgAeV>dw=s1luVAo;j?7%!Wx`o73}E$Zb~aa+?H9R9~6% z2C=+9GN+8o=N{^DhVo}35>H>W^rAo>{wx;^)#8Ptv#Gny2S^F-yBMT&Uzqbhw9vUp zOg!HX<4+JC$;Szi2WtJ>4D^T3DQ(HDkdwZSj))%x4 zTVb?*@J3qK=K{H&QQPxMZ}bIEHgwapa*VwRjlt^%IatwVrpcE+od>_eBvn4&=)+gG zRItW5hE{(2I?*IH*0MMz&(9H=H4xgIfBz})9IhG7Og1%~ZtL3;ORU3NRl;5ld+dqnRaJ3-{` z8be*>a8pOyYUKh^I&VqjDm&`ZRnyzqoC0%Z6RSD5f_X0`hh4qK;EB=;dUY}nZGnS} z2&!4^i($Ne@bwz6@s|#L$nQHG@oBkqI1a8{8#iv<9rx}&@Si|@``xdPH{W`9+vdx|`|`Ku>m_blL`y%#C5F#Oo6y3_*1 ze3I{Cc5JKN+QeI~OM&dO8a+SJGygNTeIC=hwSDqsL$cb<>H9%pI!4aa=m3PBKJuB* z>|=cgi8H6%>AI9T#)ZIJZ6`g*Gu18rT@JbTM}ZszyD=xTcTjn^=Wejr#Nok?wGGY3 zM~!EjV_#0N*wxM)(+9$&G2!kb~lE5jItNE(K)ch&M(Hszwjnb)RtPtpU?H4 zn~6VjI|27R!tYp{i`z@-yo%5*W8)!v%l#m2(I-9f3d( z&HeyA_TI_sq+wg}>Mn<4EvqT6fli~e)zMyrhgQ>;J#K^V@UdHnK3Kv1B>6EdP<>*v@WVY#+hd>)hsP z_O};#z|D@NJ>NN10J_;6&WvKOFXjvh6sk@Y3g~XI*-dgji?pPqSrP|Am@iRW;M_eL$do* zn;WhCuOjr8vBx@UkGt9~Rpf#?b;g@c;BmW?Jm86+jvT673^Ir*`vIOQ(?|OdfWGRb zEF}avxhmeee>ggJZOe|AT-vS}b@S5hDw3x|g-5)ogv5r6CbdA~RC;CxLHlJa0k+6U zJ)e|)Pb7>)XqiB`-_L$3sy^QTK2&yaD!I8kJC%HKw3J{t|CmLCs;oQqflq ztuC_2QnU9uDhu>q1GTXyN zY!$CHL0Xi+bb&BiPDePv5^#!?YVj!B@OALA`7bDsOa%&Hg)B8UGm6?g7`%k`%{k6G z*7g%5W}8JeUvm5)#J6pwk*q%{kQ+pY)BfX5R~!b+L8v@eo6#!wYo>rEBS5lgos_i? z#r^9q|Jjbe1-j=aJmCqyYp^WTQ|rXb7q3o#`0~x^)gNA;-hB7&^rxTx{q**SpZra* zFTZ+odinCD&t3Hvz(;vrQv}X2s8#f9Qx=^4Qo!1pwKD77b&NiQoE!G@2*jT6#m=$! zh1c9mv5z?Sfbw2*zb~%&oX!SU!euX1Db8wg6UAg4F z>fN}O(|~vz=GC0ocFpPiZ1ut3Cj`^>ps~)~!|Axk=A;o>X#FOF8kc!$kwp(ya%OBE-x|J#L(Ic|OLhO8K!VO| z0K#gQndVua==q?6#C31wTye!dm$SBu)=@{cBz+BeiQ9Q-KFJ|U*~wy%%x~Y>C-vks z_Bm-XP@e1Mi)sA7`b%&(=lx8W5K-9o(>FI7XZD@{L*Ngg*Kx6~PwTO=KW;9;yd{?F zH0E|&V)e}>Uo%j*Ho+}^*JVg$gu~u2uF0VtHH^ODwX^Hl?Y?dRHXQpTH|k+?TV%w#wB!(>xZ>McFXgj?J+`&KTel)y83S?QuMJJjj5Y1SksQ~=vw!(|4v1|FK6={6qZ!|B14C4SC%NQCPQC@T48VW3SI(HD!wyyP zk+togeXLJGNRdyTIC^e;;KIq2_7A=_#-}M!CN8XeYm0dN#Gx;Tvgl)xpLuG1cppDQ zI$pH+W>@0D$ap`ZgX?&TbEAH_`St$Rxxw>SeHH3G@hhZldOCY-;`0WWZ=U_nKmX~I zjNHJ=m3fmDshq>W6?auoVemrJG=5T5UH$& zfJ3!o(U#R*Xzpp-vyASkTmUv4t7*G)jX_WRtTl)6TkCC=@%r@BC+?=IZ^0xzx+CD@ zRc+ZaVhE`jx4F+NTt&wiOu6wX)NW9O6Dvt;@v0W)RO~k)&Z5a?RT*SPm=9Izdag_5qo(t$oa4XvxLsP)$k}^@{m6rF6DO>S3QDfT@!C8< zOtj@^9b9|Hm$lOt<_cMAaWmHi$7V3qc6N?VQSs=DIAq)T<@kojz62+Ij6jZ=7A1_% zBV2qP!?E*5ZN6^VTJr%3ZTz@l?rhYYuU9BKCus6kqVWK5$P|TS_6aqTjXf~viC@_^ zv19L?Aw({JwS7Fm<5}w|1>*=xswC5IXP{DjwcK3RPQoU3^(9@-H{w4$Y>Kau0lMYm zrP_p|$o_*p{y`Ja$Lg-JI5sGS?AbS2KWhKLWSTwvw7(7L3pQ80bR#6r7!hlh2PIu^ zhZW=x&HnMRuc?)r2@XE&3DkYrpoiwiar97KQy`dOKUDS>f!KKSVTJfS~N)};k4k0{jm|IIaEQg+~XzWLCUh^Ujw7tzNYfJ${iO zz@_Dkb^luAoLeM=OL?xKuePu96=<{WS?#j*B|KJM!MT5jMl{;oaaFb2*I(vEt+KTx;4Vsi36 z?$SP1g3N8(aB$n}rSnSAZB;&ZF?s9Xax4M5vCreo5Wzy4eo|I^m#XHr&32?&bYu8- zA8NM_tok4cbbI*IcXhS5wH}}wdSNpU4l&y+5A?R2`fxL*)`wGRN6&otJ@Q1}GadH< z_~7#j$1K^DLd$iW|Q2QD;%3SKKv_3_kspZ8=N!)9?GDu>A-_UwNn0>yh%8 zw_BG$zkN;X7(|;l&-OXYeJeP#ySzJxOCWU52K}V3t|yM>1rB<1i{F0jP1|zm8`k@} z()6Q?=QnDrj(X{DIQysd=z0^Nle3TRrSt3q@iyeIsV}(Y2%ax!SDZ`bO!1 z^=?w*x8^y00sV14(la^j=RRCl1?IM{WcR5*<}3U>i&nZ|l{@AotlT};92!QTG+ zx$%`bd@Mf2_Zoi9*uNznGY;SQ`mg`~hxY3%>Xec7r~S_t8)~uc@RQkG!8>aoX0iGr zB38c&z>OsbrMw-K*zV12K)in14}Z6dCEa>l%|6P<- z(fo}qac^$O9i_Ipc<6mY>wV_KH^ao^MjDRX^x~!zecVb%UYc|+bun>lt#FM)$rD_L~uSPrI#RK9px^Wh8ds;xIcO(U_%$vMgn6|H|3 z)r^YoygLR3e(^CJBmJZui80lPOP9W^b%$n$TrzziJGP4ap-PNIu+h&MA{jKWcDeLg z8p#sI+<1J^0as%V;%%y==u*ZTh?B`N;)>2K%RXLc+E0dxmxus+BKAol<+=i=i*OP= zu{N6ejICwo6<_vVL88w-ET}|t@%wOGEXZQuXxRu zj=%IenASJ|bK^L0p{Q^hkK|4$-*9%@f>2U5(;YcW!3z&Lc%_o;M{@2Mi5+LVBFKN8 z=Zw$J;fuJLj|3DdUL4d)4bVrE9_Ptk+O)zEWb2zNuJok8WPYAAxCm3b zMs3}wtHBt(4k5eTdSqXgMT%^1D}>6`$;F2Ou{G>LOkzu)xB>&FWopJ{d(Q_}71ot+ zwOr>}JWGwXx2y+CBZJpKIVzntED`%cgAPj9~Y{&e%%OP`zG>Kxyfv1TBFb+p6(dv}=dz8wR_j&A+b}rdJQjOj`gusam3z&L5x}_? z-_||nz~`d=XgTMs7LCDC2%jk(`8a;stG(w6O|q5Db%aLS@$qBE z+xG)?QB`|UY=D2AEe{U$h5Smlx2^3V$7SQgez>+*^jKE?+V84Amox4S@L{oDu+GIA z18my_n|&%X|D_?Dw@r5_z4k*sINfu(BJ`Zca_*bR?2qB^(in&z#v=mPl+@QH=LOyG zA#9k&yXSTau$HTz+{_w zS~yx&9Cl&9F({n_n3T4wDqZK}zK+pj3CjW6%~CFgxd&QOshx*m9c>>+;*<@2CW;(Y z+BIVUt}w%iO3etqFey2FG(=1PUFPCt=af+9D#VZh?b5d{Ig(!~RrkeGX)5pcZl41m z7N?9WoNR~jVy-%4z&?3!%vE3MHm93#no%JF8j2G?+UX;q!|ir2WPF0sv9YVoSoro9 zZzx~f4SvIxlLXp{6JO}J zeB%o}-YT&Bn`Pw7O*Rbh{SUA;58OP9(imGqeK6N_$xkc7@r6QyHfIGcQafvMVlq(j zsO@b{ho`1D$sg*bWnO@6_N+t>$IgX_nM<>XEu~YlS8=3Fl*F(_2KVAe`Jos5#-B$5 z2{3ZpqsfKjG&~>rBL~`H%RIhW#ZwGb&VsuSs6Y>h@s>T#dPadqa;|~JWQE(_7WPXY zz#RN`(mB$ZOB09_EptHZ*+1qX*rBXAy7ckqKtuqu-`>x2oW$;Mh$6)+nG(WrQQ}4d z?90|yZgDG==TNFGndU@d$EG?D$^5 zGC1hV+wwMcNvt2RJV?(@jV~-p;5?Wg%Vt?0kHn)dBrkD{Igdc`+=o48T;Tqx%Lk6f zF#*;GDfpa0{HPgS+A7Ieac4G?X^7J6gJWANe<|2)=bpalmIx{&u&9olRmx}{SmwhU zM{svMj919--^nBTQOyl;F6~@Ftk&!wP$*N8V)B zYd{-qS?19}+A*=aJ$s;#jyQWCH(H+N&NCQJk|gu6DtW|SRc((|wy0;yk$sw40HE>8 z7{73ex`4*AN1WN`d}Qtf&l|LlPd|0|geN@VBJ!H41J{elCBV5kJ^$?U)90_gJbm%S z*QXzT{Q2~!pZ@Li?e~8?y?y(~)9bIlJ3W8#LhnCx&hOW!cxF}Vl`m`J<3Z40YdPCz zrd%JLERJ{OxeYuoM&EC2cW4@4jWb z!#c2urzbt$<#+G#4jy$s(bEU#3P+rY{`Cf*pV~x`_gMj%Vnbi&DLNk;=NH0$Y{B-J z$+>wogw-c~FP@UUMyR&z_bwPxC8KQ&;I^sZyX{Bw?B#m(U*l}|1=g>A&l!DwK5ymY zANeQ_x>XO>@eZ5lJ?3t&*vHBF_%?<|rAOzy^4D*ba6X+Ihf{~N@1x;sH)CB2!fStI z_96Tck)s8iMUxGbJW9?_{)Je@4 zD-9goI6TMRt8k=V{P}_vTeyLg_!N`Kn7ywl@4j)<`uv z)?llP%v%n&sC}xoB%yh$Uw_*xXnoeMl{f2()omVS2b0@lnEf^;Cvo;SzSf&cty_;F zDaY2q4m&<@I>zK5$*Cx2zblS(6O1j=-Ms7ei#NVBoSK~n<657`=~xh57w0I=;WbIEY$eg;8%y;@zeRQIv1SlQTy0?6 z?cR~fK}Zx3ooPb{l0OFGBwod~9s_M2j5u(d@@r+z6Yx`we#mZ^*Ygpx%8KoxM8Y`- zxAkW`&FEUOiEZ-7(=UI0y7BddCp_VyI9fLP@YZ{co0q2-FJ7I#`ue-mPk;W)>D{}Z zPhWrc{psBgKc8N|`9?3QdOyKyAL}zKm4C8be_E5gWD(}Uz;m0|KFe*~^nDqteV@@K zzx!m)8qMI3K-^vI!R>RUV7_KwK&8L(`dqPbHO2uR#9nqTSDg$r}xkTREXsgEV5>-W9a|NB#R=?d>u(f&H zRg{Ub7=-x5zMsRRIR%z?@mD)z=cI3X%gRbSa zQLl3Q@yxZR^hX{Tk;B(})wsFMv%hhRoH(<+t+NlcU6G{JW0xC1PP^+lZz~UY{!Cr{ zw>f}y4wR;!ZHJw4Foy0kXnC)r$v#7U#J`07K5(6Xw|(932Bf;?cL|U6qtnOxeoDXR n_*cgI|Hh||vXgL-oS1e z@=~DEVXAH50@>!3$}144A{y(jISO!%;i91L1_F^VKfb_<8cavPO=~+XJ$FqfI~Nse zcXKOqcXQw#2;{?H>0sxg?ri7e?#3W&=)(YI5awoQ@B)7NvHx?$!~2r&|9^vrhvz>Z z`qx+fxnb=09IZSoK6{HJpq#>96r3g zNE5kix#ZaNJ3Lxs*@Wlk$}@8&53IX382!)NuHzfK)rtS>7Vv>)99Ozc*M?e*;9U3n>gq`|1L5=}1tx})l9IUBc~*aVV=Jxt z2<`0bVt@W*)o*k!{B!E{{Q2|Pi;EBBFKlDZc4yQmC@69(D>a^~WjI(DxNVJQ>j3Ri zG&W98NKRIIL6KNl$@|H}H=hHMM-}itEq-j?;=h{r`N|F);ql?aYd5#5_L`d;Z~X?> zJaFY^W`IdtUv6NHc99Ob(Hez1u0oyd7{jM`pLZ+t2JZ`^Zv)@`)z;ND6ah7xcZTST zRSWoDxsZ!_SD$}!TkDRD|N52UlZ&LpeLY^Afd5};pA|1E#@g|fuwHNe|9*PTHB`L~ zMx_FI_(rSEs0t8QvD>{W)Oi}{3b<)$a*}BvnM)ugM8FUo4zq=pypISqtN_`hot|nL ziJ$rBn5-DjqHe<6vh%5qaJU6rRwT(qq2@3! zu0|`yYNwo;F4nKYoqodwik9f^7rK!W>UZOsDG2qsl3rDNy3a?mL(5|k27&oNi(R5*Gs^IC~1@o;?CAd8I_B+QY#y%kekD^MN~VCUcv7cy0pSNiky z>zd)@jlo1K`KE;JdXrQ>d6KHb^rb3zb~_x|a;zZN<6Gp7*jdPcy)k{RCARrTjEnp< zalgh$kFw^=Bp%Cdh2#tCKc8bY(mpF`vNGmb=b?^O-st{V{KJ(7}CfWe9_bX%~^{7QPBV?=XnZ8pz~0Z6~)|G$wez!>sbdQ zIJwA6e3Tj9O5(yuXTWCB^xn-H(G{JuGI{O=L$|U6)>?24igA7N0!Op_&q;-2yp#G- z@Be2wfDQ21y5#UW0<%kcmK3vZcMao(qNfLC!Zup&xSPGOn+EaoWPX@3c$!_!df!b? zl$EQFDNkuYJ1J37TG%qfx~)JvwRp1BF5xA$qSv;m=fKJOz@L_Rr$qmn8j?6fGDG5f zEaFIPTISQ=x5DUmM1LvOeRSABvPTspWj;8 zI^SP=qvX5;fqUB9A&rxQEQ%y(cggf4Gr?RmhbS<4x@u^@((U2hC)se3anxZl%g||& z*8@Nkv1L?>N-8Uc9F_Vw4QS|oW!O%3F4;-ettP(FFZ81ybaT+oEAIQy&&$DA_|%*` z3SX6u!)4R%gW7zpsq=X1A1d*ehYvLR zqtymKJ)C}E7w~aOY~XY8Q-9Qw?=Lo;&H93Gx-YVtf0lWA?oETdEkU3;>=_QA9{P$e9kVBhWlTyeNrxDk zy0>l{?I zVg@k38Cx`1@Fv+skF*HXoONl13S%@uB%^OyJ$Z>}f>v@WrC1DY?+Q1S;RrS4r;X z-4W!KwawDsy_!36^ zFO~>^`(Y}+`HpNk0YPiy`A5U08BSuX6=GvYPo+N;TNi}h2Ertt?{uEVG|&C)9~fMc ze0ky0xfFo`3Kc`^W*Eo*Gbs_(0N?<})dsmM_SI~*@wN%V!slE9Ad-b;4r;HPaYmIP z4ql&Mub(>_vYlpny{4d~WNw89T9J;-3@pakJNpbRm=)WKaxRX&E+i9B{2789KYP_j zn8`2QJ)<+wOTg%0+S1-Aw}oZioKs|hx^wij%dJ!c?FEBLA^%pKf?{EC^V4JKWFrPW zXKmB}e;`s>W~lCvIU|dHzA!@;wV1f`Rjb1;jX=EY2S>>LXYLN{bRNwDnW+Y42kQ`!!Q;af93;`2`CcLLsd-2JUxt+!tYPqVd zTWV~kR$G4mtFPLFEq|R{#KZx5vr7GWX8Nac{*>a~WH<{oh)^BX9U{6a)O&1OgJYf= zl&52R7nxezrC6XqEq#xQz!n(ItDU*AG{9SO zZj*v-zgEf}HAW8@QmmR*ltLagG#P^AR8RDGGz=l3Y+2E900RK_jGrD|Tf@F6xl7*Swig*_j)r zL0A|AWq;>L8qVsS{$HfYIV186fSNNROe+&PMFxKwgKyvSvZ?9R<^Qo0#g zkY@N4sxaq&7{98Gffeq+UJ`?_4X(k_`WYrO_~}cGycwa1d61QAk%~g$v`CqlU3LLT zT9Rz(ElfIVE=F%MYw_#AWN2^KaQ~v?Hz;GC5KJu@_7?>PaoqO+) zQW|zS*bO}mS-gUUQeR$ZgMvbxfM=`I4?_$iqG3(qQqgJ7BGuz?G0vb;L3pOLqS7c_ zh9L>xEP3%VCeX5{&k2o+>ADfD!Q=gHGT~inWm^??J*ta^ns5i@99N{eoM;~fCU;RI z+$hf27&Y~3xC~Wa+_0J*gj=38y=!0PwcEt+Y~mp)xI#%|_{kCk2c3;QRmUoO!TZ&9 zP;AP3A$t=YoUTrtEV~z-KQlXn!zFry(e<0^E(fQLqz!ANv1X1=lMREpH}`cq^fwA! z@!)R@@Vf=9Eyg*>=1;bM=90}omlR4af$lFy@Emr2lyBRsyP~6CWN&v{8@Cw-_P-Fb zVRMV0jY^+ftwj%f6LR}gn4eL}M7iz0qECi-C71F(dAQTWXP^1dYs3e8lG^vE{X>b) z%*X$=#nj^dYp-7wL)oLpK)Q`vU9C}N22XZOV6}ZhGvLomcCZf@J=@B0eF&h96LD^s z>v)qkQ_KSbn26P8x@WE5YLwW89yz~5itkk?ZPJC-Yu2Kl9M@nZ^)ZtD5J#j8kon%2 z+~?;$g=3r&`1G*fEl2fas^I=F1Hr5zn!heJTFS&WzG(X%{!l1-0jg^b%e3XKlFNB> zn&h*QYGbto_d2O-y;A|GuGRK<9_rQ?6c}VMl8i^{hgzmnW)GEH1U9v>)(@35UmmOGKWa_Jk-dINK{)FeQTiKys zJ)iVwYilPJx7XZZ9M-Q7Br6#jrv2Sk3y2HGBJF347PT-hU0+`>gSfYe!Z-D}dZ<0W zy%O#)1iOD*qxml}b8Yr}WM+=Pya5_*wcek&fpflBHPY`kB4(4JCMhUI5iR%|J(b)1 zqwfY^CQliQEug&yIK*2cu=BvVsN4$%4*zn~G=3KzT zo%P9|KG(m;Jp(cH(pIBcuaYYMuLWX)`^TuXL^+71Qg=2dTAX#p#HYkdY$#J=*$gv! zH^b+^E<*+O1Vlyu6L-}JeMHcV3jcE2&^b}R>TTcNT-8uoDHnLNJCf3d`#>}ECIQ?? z&i7WYpz425m~W43&@c>;a@e1o14C1?PyFF>(KC&ODkj)Py3*#LZrT6jI67dVC0=%7 z-5~QQs`JyqVZcLEu)s3Vfs^0iTwg<(H^Wf|t(RYkZi-)J;+ zu~A?AcNAv~+5g#kpIsn9q88jIR5pfWY~Lv8jmSv^Gu|{ z;w*eN!_|8!P|oY_+rX=K%=cENE^!W}%r_FC=amf~ws8nr3XZU_PG>cul*?YF>Q)V( zi0OdTKpY3_zWRzO`?Uj=zvKp9bDVPc6|h^C;Z#k>!0WL0Ht8Noeh1YPs!-7&^};qH?3ToXgE$$lhTIe5xG5q?jbE0&y^TqK4KBj5{{yDjh@B6$cclM% zP4W4g-5(DLJ?I`cevucc?=?-8=Zi;osSQX{&?43-Ksb~xTz*_L_7P>ROQxD{oJ<@i z`9x`I{MAElcg_sZ56J9`5FGi|o3+g6qAulHB%ZkrcauetTe=>(%80Wn>3!Z7R;Le? zy4ue>S#xwYognVUd72t|jw3fCVkZk#BYim!H~GazEy|4`U$HVgJ8Et-SOmq({)?~k z=AqPo+8}uD>U;m4dd}*P3%Tx9&<~_#|A*UU!yj5wS{M(I(NzL@y`9xiTF%VBe^_w5 z;d6JZ&;syVs1LnpsrnW@YF5SJO=>?{d1&iPSiv}m%!4G0VCHy_f*|_q4Dk^*9v8e6 zB(=_*SIM8um!(DdJlVQ0B9H|E!Uen42UrWUNwemR#|#$LZ);H_|;-0hIwd=1x`d14X@wrW`kZ$XXBEw|3$kgb>z z<c z_Ef9;;~sbP5po9JBQ$uLy=LAW0>L|9LQM}fPbBs>tz&%E1||nE5uaj<}FXdJC_fDb{BMHn`io+S*!|U;oA{HO&906&>CH>|s~h zktH=|ij0gLpPaPXoRbOY`b^*o{KDYJWM{Ns2M9fj6WIpcnJ);9qDPV#OLKA}Fkff5 zE!u?tNL$;)Y38{0=XhlTI1X%0!TXAgvCT&I=Y(jzV5`Om#6f3QY*O}$k;Wkb%^e&A zQkA65ihK3_L<6D?;*=z9!$D}3%)nGD#(9eZN~ZaQ3HV&ljwlOz#>O=i?M%_+!OEZp z!qX>^rILOt>x3lw$;qrlgme*)nQW7NwKxK~pk`OF0gs21j;Pjt2*ombw|PK=Tye`r zI~U;UOZKz4c>D;vaURGr=>4qAEBSr|gCz0j=fw(^bG%4dYk!~qmI==&3>1~^<##p2 ze(NIY+y-(h4rUVtxFE{k?{%@*C)#DJX`yKE;th1W;Met@8XgNPbe2@a`D$XQxVMnC z>W5ia!}l`Km4-<(k|=Tf ztE!UsHiLfA?pa~$-5Z^$nSqYEGQEZtWYG-4_ur{}_9|SD+R+A5cr2MHB1uXcftqRj z*K%y8_1@$9yezTToWLjkYU*l=-6ZeQEu+W|Bp`x4;ciUJ~qwQF;A|4R-!_5i8|jek|Z`zsRGim0Ex$ zLEKy0`I$*JnSMG>^{c2}0P17X?6uM-EPB$nY1MU{KaiVl^V)ZV2DKB$2Q^q7l0|38 z(22JvL>)4*Q|dQ?*yH?JISwHu#bc*20_AkO>%3!Q*x*3*{i;DN;9TOwA(2zsFS>x< z@a^Y$MJu^aF?eM9!$yfQ-B@wbhffwn_P^W39lg0=7-T5z?Ys7Y7ty0?H%gybOx{9s zhMe|C?-QPMD2nV043rj;(=%fJ%27M2%g1xC8sb{Uu zAg!T>F^VPDoJoz5uLq&L3H_jHIwq~1!ceC9X~nxI8^*vsMJ zL^)zH^r7QNz4Uu@R`gmP?r-;vY;0D{NxvN9PzjFSgWN<8>T~v*4qG&S+JC=1{SA1D zxaTN;S^z>fmnl*A?*TE?c`R!~_~qNQ=S4W9ObqL&86d^63{JZPh5m(y1;!a;w@7xw zN*MsDV|j*YseWUPCCITJ4HbW?y~d)LTRG1E(6fe})n$*Dp|ckzXZtKesf|vw66Vsz zCrQ?ZhQ}c#dtA&qLmB846cm>WD&rBYKJvsQ!U3husuk;utPzALP>tqZTA$Hmk*^E= z5N)$BFhMIFvR9(W`tB$C2V^~Ekby71Lw8mwo*vsb1(5P@^IsDxw0Vl+YeD9dkv(%R z`-~X|)dMMDx7m1J_$BxrX57Zxp|V@O$h}9h70lisrMBWIpgbR{iqwa`olET?)yr;1 zbjAOA0Q69hDO^cHQ{-kd%7uO?JB#Z=0;(}H72Wuu_gB5;Vz5cx>JFv2`RaH02|!PJ zYi3N?xLW^K78^BGsznPCip6C8k*2+gp>pk|ul=X|+)R?jh^$5M{UL3=3O>Zz{uh3z z3I3<@VBb~w*DTDJ%Vjt?#cP!g!25M7xE8`k2EO*tCUyH9RvwM`a4M?;(`c0d#Z12-Hwi-uU&+dr z8OEv*1#w#ha!RkIm#7V6&l)E+lVq;p<%130xiOvO7V6gs9Uk_;1OOk zs-c;8=@H>~-RRHrh({wVsfs0mvJ)ePuH#6?~On_Fro~XAZw(=BMVEe7Z-w^no*&I zS2Ev`rD!|V)jRa&iU#?A&-mQRGNPUyu|izIt!MlqYSfZNv59X^O(0O5q6qyIW*Dv@ zKR-d0cx;=QyY`^yLjh$ppXjk*?H4Vv8wqGSxN8(<8+=Y(##b5qJ5Y``&?YFI;UXMT zPVfIt6#3mP!D=xykkbUN=YN{EoU&;29@5o(%GhB!tC3?Mo<}zzzXVb>N&GlQ2@n z$(OyHu|C37D+djS1qUGwf~=v@s~qxrPqQnSNazL$)n3F2gBH+Pj7MXWE{5TO6#!UE zN6YXycb_-0+4iktVz91cO|Nm$6ZnK%Xgs4S!M`2qAm zeV(3@r7g-HBzj?L=^Nx5m!9a)t0m>CSSsmvh9%RZXGi%AU682|Oyei1AU-z{8KcvU zebi}T-T?{ngTemVCT=~nMDaiZzw+ zNf3Ri>0DEk*dF?WthB`&di+}BTV+>tC{Y_eRKA`)6V@t6&4zNLyNv=ygy93+L5%E*8zF1u?}O-8ti;{Pr9mj~>Xr8qT`n;1 zyV)r91ROlso_smUb`AMS^+F~Dmz<%saVwP9yaPE^*yG*mmw|O}ktx!cG=9ggUcIYh zuTPR1+&23GoBvNv|y+#q`>s2lq!_}7+17MF?1yK)UK`v*pnj3%9)!La+Abm74FFrNN3W(C@E($R=o z9MyLc@+{vsz!(e2WTje7K|aVx<)DZ&Pwl5iFRGhQtEnX^=?4c1!dO6|vp8yUaNNM0 z+5A?7gG%kh4xdZmCXqKDA0n6EdT%x(mjqIM*w$Zbq*{jRb80Ssfa1#Q-|;PV-n*H! z9BnISTG(MK|s=3g?~AvE<4=7(Dotx&N3LPt+A5!LSvB z9+_cT-%aL=Gow+tzo5Uvulb8@O}u2PrPuE9}oN8(s=~278`0{JMlPWpZ(XdXG5Y!;MCb4TRZNs4@b<2-E|;yvW;~j#?uQ&VO?6 zW}c?#NQ9poiux7w0;+yI@TvfCF=0>Pr3GobOu=-%9*Vqbxv_m%r77h>OOn;y#NjG0NCH=bmwAoFHe&0Z##bFOO_{Yg zmf|>|%o$e*WMNW5_`n|`NJk{Gt?0B4At_+QS*ID}-Ku{UjWx)4G7=O9J<}%X@Wfb0 z=~`Xwske>y=XEl(TR|x}EjeEeM9YN~zmKfx=24FokC+tdI*lz~qenaqlY!;V&VtgW zm8fyHBj!+M`;CG>{OT@Nfzj*oUQ19zc~w@%YGMgQ^e5t?5p9Xff(|p-V`En#;|dX=WJZb*VJ~YdfIj% z95t>Eb})I6DQ>tt2b;Z*xN~+|PzdMriO6LU|4L<+n6*zWIG;iTEZ9zjaV01C{0MTG z^SlP*wDGrpWi|tRA0`Y-87Jh4LHgT~gCU5bzUnVJYl{^v1fpm|GegM&w}3z2$bQPj zcf9dSxZpec&XD^=jg#<|dIo+sec~%YMjB&~6dfLe@{9RJ>kO-eJhf`=5`N6)yK*o- z0f7Z(LFX=}&)Czu-$d%&_aFW$fETu~mJFeA@G$I+B)91A-Yd*23sd0(lou9i@QGPx zu7%F1#;YkvF*p|H0_^~wZgB;`2Jtz+4pkc?y1UyNBWh<7`VcLiXJDv;1W4OaSYn|^ zjV&W=HmxxQ4}>t=rzLlsgWz#BCmP_nMWUIg9)eYW`=KU4f~L25F60LBFhsXBjhSE` zgBX31^~o>uX;HE4!tYZzzxhicZ4;SA-h+4RX=e4Yi{EER1f_RaZh$4m0KnN!~$)I-2*GgHG?QXn1J0FVne*738LG{5`&SNXa(_;K*;7rR9iug zAW?^l5qt8x?@>z@z7f>mPi;byW#@K&<}JHK6845gq1qLT{IbGN(nz}&oO@Lbs~SCw zSLi(fbE6lqOgw!`(NPYSXs>(aA2rH^k%0Tti*)u9fP7C(&CWgpsC4ZDbS*NN&p8sE zV{@)6EzwUC4V!FbPVe7J@>160^OEgwvsvv3K3V4qm=l*aldNqR%aNa#n~DFS96QD+ zPXR?@4K{nO#q$Cz`o8P(y!}Z=+tJzEPKvwvZzq87%3&tpa?m4jUm*%)-CO|U2f zfo}!;U87A_^FN8N91*`wK}#Q~p|2=K{{=svHXNdiU_#!z3;QrJ_yQEzKZB}yI9bwitrEALZaMdG$opF};30Jt+tPL=jj3JyAdd0x( z^49LN((ng-F~stZ&&Z;Ge?ZcgA_O>mzHpkhEKDD=mBB4Gdo_gpZrsU*T>pq{EM5mZ zTn1bW!U@1^Wv%z#bHH4zHBhtsS3N4-e+6tkoKu}aur80umZ0|?C3vdTnefFE{uqgz~U4GTjo10$X zHSJXnu!lcYw7cpF?!*;Q7XQ17m$o@^afFB6R{wDMaGz=9y`2}#m-e)l4rJhW;FcK= zpjW{ryYDLSQO?%CuBk8WbyoN6Us`r!3+)zH4QlR}VDEktaLxb(YKaPbm$P;}e|1%f zyR(_<_w$Z*efbi1cBcyaN)dhlNkhfX47m3)q|6q5_32+G)66_0nro?NjYeU@-@ls@ z$pLq}rW^F3N9dn>)@nl+e3oxbu#$mvtaJ01OH?DHR;dH{Imz`djzDitv?#-3a~2iC zF4@>>Fd}`u(bR+i!%vPnuFN!?l&f}dR5It>?&0n-nalq;e1n4|QVz>zx&Fx87tn#Q z@4;TZ8R6(|e*^%F$FoM=3So%_tCRW*!E9Y!{<|T7Wy5cJh8E2Wn(9XW!!$Nh*K*D= zpwamJ`+Yc9%dF_gbUt9;nMJb~Brvusnp&7@f*3A1NKO^T6Y$wBNNe@XjOY_ATfm-& zKo17z(;lY5t=G=fisVv{K=Pl`;_dTCa`?QIcnJmYRWn5IuhuHf+L1&;S#ZhM{DG%1 zFj=T+4Oo63meyTSEVyJ${$N%{AGyHPG}-WHxWt6(9OOjlp8NZG5qTyh^Id1#y-=G^L05tQiBsC6rCn0^%n-AaWat#@9B@0&Ycu?US%8XquL|HDQcLc!$+Pj)w&~QE_ag_1{O%`@dCacO-Zmrb~qev=9lkvq5wU~!>tz%QlO-u80>UET512#QfIpx zM5Ox6muTKH+O0DbkL%m}|Ln>bz+-IQl_?-tLVk(Ov zgr_tb8OC3|w;_h~UFG5NEg|*yd-!c)ZeEW_%4awthAvo;<}`6 z0F{C@G52Wi-3cx}Ah_X)8f&Hhemaf2Jm3 zswRd213WZ2%jKG=zq94_CLlH#HqJy3XtV1Wnx>GNh18LOu*&$_o+uHald!SXsEH1$ z{|w)2VVGK9ul&JhV^5Y+!m|J&HI*4pWf9(CQOI2P~JK24^mDRjq*}y>PpS$F2ibp9OOBX ztpK+HJpqSEBkR+<>Wps}ZVn7@FA64ha|jbFnNpMLFWl6NJ8m?npC>a{nZ{mowK6S> z9Hzy+emY|&6MMY(`ze#hCqr1i2&r99$=M@@;KbinaKe%wVXg79uwc@Un#@lw+^SuowtsUS(w}Xx`9XQXePKCY4H9exwW_c{Til?iS{8A_MRA8 zIa65QM$ozjZhf85L)O`2h5=V_1=b<(&q<6&Im^2V7@3+yds$(&K8JjE=(gO1-Sw??p`QxzlGSo*& zU`@97{NgihL*&qF^k2`g@R7b`yJS|WilHeWY2-B_NunzE@4Rnn;nv+AkmyP1+{JR{ zo*rz|3uae(Tb$88_8H78#lMZ0#a4O_9);;8HcmHIqd~uAuNOv4$)-U|@=lFWf9h;| z|8Sx+^kZcMY|^;Fb!&5ZIk~PJ9RZqmH3lRjbxcbR2>v@z+#A!^Gu|!ow+0$N{dRdI zduG8luva^6Ii-d@sh<<{B@oq-W5+3Ts0xA_^Iz;TZ;Pl=W!RviR#F~Dzt^q#r;oh{ z>tUgH-`C?NfI+1&57s;K^3mb`w;cUB!vK4dWk zoLun${QN{M84e!%9EcA82;+t#<4n4N&_GJ9UtCYG=>J6BvS{gkMblJ$K(!ZxiGi>^ zj^0sD2@^cjRaeWfp8ME%;*%&mqk|y{LXO(j(6>4v{XD-@7-1OJ;UmYS9g+B$yis+$ zXVdSve)2gq)peYL*g^Pr+4kSKuz%fPUTp8Qud%i9%t9Au8%hPp*vGwL(v!&=hN}eK zenBcaK*%`bZTctI=H%NG1GT*2v3FwmbtyAb2!~b+L>)M*oB zw*@_rS$3VCgc#av2OEwWx1@IbwDj^ZuVr&NXVN?B;z)obmKT5Yx6ecfpN^aEwvmjy ztm~^ruu{5dhVbTT6II6>p_7V zLvM>qNH{v{XWr3n;muSvnxV-Il#EatyfykhzSn*;pIzF&5m_Vl%z&P}B*4}>7)UJF znjaSoNhc!wf%tERC$#_g?-Mp7H0R*ABN-fA@S~5x$5S&iX)_uXA7;(bK4HRyL}R=| zQJfA9s%>Mz-*LQpR8K?@ey&rd!*a*x}vgG{k z;0!lfMxNHM+NWGqrKP(sTmbIEhN!(v`)ae467zBCgeGj!?2wf)hcNi*C;D=v+ z5SKU}_~pGDrG_(IsDf*?kVpN0=&&h(N#|>H%1k%{S~g7@Rw~)7rWo-^hEcf=Z!_Q5 zo@I)v@Ipcjp3%@jRvsf2_@Z>Ek{?fj$T$fSdatd5CxtpCc{Dl5Zmd!=GPh+EEcuR+ zK=GYlLXR|t9vDt$L=F>&^=!%H1v0@CKuocf8bw5A0+RE{PN2X_1Z^Aok~|C_AI%Z0 zy2WSq7SK8VoIU>`N*8`B^n(f?6^4xe$4T6ttsk4Fvi%-NB&-lxey4?stlFWdSK=!= zQm)86fQ=^=(>=M5F2Ide(JSv&Tf#7KFRbMzoA_ebPfb&H6lJ zDw+>d0u_(i7pwNPMNj@z9tPPN^f<1@AxtHS{jl0uJk~h6g zIO5lzuNb25o@_Lrpm(yxxkbctzn0=EMBx&2koB8Qt$=j)E4{WZM^tD>>q~%M4o~30 zdtn~Z=PCEYV;)_85wR6W_4Ro50(t!OT*Z!c&9g@u_LD;3k7F#;_)E}16psnKECv&= zGap%2dwUBF6{AfWGyS(qAI?0AOQYenJzp&rW3>WXcxKL=3oep9-W1xW-H=JRecUf+ zoROlVdfmi{SeWPR7{nOp!iw;t6XGQCF^O#^Dq|84#i7)xue`%@uEX(4E#Z38b|cyl zC3>O&@n|LjbE5@06FxO!?@$et-W|ZD_~~i;w%|PQ=lM2(|Ee5OznD+nT-f^L7yvXp zxN8Z(*1>#%({&?871K5|=U%<%wOISVk1@FSan?F6j&Xmb5pe4{pbdl1__ZIo&OgLw zi5viTj&&WMegg%t&dWQ-j`PXf#-s7kTjD50E@2hZo&tEWPba%@3fK=6l)l5Yc32sB zTg4n#Fupbd%U#Kt&I%Y@E0LZkO=NSc$EgHVm zY|v>$nA+b}+ai^LwJ{RSPEvl*5*;L+by>-aS6(8%D?&;F@m)tp&| z=$I_pJ=U?q&yTQ1<;94Z^QLKUu;_9EA}Bx0(mtC}yTvT%Dk_oNM?se!be6YCPRs@n zSo*Q{dl8ek!QRjP1ye)KlKKZ#FSE}EIvCPGh;TKW_t=wTxr2{Gx5}Ca7dsXp_pv$-AhcVhl746ha+AB6R1*5g`5; z>>PO0{|*x!8L2{IA*4&pFF5u4Ik@e7d&%eUC7o{ZP_Q>8;fT`vjR|$DThgcjmus!_KXqHfk;Wm;W9Qf1$9s2fhya6H8jStzFnF z0eJCMZb|Jhr#Z%AWGwR>LHaXc59*494^v@}<+L0^f9d~<8=!b%xItDY zl24zVGbvQUZ+_06LQy*BB=glQqq`BMPVoCU>imeR?kEd;|QfnH-yx4|?ccq}f zc8fyT9kzI6z~r9D^9JuWZ>%mTslwmRuNdVBH9HsGwtFG6tdt!}kfgVG7CSoj3c=Ok z3>>jQm8jslu)yKHS4b_zTS=Y%B}!&CX}R)trG{)zO&;8AWr4kV+@#0^U5UooGxa@| zO%?HUT76BI)dMizbwDpD+zq3xpM4{Mi2Yqd zF^~CdAN2YJk2<^H_N#qqh09oE*s`_%CsVKW#E#UNcWy8P)9f;5=9n}-n<(GkM48-b zgXdv)S0HyFwa_$IP*pV{X?`pLBDQy{EWTjgxB@(QUmRqsL&+VK-jI%_sKL5pDBR_3 z=RfBzAGfCS;oiV+_DvIyLEE|o*Ko(zLm`Xszvb-$G;|X8$I)1MGD$3aBs8Cos*#@M zoi1(=pzI-KX-f*9jaxfP-hl?LB@>fXFgb6J~ZwX!>38=syRM5|V_2l-j6EIQVhVKEa9Xj!Jhv+hI_{1r6kIV5xoqOKOw6>DRLj_nUxy z4{{!-?eIJfStCo46Pv}^>S;d9Y+gA!WBiuX0D6a@aWWv~PVymVyz8mL{*2)ZQRZ!J z6M|8F$ay$RzI9X+7K;YCSIZhFfCn3DBa*mGoo*e#-)7aYB?-P*A?;NKUy`)hTGANJ z|D2tOyqo;;O22~tmnCc3kO3K!iFvj+i{Ogqd5UFJg(Y$jA^{oyGjKrV4bv;VOkCkD zy3>q#y;(K}(F-=y>({G>S#_Ab#}6cLBrIG!~TXE>YfX2Tsdn1K#yV=ga+zLkz%4ea7yuhXvhi?K2X3m5y!^OqL;2f2SjU-RU z#xEQL$KA@tqNL(%hpI0H1TNW)8>=^a8KbK=(`{O>oDtP_V!B4}Wk-PR63f%U^sAW9 zhmm2C!@rI1LjxYkI3}||u>>H!l{J(B$LlvAPj%a0`?hQX_JhyRxwGG{p;&{_aH+F0 zp2T055g@o`;uc^UkZk1I_w=rX_s7zuNxso*2bHYJOpuP--hrR7&!JArBrVObd0+Mk2zDMP(gUcth z)(OvowgM+u$LZ%)Gdqb-OE67nkmZFcCyYg>K6x&ri^k(GZdKW4x6BnAxyQ1i*!7?I zvQvIhAo#uhCti(TO*!smkU5-^h`vQ&3A)xeSnC(&xA{d(BwW^l5RNJEgizTv?Dsvl zGtiY_XG+rB)kj+=*g1_8&I0@=hVPj0+ayk7gZlsJ-J`qfc)GK_%|q7nb`CyRL5s&l z=CGmqR8k7)|I7t2M#9&KnU=Q!p)}qF2}vzCnSvL{kO+JVg=e=npx)YN_h1WY@14T@ zTtGcOa=c?*k|?c1FY0poWl-y&ziNBO@Ga?jE1mnJ489+;Ac)-rP;W@2ZdE^fyy}Rt zp!Pc(OQJ)raHa|)o~=7V118AsO|+orxFSm*1W(lLK?RA#SplZHH<_$gcIbELgSC7^ zvg;3=mkD;Z$evF_l8^?UdWUv6?OmIRJ(=G=?x8iUGyTsIKl_Qt+NTnpTnlK(BZM!F zeD-TTIQ7QR*NzGLP#$X>Aoz)M716uI9lG8GV@5lU2ov9SRcsnU#d}{HUVY!0cHO(2 zi9M|3O<>kXw!Rw9@M-t|U|cIt9kAEeL+i6sv1x4iW1_!Yf{I*A(*W%jI}RS`P{?#f z$H;LzUBR^&XNA}?&AW{AOFU&7TA|Q)?AsXN@i{G-yqUd?^4B0;e>QUOtzsZ?$9U>k zWU^-D$7+AOGIqIgUmR%n;`?zdG&zA?v;4sf_>s|LdH?vG?9YQ8p#pF+yY{ z$=-WJL%nljJ$Oze+GLA#YUL71VGcu1^5q_8N=l%YCf4AT7ul_4e*L9uO^?2SN z_vgLo7fJg(xB~N%yvV88XS^4pzr#(f{=P6k|KUxL#(<_5q!3j)+w3!fN{9h5@1diDc9TXosxsy%6aJF;Q@v?OgT@HLMOwY zNUNdaZ`7cBRrB+X9cMrG1`85G%ztTTK2SHRG&lKkf+ZcP^*>x=XeY#hXIqK@2DhV) zv9t#^;IIQOH{-K2>QRbc-zmF#L zm=dH!cK5P{{p=8l4U=r6Cyj6Z)4Fi$Iw+*9^e}3r#*ZsA<0$UVS+65)y0cI}DOP$D zn|vyteC-;x`V&KJ&a;m|J{aZSh~-VD1#-2HLNrfM;D{BGA)v%DH~wZs+uVv-_^-0l zJS|AOua_nkQuC>B+rZF*Z}-xI8CFm8O|Kn)i*t}H@O}`!50HPrn|^=aGu_;zO+w z{IqhTRGVB6StR9vRZZ8>$C{_gfB){>tPpi1xuZ#mk&*afa90XrIW6*F4M5usP7^mX zP58kL)u4!yo#Yy<#Mq|)DQBbV`803wIVXE8bK#&%8{ZG^5BGG>Sig^~Jt%e<`nn5( zBWc&~4jO+^-$9F?kVv!|8B35Y+DuCw-nS)9eht8H+L5Ro$p#VE^(Rl;dh5&q*X}Ey zZZY5T&8cQN4CTnYyNSu+8!i##o63{V^r<0sE0CqFsj-DQzUJdB|BAK^RXG!1TjpbF z8>rAj(;(<`wAvtFugWy{Atzv`WeUmU5o=p_DLEov2j1(a*rs-ekhUc3lZuZyd&CLDyxuAHuwZ%Ts<*po_qk+aSVxPwa^`do{grguvxt?xlJA-yu)jZ`xX_ZQ6-`X06~(Zzvw_S$u7D|u9!=ICPE95%j3N~i zbSKi|FBuv&j!VZTamqkzSzZ-tvN%;=`C#fOT576RW z5kEYIrj9agS`;k&y1u@_iznO@L6NP0lW@xoXycu7$g~Ny&~6w6N$Ad-XcINLk#j`l zRmlGF8}=5w3Cz}y1B>HIKh+06yfIipN{wMW#2Jh$nLe#9e>m{s`I>{KLqvSaC1m3H z@pJ9BX+@q0e$+VHSnXZ?u5JZ0^F6L_2HL7eSr-`AUrPFvixclgvMO3~ThLGKlL?z2 z-h~1Zq7AN3xH&V;iF)&~QIy$&5^WMMCc}hl?o{8Z^jQ4cL%2z`+0RxlnN;LEu7NAs zEu4=M&SYDw5Kp@mV(Iwqixvh`Lz2Tn=Ya-hrg~U(oUhpiN;$JCAH~K1WrbI3taa`wbj%Otp|>N zP3#1M{i=UEo*|Nn_4D|+^ARx4wz{vQ6CbpGH{CsV``Z&Clu0uY3r}&|771b8m($I% zp~F}is;^3wNlOgTQ)c0@P-v{G>J-sWMUa%ART_2Qym%Vq@->D5{u9;w0rl(%qE{>Y zVcx{xq35jUgTZ5vjcXh>I{-(_^#OMYrG7i;U6_&T?`(AxA&+e6RM4t59h_!rM}&d@ z?I#5dfJg5vI-YxEj6z~nGxn&3QVH)Uz~TQocxR$;P3J#i4nQl;n~ z%7K4n=V7aH!FtRJB)2dAYBn8!*s&0ucdIk1mpQ14^_uoNPG|e}%vl%Ir*#dZrCO=z zaEiW?@Ydbwolh3C8HRLs7d5zQ?zq8xi;^V@TFoj?FPa?oCG}XtN$-H{-&IqM;wN6t zfIOy=0i1K8X)iR@@Ew=uRbGCFYST(*xeWYt+~se7GNbE;7>;f1T6a!qsi{O;z)^jz z*V<#q86GS9XEDqp7)$h1fXMv4goD=7;98j|m5e(A8YaAYehhL!UDme55}{r7O*L&R zF%iYA)S?g6A*okb!fKK#Wz8O&fz?SN6|!{)eDeh3u<5PcGceh5Tl}?F|DSjtBnPgZ z&Z$Tqd!LgDT{#`jpreO!PiW%%Ik_%V{~24+r?iNSy$FKA!*4=$Fk;HwFitsy&@e0s zpMQTtTn~ZB%yj;tP!Wh_kM=JX7CD8^10;QN!m|P|E$V>v$Y1?e%Ukl)7C* zML9OAiDhTyTrCSJD-K6dEQYm1Cs1t2&M`_afpe%03~k4$tM3~0KP7 zpe>D8AIu`F5|V$5Z|$l?gFmzf@a!lo5G4xVs((u0KITeJ3o${t+Gx6$hzZfzkWo_| zSL)H5Tt1#M`2&@_QR9unqQE)09)F+e$7zx@&Kefw1V;9Dl1n7$*0srXd>Z zt%Cv4bdUlo1}~2{;%`p_`CX=yP&!I~zvu9@yEb=xrerZS{&Rr^pe;a^}24HfQ?`%Q#jIxs<)&aQ0C_)?DYA`-(|G$twQc z+XdkpuCuKj2uo#?@T&60e{lb{{;NkJZI(wJ&l&ia=}YrUEKa8sUOp>kp@-dGatTjo znpbDZV-sC%eY>UQq$IdVMGbiJEIw&AQOc1*5dxf|zu$KWQcQ=hQ(0Qqhw@W;kx(_0 z3Qu(aCAa#eDdi{eA{aV~X*D^t$YJC78H(B_LjVQMLtj|8>;m4@mLy4lI&i5{CD0E) zCu>c?oa3O;j7aKdoMRzsN-EQY^h@%`ORwouUsi1FMWVsn#4omC=$!_noJ_@WW{c8O zDMxgePHF)6)$Z*&gY=K&?}w)^>DpsoT%Ru#6)j88A-cS|lc>Nq;H2Pm94ULy$Ln!< zAH&;py?Kp=;?$o$G>))9pFV!7~-Z`*^7CgFG z_-#Kr*82@*9MKjBTbX`DKK&H~H(II)YnlNIhi%PW#l$<^szj)J(d0ThW6n8e9zWt0+g5$Rd}`TRs|Y^28UnRiq)-2*~V!7NMFda3|q3;H{uyN4tbb zx}g5PBvfsUEs)c@0D)x7uJ_whgDWNQ&>euK6gK7-W9{xBzQpY zsro_);heDTs>bVib7mika{{z<6^;#IF-VQ4#N~`+dpe;AWqnQEEA%*$Zrs>4!7b&?3n$MP*Is~pDig}4>(rH@`dZ+Ar(-dd5 z9+4g%U@%6{HLee!_ayXpJ{vK{I;htCjWDxh)k_r z-Kb?uV!Pwoq76fzX7u0bOIRwBaNt-iZNXHbQBbPOX|J3=_vLu<*Kpa*l7gRfxqrgX zhuwE@hTy01eE*X5cs`}V*na(b3*p(eM;}>ITp=KR()eYo@{48DB`ZezP+`wsZ)sMp zI6j^wQ3J&>pNKa9??0af`pl+`DnQCa{R;Ky&%ONT)^V$Y8YSN#Wwnu=wpSMKR#@gQ4eeSOsrjsG6rJk`Kk#;js(INR;gRL@Ak z((4bCze+SxW*+3-NQDYq}9?$xKCFnb9TT0OV=4&OKr-P+tD@-w)-8al;BzaucsCZCn2%7 z$UJuFp!n*`5&m{vcb7_Xv$D$5hRgYrnRdkL*(Mu_c1f?qso!toK!%8)d^SCnC?-tI z_89TrrS^dwb1?%SIwvVWn^GcdXSv6~6^L zs=!Q3u0?V5hpFc_W-Nf}&5gXh}MM_Cx2eFOZDTzB^ppW4! zRPmQ6gDP(5IX!9W?(g50H8I&A{Gf$WZ3#BWvFm4B9Q8)SHvz-$fri!`m{B+)T>RGu zW%4|z@5hGS_w$cb{VQVKlgA_~(=_23A9^SCF3%pT3GoV_v(S@CX<31wk)w$k)+CSI z*OnI`ohl7MI!tcDBa>VhtCdYo)mZ@TkctkT374QkVQw<+qL2R`8>@yGm};~nFaQ&U zs|^7xj8)a`Zsoy*SPY%@L$IuD?vEi-p-&nA||e0z^gopC_Q-x^3^ zDI+3oxRvsVE!D(qQjc+-#?(>StiRv7tjIJ+e3Xcr1|3t#I~^kncgy^`b2IDm;p+^c zP0g)mrOJHn?2h;yfw-dFgf^bHVS zxA{?M=V6nB3|3G6yYUzDG`H!nxL%qDLVfD9g9p`&p&=Zmk$(#kr?c<$iR)eS^Tf2{ zo~$Jw4>H5cb|hpKv20uPeRtbGjk}{|tKEkB zu_GAO%pab$SI^$preG^v%{BLx$x5hcKEQ2h`{T_)`@lY)s6OzO)d7uya9;eU0eLI} zieIMWZXpnL?b0KjdMwWuzn;wm?xr1HE;QM%))tKyiC*k~=vp1$s!ZRP^lMCik%x(S zjs>ViPbyArDWxI1_*Y6sR@GA*19H_d=`SpoZ>pN~<4K3KW%Ws%LthNl+V?E7i8nuz6{hK0>vZD^L{SW<7(wPy z;tkXk<@&D|?ZsyKML;<1{mmEskh>dlUPMT^7w`%)vk^jUV&oc9LIgA!&FVO})f1|* zn3~vFs!jW+CWy{{FIWgmYLhw_0)3=}vP5W}%__a+wn<)?9Rv0TccM2c;}!?k0^4&+ zW~H5RD-`wlJ;Yu2_#YcY1kS?e-=%(u;tBJ>LG)zen?F38qZc6`L~ zZePM0lqfRGhpzh)Ap$!jf+>&PEh5JzidC2jX;FIa)Sh{FEu@6= zQKUH3bVDjnq|%q~5Teii@x*2b>vqmdCm!j#QYepzel{Vx$g-GvVG!Js##ONjl63DS zQi+7dtWY;colyx-VzWF#!9r~?w88ZnjoFJqh9FlXGjTth<8}ev!>p_pkNYh7=iPpX z&vj*M%=1Tv8|4bGRwOw+5GYkn+QCAZCNe6Whuw^0rbpA!zH;MRP0UmJM^?HYS1 zOkHQRvU#yLeFk3ISq+P;Tboy$(9Kqk-ysfn)TKzPgKqselZ#MX~Yn+&kSPBxU> z!uKb*dMM`#L+Z7&5pGxvbweQWAjYlSKgTx*)_**8wsK|JqY<6*bqx|o7k7>ANhp** z=(zl*y72eYb4P>m?CYmKRkCA98uJQ3H<TE;lG|cq&ZX~E`j&4O4DPJ{?N5e>T8w4EWdMF_iLXx!Cl58ISv6+K8B*=fxIe$_xm;BLXs%c9W2{g99;I z#VSvLEUD9u*i*KDKVMG<#fkzJp)X-jh#R0)PZYhvtPdy1^F&p=WvQ^Lf(ZdZC`cY` zlmZ3f21QiJT>y)cLuD~?2%?LwXQhbjP#puZ+?ud_1~?e~A-EQ4siYB!!D2=)7eQ$$ zXHXsqf}Bgf2mT(D73-6i>@8rXw|KKRq#|7F*Q2A$U)f+t3xvCq=ECD>~{y)68bTfPfX- z&8Ab?1_+k+7??-3AuS-Nl9YyT$WVhpB@bKC9yKdzN6O85N(3*S(NmS1&MT(D$!`3h zoNT+x)HYk~xd2*dE%h^AitW*3mmJg_%pH1rKjOlc>QvW%v(qi^IM#{VEmk(GE;NeM z?&|;rns9PiF$c2Ui7OTg;$yEjN^B_U6vWm9Pk+{SHfcrds}u_9Q%N&oBdRrwcAyz- ztg-#KDz~Ij!SCHh+r=s2V;|ij{THdK40?zO>{?MCSV6b@o^=htpssV)61xxAihY7i zuMhb~7h^e*icRRUeB#=EN$(*47JZf4b|e$$&ZzX^AVfdGAMUI>xDy6D>n65pzeu06bdKCEDMGW&vy1zVN-^7)bVOo*n^){0z_ZK5qWI{I%! zfjb3z=En(Jn}3hjb{;8(R1SVwacnvJ>{j@t?$IZWgtSK^fAdp!KUa}6OQ?PPe#73# zClJs>zR`Wbihv>Z?>@9DIXu;+qV75*l74lUN*_+$GoX|si!KO|Pg)i)73h)_@(?{k zFkrS(GWC#DK!5)o2S%Zv#(+3Ak17_ASpI6Y2Vq~#Zc>^3xf-J4JJ)}ZLz!Wm`OU@R zsOY%`QlOe}1CqK~+onXiT5H~`Sk8|}{m9E(6qU4Wa z{i-2{!?M=#;(LhldK~AM2`V&;WeBM3lSMF|175b5z@0SaZE>K;_Ng;nH2n5NBJkPe zN9QJ4D~1{Np1PyNJW5}d zwK5g$_-Aao_0OVSy)Xce)>RJS6uzK}%Q#wT>EeIbFL2uIww3xn-{wQTmuIcrpS=x2 zdUX!wJcFOE3!YM?UhK)}-(Wwy`HNKoV_67!`m%j;oF|aHe3b)tvVP6JGNfDuyU1f` z`BZcQDFFI2>viTymS%ks@onWDbIG^$WUVzmmi1Z=s#;6(G2YRuep_1ZF9?xjY%C_9 z#^)#8r3cCyQp)3OKX}xSz`~no#o`Z9usmX$SLS^33^kq%HUS9nO)4JFyy*6&A8-Kr zk9@ox5OXFY?&cDMCJL+hFB&E`PCb}*tea#rfFmo7f2o0{h}=*-Q$a(cOLZDK2m--B|`rP)$Yz%qz3 z4-EVgbP38r1+F?*MOGcbCqMrC9PswI65a*$9zXEOdU>|2y=ujj?HSnfSgk<9XQb`t z7p3!-)Oc36525bElzp~z?yc|ej!U8hw^Ceb;fa6}67`Jp58+X#6TIp+g2g5l#kM#F zQopTDcxTK2T#t2_PO)#m*Ml%HyQbIlbwosMI@7Uf$;bBR=`Ps;-*Cl==Jlt?d^^kc z;6lsHnwm0s22b=h#^{i`OAyDP30ay2i1te|)I?d%J%l)h;V-E^Olp6VDrs})O?b=* z(^Q?J3r$(zqpun4MlFqZ_Sp{yiE^?-dvijq6?!Gnl3kL+hj6iVF3P8u>k8fr3!ZPb zDqC>7%2!6kpFcf=%^Zj4Of~~w+1~t{ngE zU;aZgg03O(J=A=!882%yQb0(?$egs|aBu~9zfR$2b2sJEyrsw`vP|*egDq0czgJUa z3VZ#+ZSw3P(XGR|12bwAp8EkC_t51cp-Z4>+MDx+Sry$-XZgi}6qCcsZpquk9u%~p z`uy`X+Z<6EMMf?plGICcd=V_n71igop$Gr4LYsY>yI-9gmO6G*djg*})jE&v1`b3g zW^?;ayht-IREd1jQ@&gEfQ@&;wT%48!==KcP93C!k=kO^o2Oe_lgk0Uhi^v0&}nUP3HruQBLLN3@4#=u4tVWD}D2#yL#kq)$YPaq)ZRuo(OtQ zCzN=P?l^g}7j-0sx$1P>0bgmJB{yevTo54(-I;PSbJ&Fh|MYvi{*;VR_s`0&Vz~zm zFQ-n~hM9wYMz;~y5J}~+^X#Cd(Uuu%VeKg-=?cs>Ogx)_BCea#{;5t$P|f-Fn$fQg z*NA_=ae@v*=a==3qxGtZNze9_wCvX`B|hGA>-&SX zn}qKn(60mEl4cwN36ee1M%7v?Fy*atR3%FpWqPfFH*Yg!m>CoMX*uW` zZ>$I>d7^Nsf$4=35)C(=`h*SPb-Q%=WNXOV19F5qy1pk2(vYZrED4gij5+ZL&vANu zyHGOiNVV*?nC3a4j8TdzQ4pw;&%~~jDAzD5=q*#L3EUbbmxdG9{S*oiUE%of+g9+f z`O#TKAlgP1&Fw~yd@T&b+0oh?h%~fN{EnK`PAhS6(Jwav3ofvR<}SRzRt!aw31={CE1HM*o`vxJlYVlQ!5+ zyZm_$Hl99rQ*Nv)UADaZJ7Cr5^ndr!cvxJ0muNh{Dn?y3Y5ji{rSs*E41ha3hO+Fy z#%KiXY!h+=^W>-P=;Ly{ymbT{ULSfJkiq)f@86@^uU}?Qit=jp23t!uNc-Jcch6go)zS{QY6sazUZ1N8=`4$lYo62Qf_TI!;eXy5JN^9qhVnS&))#DI^_O?( zHP|fA<{Egddt@n0NJmIV1qs0VB#-WL)=*_8f%HKSN1QWrdqS1Q;MsdQm0XYx4j#y@=Hr{<84+(3? zaoo8JZssTpdw>>lz!Bxt1RK|tTdchnAJsTB%;cj^_QSX8RzlJNEt?~C5INSO8icBO4Oy~{3n4h$$vDNqwz+w1uP+Jz9 zgyHFuqwdm*o^DyrKSpkV{So@*dt4h~QIsr(Gvqn?@(5jKOX3GWCEu6N6!v%nDm6@9 zlX>t~3$V@IX3#)=)> z^T#)#4@MQmD8*pZ(0VaWYcLrs_BV@<(eM~V(V|Tvu!%3|cp@e(D$eWL+Ul#0h(@j{ z?rUB9N0SG`iy?|v(5jzq89dD+rT8v^jG;-6ZmZ_4Cdh&{0qXy5N1#adgf@wGfl2&! zzK*p;ELKmNFDZH-mi>pIn|#ubX;blQsa3Rpi|J7x)zvH15deCij|%0g1i-Vgd35#}>2cWdCj zrX1LT`+4Q-GZ*1sJ$0uJ2m$%W8OsdM^y&f8kiXi0$J5&lrRg@V9K=^G*8kQ1fv*g1 z;L4<_*;}_h&g$9X7jwNQ>vp_&e!EH7At}r+xuvy}a&dC=!LWQd3ZcV-p}Cj8T2!k( zvT~oGB;OLpL&y6e9e8_>LW&eQPEZ zj=e$HN4`PI=J&W2z`T+-d{Ap(GMOWRih41BIJ5&-3N<7rNemVM&wqbd;^yk5&V zRqkKdwxUc=yICFMZS1)DfVZDra%Dp;Ob5H??5H;FD#v=PGqx(mu7+w{^lL*|PM3Z9 zPo6m4X8_yb(pMU%50hz3=h92zbV4uhOo9zLBANYeIdGg?Arb|mOde|ILMBLQ1@_O_hVluXZW9_w?|8U(p(}i4kg-+#b z?Xt#R%SYR85l)7xw|Kj5+2u!J`Q>LptBTjQ68u5e7qU@8vCi1nUIy0e2qH^pcfMX6 z*CMnW$_>Ff)9Di#brz5`!;(laJg_R^Q{p`6+9)G>3^2K#S2ZBtgbJ)5X{*=kx$i#E zhFpI}k*Ds=i;mm33t@#vvi=*_I~|0dgGTa`3tKJ`>owOM7|KOQ$`j1CMbS5W;0V*a z6~Jh$mkH~ap@Xj_>mup&4DZsd)L}LZDlJkyVb*t>vYfO-WcwevScKI?q(Kmn%W9d! zJ4N6Y8q&Sn+a#%l3O!w?fCRLEdM4HvLLC1#y&qYTb-o0+qV-PXc*!SK?lfdy1X#tN zG+C~*O_Tg1d~ZXyS)hYcU6Q?5F3RnRukhT54gUMw=yA0`&3n71S1Tx}t#HESY9-rC zu-BDJ6||w6R=u_}9!90;JnyfaCiJEtK~}4>d6|?&!d`Rf)Bin)n_eBn8(%Yhy=q9F zWDYrAm#|KHaEbfv&~&~a82iZN@Q9>Kf#e6Q5U>DVAa!e+=(7%1j_U{Ii)`Vw?s@_W zMCSQI;JLUcM;U8tPY-ixCw|4v1O zA&N6EP8`M>>TAp>01q#E>JIq{!_3sAbq-Hz{P-78Q}tvq`{VI1e$qDl2H0a3fKLlD z`l#j79Ma%sR|5(@gGtRQC_YPxjD&}IUm+A%l=;=Fwtf@@27Z^8|M}s+6v1S_JJ;ep zZ4-4Lgr={QYX5Bq{GXSjM(3-BJGhl?02D(=&ia(PC{T;_ly@|A#l{jl(980ABy zMN)he{}a_)Zu7>d8>a>pD?Mb15_V;_D#?-8ztxk+6LNaS#nu4iU3mRgY+s{{(6FMN z#oAxOJOcAK_mXL#A~RlGBg&_-3ZaJK8VO~U^$*@5&ut!IBq2uU_2iM9EQvUUIHJYg zwck3K+$#dqbOQG+;wS`D#%Rr!OQZSOd&u+b0df^jiA6TMr9>G_8atD=-mLj-%|+YE zr-26FU*PJxlq*t&QN-N&5|5w%-9D8!ceTCYwOYP@|9?MQ@3z^i*tKy3Y>%XZtl3Iq z2d#DF`Lf8_kGHiW?Psk2uBp+DzA9$RMHL&nP{)u`!&D$)gOZ=}=Tt=YO<|l3FZ@{E zL;r=Zmqt;mtFVJ&Nr&3eu%KC4ifc5tNC>VeL%=muLe|v3$B1z68yYQcV7qtDlI?p= zwdCx7b^F9po1tbW--Y}8*ZgJ+Y=taJ>#-bqP3*C+d{>WN$M>uB6*Y!VF(uk`XmABQaLDP9%v0{Ir!63HFMMP1=iB^ z_q97AGi#(n9l~X45Be0XkO7ckyc$dZlBoF(kqpOhIW;^tW)`SUkU-qpv|ahfu|>P~ z>z+gu$JVF8N3o;2t^0ktq|K}hi7crw>zcocAJU^GP$gpl3e#B?11BKp{DGhOeawkE zzbzcU!9VYSl5FiI4sm#iQo$93uuo7~bL0exSAcTD=<5|xe+2OtKFn+09y_O?Jc2*n zGN82e-@$;vr;*>8PB|_t`usZY3@= zzkfgPdwXakF?b7@$h}T9q_NbRzJVaatNH0-q#&LMS&Z8L8uUHQr`JrZz2OfHm;#eC zU!-%^@v~&glU%aX$7T>Q4{%V!r>}{30>WLvcB%Xip*dIXPZFnbDvZkhbL;)X$~9!-(}8%a)9XAJf(|3UrS1=2A~%8;U%R zjkdssU40=bxHYqBK~cp7+^=8=?h!Hm5dOapl7OZwWF~eKgpqO`IL&KpBif!*aVeSy zpM%}s;V5>;OkI*EioxeNPABB&{o2GTc1wF?(-I*OHyPTz6e2Sm zMZ%&_+~1r|X!&w}b3!knG-U)YEi}Pa+eudXIxy5<;K*>ROx^(q^ioh!`2e-~d+gux zFz(=`#5}c-x00ROOR7D-`c%6fj6$l(f-x#OybG!%-J6}tKlpZq8W9=98!pXGhf1xs z0&e(ybT(G{?K8;#Ww(aR+_J2ga+5qoN30|ItTgT2FT(k#m)H8Kr3UqAt=}eDo_76x zuM2!=|6$7MsnJUMtK)j(s2!Gq#j2EIQR~Z5Zlge#Y5oEqd1)zep70svcp|zT#De8H zYJwj7x6Cvs=+!1h#}j(0Zx)U)I85IruJ|Z|iTow!S7~FVP*HV%cGsL|Sb4VgPF@I(qmBswPKJw_3?a4iMkwN( zb4Krtgh>NY(6Xhx1q=Uim8QdUnpEc7PJ3#tIxIvEcxnfo>)+uIs2%Xe4)IHET3lTO z0^v?o!^uVI3$Lv!mcMC*FiQrqB#Sf6KIF`*?X_*5;Twun&l*Sui=4EmQ>4+AQ1W~JwL)OK59LpcHJ0nT@W z#_lvT>xq>VgF35b zb=`tMEVfSER@kW_i@>5u*|{B+R7F2xiCUOSXo;Cv z$b;>S@}mjxp%QV40WHJKC{e^~`<%9uSNoCQ1O-&Hj#3o%0qa57H9FyA0z~n|CY24h z9U30@!i(oGfqri*X@lijbZ|soq->Zy<8=wyhc20>HB2@=vB@qhc~W`8$&Vj=N-#6C z#}YPL3-)|9E@4mVmg(ur3AQV{MUhnPCu9=cs0^PGdj?M;k&bh+FP37x(d4Y@w8LyY zWeDiklQ}Qvl&3kwp_tnEz|Mw*$`rSkhmA)6w&NMI>la_7nd^D@eZ7*`W*ne1fzfD4 zI@A-*jir_1xy@>=t~67ZWY@npSA|>4ZGU*z#Lh$`jw}mO*|UXYtJi7Y!*$@Wnki}P z{x(mmsaDyJ*?n{(e}Kycm5Z}aADeiCDZ*`aMCE!!$f)m;`Cj4lLNx-T|vkmNg{j z6ia46dKdxkbU{asUBzKmVe#PbAcIfmMf{)@paOYoZ%Ub?aPo%WUGh$5JC|&Uk%-b6 zx&P6{nUH9AA*&QtMxdHwGGI9+na)dDRv1m zJt~ck!|!hP|>}U?VmZ7le%Fq<}u=GeG31S4Q*f)UOh zsC=5v!8n44uxLA_K!8f1`ajLPJ>3C}R-!eZoaDtBwx=Ie$ATQG8gs zQNlk^FPrvI5d_0pq)-izs*Ga_OOo|l1Cmsg0Il+y+b*2?rbK=Y?9Z7K1%_d%^@0-l z5{}gpgvc@3mW1C=7TZ{WLDL;FyG7U#(20m-nh|ay~Df8Lg$MYQY`jK?0NE)BEdV`9~fOa zk345|<5G7$J6iG=rV_AkgPmds1mhC-yT7lwJ&zmwPHqvV_sdl6jPg@TR2CM;d}H>V z)~sn>E}**>uKzs8Uw%*8a_F#P)r23Vx@o^#L+QrRtf@ru(5XUnv}R%fc=C^#bUcUF z?w??VvT2Waj|TG%=}+_tLWUe8Y+U?BKpczr6ACBt%X$IoMjfsf!HES_|6T+P4oHc1 zf(#1zI?Ym4xmW8Gz_t~iIL;J|B460=R}P)B$ZS+=c6{-{10xbvNCWOYylW|mRD_%( zGl~3`9KL2x>Trb;As8zYN@HBivf)5qzE&0T15q$gxp5;1An@`44J>IlCZy6n)RcU0 zlMQRq?UpYBd{T+nT@OQ>9^G=o6N{-WB%3DGSi?5EZ)_Jl`FJiN+HH6PUtSi++FUzW zhVz6en>ta8WZdn8I-`f<91!%0_Yz>nY73zp^$_lSp+n-F^by>@azh)2iLDZ#hoxm^hfZdu9+ssZWEL<$PW;uve z#Rf-UJ>;f0V`}pf`DMvJQsbIiT0k|I@2Ka|9L{g1R0QZm?u;pI-bR-E9%mu|R_33W zrhuf!l*-LtND+?iw}52!a;5&o?Quc-IYVYFX#Cl4xI zJMJO8IOGnY%?>(;vvu{nb{&sUx?#SqO73UgZc%Ti939@^Vtl&}wQ^tR-5ppMmVStP zH)XuBc_pN5S$pTU-Sl5s9_W-kyUHZeV$YY`Pa3Me#owJ50L%Ns+2BAlZTf?`Rq%pq zO*o0&tRX|X)4u2S@Unzwp*(I>K|a*x_uZlkeWMpkmS|#pJ}A*bG3LR}BA>zXpwZ#r zk)4YeNr+euv2}nf7IJcv%p1_deIfRMSSrzjMSuIi78dSJ@eSo@e&0uuXu>}c0x&dG zgyuq%1qIKe9ECD3<&3Vx?$ui{z3!_u#Puit3}b^RgRI|oB4YwA2!i4rWbcUmypxRF z3nOm%FkI>pTsoYIeq|jQ-r3ZOO{qH{15GC8V;b(6gG6Wj5NA{)`eP4tk&xBK%)Lt* zCkxXg@AhxG?!p}>5sw3FBqgdDw=`q_0=tWMqAaXjepOFS^M{;&K{+Zn5hpUQ4S7I2&jx3R zO%Fk_RF$ApsExv>$VKR1r#tCB%lUj9LXpaC`KimU@|jvz>nMy6S-KXS2P}W(;11Ow zKYo~#{t^YOL&%9WI}5tnJpp1|Z)_Bk*D3QWauq|GrC8K8vh~RefK5Qdzjg1=&($0; z^HYs{GWoy_wyez+WequULTR->oQT&+k3c&Y%vw3>X4G9KOKX6*pZcU<@fq@RI@lTa z1W4xG`~%hF$1v|#ugEPD>qnl0Ter9&Z=F$iRrznsT$Yam%64Sbo%!tYD#4|&arX^z z()+A-dcrt|u$S@~)ZhVHK@swB<0p6T?eUrsBL?}?%5z2cv(w5XfK#rqd`4BlO;ET>+}_=_%xJBHxNfTz@$ znCzC}c9-`Q>+b^a8L(DsxwQzXP?u>kv8cP(wxaFwXnd#c4G1g4sADeb?GKHpPHYoQ zBEr4uC~J5}2;ET6Y8zF()T~Of+M$usRR8QK#P*P*4@HnSpqlsnyFd4SY?L~h_vMT< z&GFT`jLn^;et(dCD%~h}s-UJFfE(rw{CG_FWlSWu?cUjvNubnG%1P`9LVB72nn;aur8k8EC3kf`0#aqIfnl(tn>n+kWA{{Rok%FB)Kk;aNKV ztG>;B9$W?qFTZu`*3a^~;bg0S%S?XRK{Lb*1ci&jUD~%q%UdT4@LxIf7|1jx?OKDu zeQ77jWPR46G5{gQjZiw`H`&<`Bv9SWUu6PG(({E-wDeQ01dIYjVofJTKn&6BR3*`e zmvhHa>~SwrI{ebp@u!Zt9|CZ*!z%IbK#=(k>gF+ckcMCg_jB^2{)rp4zGCJPdwt@< zgjcf&=dE>O%(;!AYW37405tt=Jictp7q;M6*;fP0v=XhaFT|MqMWq<=p&P^@SgG8`-sV4@9kaQXbU{?>byC zH~9@Abj89T)C7!65!eFXq-ua#3ZcY8ch3F%jbdhRD(J+DksGmUjV=yF@8!=o8vR#-WepDB)c-BngR57r7Ob{8Tua#m^(r^77Kb^^)H?X>R(DaR42X7^ z_at(8F6Fzj`=KY>ZldOgJ-|%>FL{T*wiaBENppu3~3b^9Axjk?5));xU%Br&0U=B zdH%m{nGJA2;U^Fv=kvmd<x{ z0R|FWroi)D+9u+NTuhIW4CCAA5}KOBi7n7Cl73VkyY+m8D8b4gGRx`tP;jP}Nf^VD za3}uHe~WL_5wKZjpk@T75_d1kkOzJgj8}SqvxK_a_Q53JW?k1`x=dOCxFv6Ob#1O3 zGM(D+_yMN5?9>0e306x2rTATLva1e5#7gkk?5xew`Mjg_1@PY3q^pY=@tjmC{s8f| zShca=+j=Q&`sw%dCx9T5{3Fo==kwXoeyE zUp0e}gb~-yD#2#Nxh_HJX-E~|EIHr}dOQ;e8qT3$iWTt@vZ1J>L%jTKQ`6BE70T8f z<}Ih5=_S%_!|<&8nY^cj8kO&i)sJP7nXEX;qrQQL&u?1}h%Ir}8@L0o+J46WdKzfO zYSn)94D9pWPe#%#=WazRPUgc8JfvUQblz#|IhTm!30J<~*0 zo&3q~a{Ftt1nX!-G3SjaDNCQ!&BH_F4l2qB&O_7~9%cjMUE|77D*ct?KSOdY5mK-< zTomzRU}FUDIE{CIDknanD&5Y{Shk!}InmlLvMwsmI?&gq(^k%O302F6{yx#|cg;A+ zvHHE+AL^aZ_~6CKl-mt7UL)IS0D(HJgBktO+<+M{-!H{9fVQB^1pMkL3bq_ z03TO(79!W@+xwTTP%)T49$;XP0JErB!RgXbHu-cM{* zlOEV1?Se4PmUtIZ>T%D1nl+BmpH;2WZDdHT`YQgxJS)#DRzEBNDoJ*}EJ8eIKOvZW zaFmGRlhJ&^aetI}o*vcJJQk8&K_nomjAge#WjEVDGNQh-=4VC5F7n|p&Thhy`4bCA zsVbqLH5{ zEbsb2b-K^rp z^kGuh9`jU;3;QuN?AHZ)#-dFL*jIxe5?fy7Z1eGc^qoY++3)W0hp83AdQ7ZsadY-w z>h+Uiza9(zIzJE7gnJ*DpluRNkZvIVt%0#%RjZW+PataD9~6w|v9G za4Bj(SR50I=t5_ld6q-rUzzlxBhw|%#)$sOTpM+Lefb_LIHbWAP9~x%q;V&8 zjU-WMm9hij^|=!EeDtMM(x46_lab^9a&)wme=6|mtRwGDwqoo|?!bCplc zR4J6Mw8V(@I19mL{QN!Fa+NE+~yXXsy_h4nD z8|Oq9^9=(NN4QWyVB-Z+TjmLpHPtkLw@RQ^kR{&k4|XEW7!|~<3TwhN6Qp^9FM?BL zH(K2S508v;R%erLn8DM580Ya!366x9*<30ufmD&oQ$%LnLNfupc0&TJe@*tw{+5Yu z7A6aZy(xpaP1*YE_+yWJ;6kco;zjG87riqkzgZJMvzfefI>(rD&SH5vy7`EAusk?& zR|G*9pfQtlVH`Q}djy`@=Gsi~v8003}i$kM|RWexLJzFKXuasQ(;* zP6P@f#KBmIS=wyaA?hKM1OiRm7Wf^A3S&}3Mn*4_AA)EZxX^v!TliA5+SNqxno~cN zAwvDTKdhE@P$PT|TZZ@YSrNabJ)hQPP$-d1B*i(9$nieJ{>$qi;f}vJHfUH2IcKJ)?3BcL6$&x9u6023 z&S%R>vDiTUA9;b-3@*ecEjMWKE?~*P?0m$r3yI`H4zgB1k_oco1e@4Ox8MoLZ)m(9 zkeGb+#L{k~hH{bL2+7>1!B&IQgmIp?mB!4LV{I6ZvvWiL7_I%n0!V0H@q`FmyCy4c1h*nNRY(@#CZI! z`byy$DGa(y&711o6Q-0)goOHjSJ_AswalpODkoeFsDdn;4=%@b)!E?VW=#G9E6DH_ z_hnQ2GI>7mOWvF9q1-mZLilQ&>^1yfh&OY{eU4)|<~}AcH}f4|;tPLWsA}<^s|v5f5a+bo z^s>cQB8Hi+mAne7!z9kj5MAAIfHh2fjK{Suib-@tP$`r$9{$ex*vITQIFU+t#3feB zb)sG3Xnr)?VrwMm$7|i9W}~XmXdLf5m8!}t=s5T{pLo`?{^VTK%0jf`9#I<2NKUw4dcJpocgjQ9&u@i(h zEmq~DW))sEVC~sRgaA>hg_Mam{s#2{6|AFB>Feiyr+N7H25CQUAvk@Z(icw)i%XKu z{a2L8Yr=nf(Cg^4Gai-0eBYhTy23=yHRxgKB%;@3-My0jS4u1MyMj(@?5Un>@)jFb zL;MPS&5{;Qcr9dJcVKQji;kZU4r(d%#oiAf^1$q66lhHAE(4NiN-uHJ2jPuiXQXg8 z)Hpm=uIWH6t;~$!VOivbWwB-gwreEYTp3~jwOC-5JvIDG**a~&KU%qBAazkL?8!=O z0&o~Oe=OjEeC$)0VzoiDjE$fwG{bJ<-2(E|#Xi#hz=Y()lgyNv1{DT{vzZnnBpl#CTKSS{U;(bwv=&owsW zucnL5rdjRZK!iN$bcZFFBwQJhW~Zh&9sjn-Hp{EYYtL-R9904>yo%m^LHZ?3-c_6Z zeK)TA`*~F9qkR`ik#FA^UU>NCDkB=}exKTC^r7C(sp;Qu+0#81J>4bLvfhwN{ZEGZ z;6KwIyQ}+!OxjrE`66fcW7o*4+FFXCFu)|_A9wF63U+iX)fvK;o61`bmI8sSX=B+* zH;?oPaKXl)wctg`y;3ZO7cETDAb(KE?dXF*pdQPc&WpQ?kMcvxB|!E@UZQ+AYV-H7 zGSHgF^kta1aGb1JmG>4QHvS<{vPeNzAEPpjA zt!09?wcxOW2h0$Ni0RlXQL>{6=Us?WK6O7n9;9bIcEl zoE9ypS@_|Kn;SdkTPdE_-b0=XLu*%AUPTCMe70BDIZTZrA$P3i_E3@Vo6%D}Y`~hoIUr;z1p-MI}56A#X48mogpi@Tt zVL)OzeRL8Bk+d-3qr(!EUi24j575luqC#-xcllyOkys4a!|cn`%R0+XJNaZH8Y`_M z#11F&XeBB@CMS5%sw9J8to|riRwSS(8wf~ex926!wiLSw@P+y|tZqNIt>6*4T*W7g}^o8UA||4DJHJa`+zCWJ%uqJdZ+!GlQaMCvRpCzk}PQD z6}~I6`ILDk+T}IOkfZYUykOGpUmQL0_Vf}e6J#}$C^{%4)bkP$q}5(;$7q%4pnD!HKg1{qUWr0*{9y_1rZOgyd0k!xV@JE-qaO<442*j05KOC;*VQ`x?5}aUAIbn2c(fMGp}MMB;nA7hS?li~y6%BPZcMp^rKE{q#JfqvHOxW^F4kCJC@{ z&WlQT@HC#h6)R)iKA}vK=RpN zt#!-5QZlh>TBvrAAHr@$@Kpf^aqn5iSd&%5j9kQCPD?3I{np33c%!?m(5YI&@PY4H z*C*je+wm$1;bz??PXPTcpt-sN+t}D85BqOma)#E@`U-ekH>ZS;G~id;&i0r5T8#Gi zBK1znY3BJZgPqZn2u{W-^LcLaoBK}XK2V=1Hu|Yunv~}7OVRK4IBWi3Czere4PfIY zX{bsYvZ|)2vHxF3Hk|t-8zYc)$fN;AS6M8{`24zl_t|K`&m_B{7`!k&!*yQzUTBzK zND9Zg{DA7J5bOr}fY9Yu`bL-=oR%Hm>r|A40}!5OUV1K5qa!Yn?~qaw4P7?6vQz=D zYgT-k`p*Wa=_06|Ox-Fe$P>%(q>PK+^)E*Ws_n8p1u;ZM-IBn)L6VnBR}yqNwX`yX zDb^#e?(m%K^1jy;1nFgKch~c*F>4JX}-QP1^J_T0*98Mni zf+}Egn+|}r%w?P}uqh>%#;!{HB}CGRqMR(+FUO;5XCzeG)kQ zWpJQ%sC+z+fyVi?dZTD9)(t~lf4bhFpyfqSN$f(9ut$38*G0X)6|@X2y8l%MRnS<-`SY z<|Q#cj1}Ui3wnPzrfn}a$Qxq=X|Uq54sX$-#Kv20$0t(2 z-gt06oBM%p=8qrTtCl6B0!&%^G@BFCE)B8@N7&RXoR(hgQ&Qq2%s(DoEG@0myZtce zXz}vqCzamzf#9?O)BntlBKxcDmHgcYDj&@{rhek}=N{?bBasLQI6*|&2wx#F`2L7fMqk|4kCIH3*mB({_p*H1_ThR zXP=~Tq{SHdo=#$Kjk6V1lben(MLkwgIAEwG-EUY&Yd|w zt_~_g0pZwRcT{1noPd^4P2!0{WWqKhW`XLjO?{|el{~xRYX@1ng7^C=kX?e{I zG;WQBnTatWgPEmDvV?7%jO zK0Vnu#zb}e7&c5g5RL?-XmrYj8{(4(kG}8-0>UKtd@;$%{SuO_YqU-^uXicwV!njV z1M!MIsqC&DGijx4YBW)g(2MyY>m}T7wyF$Qpi-Aa$x8CHvdL}jNDrp?{-c`v-*t~O zE9tA$C`jCkO<;bgwUYMVuQBQW{~Dj20)+i-v4c8Vj|Fvy`gQWuXEvXGJsLeF0Szj4 z`KOmDY%7^*7-g~mvntq@v15M0cNP6(6^>lMfr|H_RzFoUvTu6#H}XC5&N$+Pi|lEf zF&Sxw9QZzh4zD)8{0-jlve#izUEnuek8J)*DZ^)|^LA8`N?%Wz{xK!6x9I zDLJcUCxIf`70u9&yy_78OFQuegpySpLw2|CA z|JHBry=?gQ?UfOwwB05)A+;v^x|aZkUKEXR37VUjm&mc=jXI^vFHyB9`hc2TwaF$~ z137j%-IfBi?me``wA^!hL=vbh zA@In;0y_nel*r`GeN2An9qH_7&~J=Wv0HJa1HZy6$fe(t)XHB6%iEo#ltVhpVk~&4 zuK0m2!2U4%MscUkm7Vv!@w9kLdL*<0;gPsqKL_N5F^1}ro64uDvi44UbdWlg zycb%w(x8u!6meRCMY|c+bh}HLFb+4~GeKMNoooWv!C%IAbt9Ra;~9F=XQNhCPPEWDBz4>29%Q7{ z%zxWFRK_sig8$}%E_lW;i;Jy|K%0$hv7ti4xga7C!RunE&v!c6e;_pt+ts5@8i)Am zs5kt^Tg0i(TdmJu=@!!?WOTVLk>G++)#lQH53kdbvi$ELQ^PCXdpvGtT{;)Q8_K?Z z_=Me!3`ti{$Z74(k!k(uSeCx$gnx&EO^K01_m$s?&cy`O-x4lAgJqrju4hMCWtZW~ zK0JVkm`3J7LCA0P^p7ba5KRJrEm6uQLgHLOON)4~z@J1^Z*UbLk8@)t>LsXxI6pTg z6SSE3v9!bB+A?JC1sk}Z#{YoC6aqZ)#;s*8TM7idp(Vwa8T}LeVL3eCjeGKT`T5H*COV_Yz)QTebhSsdN3g07J<-*8 zX|Gg>+-6m^2K;&>VZ8d!DkhTrysY4CDZk50N_(c z!4D=b@`lAve@=<^%!tvGX{T+ABCT=HURmEEBZK0JBC!~=RZAQM&|)(4U%7+?oxZJ7 z#fSBB?E6RDI%hbORD3EfV;sf=C7ES7m2I%1^BkaEPOO%b#@?k&(YO?NZ7LRzj$(V7~^li^J^>j zjTfJJ{^48u?n`YE12%8nNsMJKxC2Qx-r=AAe!J=Xu9DutO!4fTY1wZoMxaIYs&B&kAp_w4h!{IoJ$M-cD1H?^n;&d?E|HQ7bk$_9|v-q119Zuv6hPSvXNG3ev2*2rhO=Odcp{i$b<$MeC zDcE=C#1ljjlIdFn{%K@C43sWX39kz&vN6$rq(D@Q9+7x6*ye4Ecp02?4%1$BM9biZ zV9y!vBE{*)W|JjUTt6qTbh?Y&K#$J(-1{oEra!p%vD?R&bHA~)K%iu&`F#(PY^w1f zQ4$*R1oZ6CqW40)A~hTizE&9+T)I}E@m5>5DV*IqWb4g(Q=;9TXX|+6nI}2IeS4ZR z1Jd%FiyNw}v~_Hn>4haug`T`ZuzFgCY@;xUsbFqJV@>jI8E?Ds?Zm58`5^K5^BOf% zWmL;V-Y)d6(l5IMGYx)ojNAQW{&ur=kw;V+H|P6tE_xGh8OL~?tU#=q)x@>KD1Gyt zbbaU&QJ~8up4xZ`m52q3i!hUOBi$`1KGsWmv$LQ92MKL;#lY%4A1B3qzMg(TP8Z5aGKVC+7(l0<$5p;Vzyz z8~Kly+xs2220J~M@g18G&kkj2ydIPz>qCA9r8od+W_QEL3Iqu$2Eh(4nnGjT?$k^Lu_^7 zZOI?L6853r4o3*VPG+$5oe2!|3oOt@^`=?dbGF$#CQNJN{>|F2*f_W&q3U#w%*QRc zfFl$EMz{^7ajr*@_bhLVE3}uXzb%BF@5u%4Q{q2QmG}!WCBZL;aJ@B>NKV{5sO#U! za_?#V{Ighq9gEnQ=gN)>^=a$i-%i~mpZ6iZ?%{}>`*4BeS*!_J_q-$GCHd<{C#H$`OrX|t~*;ZYzXPx)3#fTVa@#x#0?l&#n9yK;Eyg$bv-K@r4;t*=!B&7EHiI{1M*w2E4mkg2dE=AH1CB$bN z!y@jzUa?%24RM0*4*jBUC<8s0ORfS#beriLuz^je6oxRk11bOh0VQMr?28`wT1=wH zwvUbk0T)^K#PD&eNZC^}5HlYuh-4FIR}Wn03>~IE9hDN&1znGcz1kIMo3pf7#_REw za1FBxGsnUn(i1Ck_`5#)JSg3i;=MdBkNulM#gy||JzqMzCnS|P!w+})F~3M82gOv- zmBWPAJOZ7KaWc90tJWqgLCSMheu2keO+n()(~6B$jmt0N-iTL}u#xm7dOuD|HnjxN zeD1x+vWQz8b|~%(>>(YyO9}}yeU;|R$Mecd{_jr% zHzN?ncr(@(jK2;9bCUs#U8xi6%=F$pD_fn6t@qJ!Qh(*(J~>8cEg|fO3=_&0^qf;b zmk~u;W(*s>{G2w$@3Xm{oNT~A0&7I#8WX{Ofke-~Jjj--UF5`OEeLc$IfrK2pd=ta z+puU$-otl92^h&R2AqjRdVX@bfr$4L^&`|iQF!*@+~Bs*#Ij==fP~@KU}w~fD;+x| z$aoJKN{j#nqo?#{;`qHm0zJ!Nv`B@B6Q7-1|E4bSzvJ3)*mkc#mBZQf*wJ>;elXTT z2NUixMo^nZ$&bc&ubPiOGXJ!*xF8bOZw`2qfJMinWH~5~qX1?wMzY#UP*m&5+4>mDREaHF(w^Z?_CNXY*jU25R={tXI(y zw%8}m?Y;ndyF!>>z&T~(WZJi{lHmUNlYATFS&3BiQhJ$9TMc7qUe*reMe%c6UH_xe~ND zpOjg2oc+a^!#Hs-D6V)ZGs9Ar_qrdW5x0;TGtrs!to|!gp6^Zq)yZM z4UFk`vhB~B+KKdv!CYsW?E*37RIdjW&=2SPN}%8KH4(nRXvWKRP5& zqLg(|3zcGnSGjrlwepF8Z|Be*7%qNGG}2(QfA0%<^yQSUvo|0TRXc zBDcIJFFx^30@DF?08Fee!g@>_WTQAJ5X1d%*QFuX|a@atglML0lMNYJL}*~(@>h^ru4!9Z#m zs*TV1aaSUVln-JJ3UYqu?A^QxZ^1st*h5-RwBk#5R|R?yF%UTus#1fVOv2}$8+?)FJ9|Uy$)a0 z|8)l@p9|Zh^~JR0V{O41ArTiWegDvtW6SKKL-8}601uMql6Iay>#@Lr7W_(~d-i>n zH5yvC)m$E^~dW~IlJvYK)A=5ienABCSQHE~{ z50vn0f>}#?1S(?(H`J3x;^;#@vt#`;*(>7ab}%za>!0=d~rFidL3 zhgp0M9%-x5;WTJh0rb65Ug~@^rYgkKA{^;{QJ;p7v#5_<+<*aU=w>@qnrrFytad$4 zp03>WJ&n_PqW1rr<*Z=>o`q2lh9d!jk;eV2-<*=*8~_?$gZlpq+_%tlSQJ1lLqH(B z=dYAoVpwQdiw%{=+EDv@?_{EyU3*o)| z>M#c>15*^xvul@FU|fU3aE(EyW&V$mAx=_%ArJr9WASDW1G`2H0)qCVEi#KOw*67z zY)rc6L6nx&@IHzdT3qa9P%cR>&Pg`+GVVIY7OD9eCV#LPpjcZUTQan{0Tql=>^+iI zxiQ-HZ=WNtKTQ(f&&-p)WK`6Ahc%*MAC^JI_9Dm|q@NC*_jH-+KRWQo>18^bwey(u z9X7O&oZ;Y7ZJ41N)UPmb__aIBwM;Sc=@=o*W4Op5 z{M)C&=g3UHFN~ypZFt&{?R&b*r$h@>^4;zE+vX32%8#WNhoY#&waB>**uNT;U5x+w zM-WGJmiKo#CAQ7DL|0>`xwcHc4m%~(m>bJ3#_x>W?7>eyh5`$?(ayU^=TS$D9WM2Y z9D;&^v(g{Y^9`n*53crq0~uTUT_muwYxuva*7o=h7Sjz&PH{oPj*AkyWyY;yl%cO; z=E-}_(`f!^ZEbeyA8(2_C_HgUTlTHq0oGKdishI9_weV*~Y$;bh2 zm(U5pg)z=$E8`j$r1AT(ydZ+Y7|89xDgT&WB-IdSDxctu@??4%tkRXJ(;Wz2K1#yt zmTgEdK_M(g;Rofeu+>U4Zq>W8N1Jt7X4&Mrni0X>_&2$dwzfg)pHwr zyJRS>Um3x!cC7=~L@%E^-T~e)(_cK3g{`>u^%mdrGC#<-PyM014%M80fLuEHBv47MVs+!E^^Lv=f=r7$}kKU$&;;k?0O-JuHW|qe7}wxU_0TyknGhi zvb?mx9^`D@MWnG;spH!!%s{(~Z~q|WL!f~pS-`fc2vbUr1>;AY^w7b|=PP?GLLryHGc+y9B8>Mu*y zSdZqm)lPE+88~9bHloMgLtJo)J*KQw%2rRq-K`G>+v*6b-R`#r9tMXg?SprCMveCc zoSAByKRCXw7?u&|Bde)UdwPx_?F6vFO2f+@7)KKY3>H00Pg3$yM-UmoZ_*=7WfB1i*|3=`>~6^ z)bY1;^nweu+N|Q+T1QNJqJ_v*y-lLH6n%YQ_^li9XCK(ycwqslKI}foQ=aQq=-PGL z%qGmh`l{y<1TZ8udHtqyK;mVqruu=cN3{4J|7i$^ND}(2s2D#uKa$=P4y`5oLw&A} z)AYiG6tKvl+1cqAl%y4&U@S9I$-lyZT!X%W%x7?7F1MIwwZUAEU8M@AsbJn$aW?Mn z#O&;yqX?=e2I)saZm_`bkktHGt^^B=c3k12Wzdv-!SBAn)vswVo*M74&!%fgW#?Km zZcMOh$`zTHaWtoGOdcDa<JA2qtcq1-sJ0-;s7Le3##Aadl0VPKG7MPQ-;)p(E8#UXtsb$xR$u zxGERkfE!bu&*^`2iz)e0j9)B1`>Xn3HDoyP5Ln`d`B-K;%>b78S+X_Y2H>ESBe>42O*6vNz!sHcsOfkXKPvE?-;!Qsc7B^)}<`6hSAnj3)JJuGbu3LMCJL&&-ADE!-j zcz-QEMgZB`$ovVgN=#q&w&^(-hn=Ax+HUXh8;{J*vDV()@OalBSRcf0Hw-0Ycx2h! zKwg6(TV!aAu;VQ8ze$svG%WCUEZvz-MO*-GkyLHE@59s_mKqorTT4?XE$Ec+XJj9> z{cfDTL;MOE8|8?N-TTjyQb#5bVe_wor3D7b&&jg;jrwf zk9vT};L0S8*n6$weW>y(+P!Wzr{LoZ00G|||L>#M;BH~U1y?2C7!HUKW6fBp1xg&| z*|Pfpja~FW;FOE-fwP6HnfCdtaEGuxaT#S$Nao{ zCcZ$v%dbz@4%xzAOiyF%h#E(qwY_3~wE{ z{CZk|_a~q$gw@>!A0@1ayAJt^`qrgXitWSB^oq~0G5OCd_m7PwV+OZ{d83_qtxl3R zzsb!53{kE^cUt{N)4z`0q2X}7_dfYaFH@VoRZA>d%^>;sq$fmmh8d^WZiIAxW<{o+ z{Y%p%OZGC1mzbVOF5H^9lhfS*dt-1>vF#>VeL8J#EHdfpeY{$HzEC;bcLnv%Dl%+H zvdjl|Whx>om>2i%op?6Yn*RqktDR+QZ!d^GyJxbBiHYq!W>g0NFDL^*^PRNfs80eL zK@l^_V8Z%V_~dgoA2Qg|GLKT2qHI7$MJBOYEkr zImq+#4oo1RHZ{ZiXza0!(*lXbMy^p#fKlMOAlHGqf6iupWui6MWuU`?K(mbpP?nu_ zF<1Jwx0nfSng3pZJzQGI_66YjVRpDOFC^2UjR!~o6odgsawApSXsLvGgPU9k;&QTX zCTkEj>QJXJ)%REkQwif{muh-LGs$uKWm@~lk@{>d3v2vQHrh{M`e>VoGaI|GfI){q z1-VuAN+_LvhGFX^);AOBOJm=0x3&VbWuARBI1R+NL9b@HD^qIbxPgy&F|<_Vx0$K_ zj!(DH?%|b_Bkq#yifBk8!aaq4nUgUmva2gMYoS{JFQn5o)+|#aGg!p#`9Z#YmkjLy z*n$#5XIb2B$^e?a!`n4+JF`WcT8S)fi)76ey09r^{ z%H(%yRXXeY@ckVDWy?IiNL%>3)S||YRdqStj&J)i%xx36S*tJ8C~Rae5rsJJg4VPk zqRWY|>p1e9MFem=84*c)G?w)UHo%x%>3r!4!Y~67RNZbov1vYVuoKpNf2llsWw(^v z{zY3s-}40>oyc2q`Bn0_IM+G8U7y~7aIn))^p+Eu+)=9YwzCcPiCp7XuPiiNexnt~ z49L})C}cTL1tw0+Bj(oi6q7I+!*hPU-u+tqM{PS?ML+>u_DAS1CV@%u(fe0YO}638 z{hVv`H=+H7oEyE@JGU;SbgTQCxxqG^=+`^y-am`c1y}u(W9ZE#eev&bMEQctVenXm zWt8Ud%)72T^fY!TajY|tbsN$Q2i#FtWwbZouL-tUDZ(0?(L5h?X)!$9E>RaR}Xl@wOa}YeK8>s8X<1thjjO zu<-d?L(jk$h@NtufY1-fTjfHS*p?uWb(UT{39>DnOXwdUL} zbHWL0dP=+EIb4Mfz#f9y)$zZCIA)q|2o_EUct5{bCM!ibJx0`+K&QO4?9JgiUPYaI z^{wP90`l~Pnzo+1m2=UqpaJ6Y^1ooil@uM$pw=-qskn^Fyk#BO>@SOSlT^a+qcpYm z4O2k;f{_A_$hnW71Phq*Mi*nFQ|2Fv|F2-lprqCa*teCE;XOw5UbRs)F%S|G23I~Y z1LAl9#$BKFO@^)GFc4_(LF8krfKw1QwaE^W{e1qYI!GSCM34YEp{HziJC>M{vO(uy z62!_TWdT?X;xp1#q4{dJW4BOW>zf$M4+}793okkPk9n622>p%kx6S?-uqmdL5djcd zpOO-1r1U{4!~`pR?S85gs)iGR!;i8eJG(l{Z}}{DAVR#X_-vDAZHGv~F!@hr$OqYB zjm^aS;1TPuLez0pncdj!4-J^BvY$Mz3mR9e?m`F7D7A{R;`TSxH0twi3O+z)S4A~YJ$uE znUj|LZmm3Odn&_%j3ot*5}5dsh1O4l-c7Xgxi3rDg|H{e$PBH!(>CH3wZx|9$DyJM-dY;m=~h0~%yE(z@O= zo#d9hO&Iye$>h!1WSO!M9}d}aupBN8olMY|$?p{#+(9^0R|()h0Q0gDNrJ$JOCZ=s zSs6aLBRym&d8t<-Ymzm=ADEv!pL&^%xo8I>UZ(T@q%Ivn7l!qIrKyaYfxyIhp<8k# z^Gy}h8ocK`aML21O)-L9M>a0@{@N>%ShfpE$vG0uKNIrHhHO{@b%^w=QZ#D19?e^; zm;dNAs3!L+GNF58KybPDU%=ZIB^e3~a+AQ8T~5b!(A$XQ>HhuNMV5xW@}JM9gj1$h z*`#k2E7?}_jSvduwT2#IEc8tm9n+p&r&BFk#`POWPQtE90;02KQ@=Zx@%^!>DTiMA zFZ%OqrI#72CU;ql$H>y$zT1CzHZVyUTw(?WLlX7Y>e3l+-RTMr@}i=~2KUYqovE7a zlI#Mz1K_Wh&oN(mvEgy=v%nJXE;7X-P)yS6`Kg7hG+%+^zY9|Bn?6gT=j0!rL0K7+ zjz7E5@OSL?0MiQT7%A%XVp8#visPLxxsxX3huv_v|A)h2x2;3+A>Wenj+T;!zZ^#X zH`TtOH483E_!htY?{4-Nq&eaL`82~k88%Oue2)i(UE1*2Qk*HICI8Y%zM3Oi)F`=d z|8~;%TDS~SL|t1Yfi!TCWJMCAv7E5E^mHComPt$%{1IF60ExRtGVc+GO$vSHDvpou zM5UbQQ98^i#snx+eqMXytD{3(ho#&`7OB=D`e=2J zl1X1IH_eIasLD~^uWW?T0Nc)T5P~(AzrbXyPiJ@3;XqKN% z!;cE_-7in}^Gcf;&R^0$C@C^ZlW?o~s=3h@PI3OZNq?^wRfSMB*-yTCR2wzgG{ znKZ6)SlXyY^aOW%p|CPoZ=7eb5Ot3F@5fL7f4<%*I>|ZIimV9(5%n{Lu1G4Ti{IW~ zv?-R0imAiQEV*KP^VN0L9>vq8Zj-BonS_T@(lCPl@R}b!+l|j~=wh?9zpBy{{IENS z#*775^7@f==| zaYr4{iT7LHTw*Vk@HF{*U2yVq)_Y#m-dVD3|EmrRnYGtfT+BXLt1~+n!lg*UzqWh* z)%zmK!=lFo2TNP4w>inrcXXBLNyB#=dt-b==c7#dXs`rh!GkQ5Oe2)MV(2Evh#0{% zHaoaa4yv8~FpY=dFWB#Jz+?0rd-qlyr|om{FMxM+b4Nw!WrzUtGU>FBCR%uAMkFcrA7c-wDBu z-|WT~B1xqw7OJzLLwylGwa6pgvGUFF)L>m%6a5l$k`QhMTWpmP_mjzniEWEJdm1(l zOncZgrxWZl_5JbfgVNMgmQDo{BYaHl1M#`-R4l4b28Uv?R+|&T?|vEn_@+AA>YB~d zU>5KY?viJIy2bswa_qEm?)BeW4I_xxf9_m3yt!B+_E_&tXJ@C&ePt79sy_uL&8_d^ z;%{#~>No#34Dxm$JImxKvnewuBM`{C--^F;?{cOU*;(gyv{6&v+&p`MlYld}QrcVG zPPCd`pZtrty3?s0#KunH4$i$m8lW$daWz zzjht&8^7}usoQx$W3x;D^6cZ}9X>q{ydFd+6Bm52!&KQ&( za{$8+jIurTvdq=@k3~BRMf0kv4kEAmcG8pC?Ka9Cm=?bVJtONP+yeKMoiWsc05>ky z>(e2X_@@@{uq$0obuG2ErW7YMd`oDG7C{B|iIW@oeF8%vBx~(m95U=cDYFKFAQ2-B zgAAy92(2#D25e|g>%f5rlX(uEhGoE%hwaNm&x$d)km3rp-QgSV($8%JVF3l<{hW{2 z{w$_^8?7O6X+nL2ds%#^!Mv{es#!Ax^to8rcuFVE*yf?2wcZVeB0H0;+&$iRKbHdj>Ev%2j{Jy`Lk}7sAr-PtH za11ckkiHY~yOC5*QSKp(7jyYFD)~hA#27|aH+lu96-RDdy=l%??`M=Z*3~`wC8vp! zUvWdqFI1B4JrdOKJY{#Pxo@g`TSlD-{(G~d{KSE~z4}X66pdBGPacCh-n!gZCR$0? z>upNw!~T*6Z#CX>4J7>Lj7hMGMS8nJ=|r_ ztD(kiQnu5(3*0@mSxk;m1#UQvQ|kInY+#?+RyL`&xj6e0?s<@C*Lcy> z79G{I+#0AoKkM-ZoGM$&y=Y*kLbXAA{6G!!GsuY-N7bAW(=ah$gv?}HS z66=9s>O5Zc#KOb~0xN)o%vBW_*PWo52B3t`I>nyS`L@(;)rVoZe~Y+rQ=ZpU7A|(X z$`zPVnnsSs>AfaZ*z+;Zl` zKQL#rT-02lj$KR5cU#Vo?|GUX=WMPrA|<=J?RsQ7#4AlnUvt@V6@8Ve5h-r=#(#vT zNjeM&U5{mT3fBFu?D+W*R60CQ91Xu&GDLX0u zhTB$|wwP*~C9HaW91So3q)vnh(gaDMms=`{AapIQdQM8FL&i9`#yX}g6?v?zTp%pR zM-Qp1Eqi{DM35MKU((1TzBK6xLFbF|v#%2Qdpwb-_CEjHI?GYquM}N_qDC};J2!@m z{xLaL1EB_!vGb!j{e%AKc?TB9sYW)KivM_tu(qU;vKZE zbU>uLTe_Q}qy)b4JJ9h{6hAvd5e(^hOIZG8%VPi3=d zEJpWU67ncE7OQROg-+3U#0a%fuk=T7a}6U1?t$F}hn%|R?i1)2{^B19*HA-3b6(v) z5x^E1PxAGCpWofzn=Fq}*Ie>UHku`q8`50$%;E5m-^_?adzQ17=}G$u;Sz}FNJfi# z@e|XK^pM<;^whQ^GnI2eMbNwa0(Emn`xL@8l?*ic+1Q)q1tkqIZ2`CRP`~;ppi>Nn z{rc8O^Ml(d;}*+%JN$Ep^>Ngom-Un)%#d~szKwE^x%rF$=_9hG=dk}uH$dB zGoa87x^rOu7~-Q5JjHO5>ZkZ7>YQ!iz3}ry)t-~PPmTOCtX>6u@2D&V4lt&?38qcH zIIsS@h&lc%VmcEO6Yi%YDt#E~a)Zzsfoo1#!-CNP?MY=V-H&tlPg$;IcNaQW{~s;wApT?UQZs{(xm&c0=N8E|do40o-%K2BF)~9kJ|8k%s2b`a+LgKG9^(d)nD$v~}>-{?adE&}k{D`E2lc zJR=*DJm#E20Gt0|q%)Ca|1o0Y!{jdt`}lib z$c#_!@jpb%e{;F-g-yHW_!d8JHK<+K?qcFqAMcbY3=z6xGOf3e{$ysh@8Kb#YK2#M zik#L0;u?H8X8Pl~PN|VB;*OQ(+vY*sVpS8u6a=*=%+z^qGZ>eW70801b7nKV`Oy<~ zC&Sv^bm<`M?7{Wd?yPR{JJC?m{YDaVf#?vJ5H8P4*F{J10{^QVhCDnof3?D&H%4w8 zqjwiS`?4vuYKE0MncT#h9y)m8?G5w8BSy?lyy(RS2P&I0UK-i&Qo5U%n(@=jYVK>M z3HQgW?9hVg(l%^nrC*!sIxa;hVVrAvAi_{0kN8WCltw69lWD~|)>Sf{2_D->QK@s7 zouIR*medWO*%;Q&7XG9{O{}H{UMW_mfXazyX^KzFeeVZ0`xvKkFA)9Yt{+bA8>TGW zn$sBA1_R4SX}N?hKWqw6V(c#m-f)Q_!B^Xa$1!*&ED0-b@k){J`23SOsQewLPVdl? z*iMbRCCvO7D`bzBK!AOT>O|I0`OD)W7=HIwgF6FdIk|GrlTRGFi@Ye6N3m`unescz zZ<8j4vMBl$BdZ=VeN|-Oin$JYb;^s5woS2>{Cd;tb(OW5=^5g8tS(frGyl_eDV( zvm}%=Pw#ttI1f$>my|n|uyw)YhHfY0{V^RwAzlshVT`A!G%hvyWLLQJjZm<0a!ewYhOflbWkuFoa1i7`HHPGOSL{=4C?8 zT9ifsD#1x=hwGjsv{^QiaI7uF2c2i3R)uE$x(C*$fR9(cSZj{qMT?!=zX6I(TeO}+Y7b5+0baVnc$86)j) zdh+sT(+((oPp!CiT_NJgVNPfSf79_5p*Pux@v)u0{gtAcRo3ts#snW< zqOw3nlC#7kG5co;J6lQW8%Z}$g|k5A)4NgX5GgFrWS@CY>FtkXwZKOp4*BrdiU)nK zt>%N^y*3#T2d*Ct;f+;fN*~-q=sZu7lMET|hlap(DcU8@EHhUKRAc~)wH`lKUe@PQ zz{O0BI#FtqX8R_cXGCW@|V=Yt|IDIw@7<8Vr-Lb zo7wbX{?JC345>{$)dgp-bZ5<-^V&4WNC}VA>*_D3lbcB@7DkBAYxZ=&#u$Fm1PV?K zSb>ad5t*_zO&+6lL&iO?`g)x;o}f-HKu90_mU7KSxfa9OV4pRcvYOJvWY&Jp9q3OT zk{hjzA6EG@MhK)9Ab7dNGNo4met2YMMW1Z^S6luXzIY_#KUAaM{n)waHHsDO*}gky zo|A~@*7iGDawL45`l3+HY2nzk2|v1I$1(l>cV3E;K!j@%s1^) z_J$sgwC{q!s8HS1;Y zd2Q^sD6p%zLOH<6=Q$B-2ZB`Qf;{`V6^aGk3FZb7O+39VVah*#-xc*#PZXDxIMYsYM_$UX?cU-2C5Gjg5MGK@+_mm! zmR&P132m{_`F3sJVu*~ko1pj)!n!K?2(C&#F31HKHl7(@HkkE&S&gm?AeeZ&>%4v{ z7(@5XsV3jR;b+F9s5B>sFyG_zcy`3t09)O2YOp*sB-3zvqeoW+R#>1h&>buGW8dZ` za9&E|Fzh>DSz|Q))h=Q_e{;#iq74AJ$Z|MnKR0BW)Y&WD1sQkiC7C`l^RMkSJ}5Yf z&o`?$zzszMxp&3Ft0d`w0U!-{w2(k?1cEU}O+`Th&T=qPbCkh8^xvGaym}tT(vzjE8P|V6!L&1U0NmF1j zU6`|&wJW52#k$8ofi%C60b~B#dI9!FlL#A>-2m+mW%jcd`Uyw*CmJVtY7}F z0?kP(TQG1Rn$OquMir)kaX!t@QXFK_u9%qss9~%2lket** zys-Ycl@#C$<><3aq-@IrEz3~ZA2KyUM5$wZvnun**$mM`ktS+%cN2;l8F>2mhH31N zcaPh0-Jd->hL#*@M^CXsswKHqm8`LV^08M8#1T?t1W&-(pK!?tFy$u6cZ{>2x---_ zUe0_9nVQ%I`4r|u0Yp{-d$ZS?y90zs(X*8%+!VY6J3aV*MVa`bpKcf_6CYFH-#2bg z^D8U0!-(lPY}4O_S=rd&zH0j42U5Ue%=^fio1Z^vx8kR%awLSso`%K-yNmmA{#}cF zb)TO2vtP>d6R{kTrGroqM`7qd@uvuuh!;_nYJz@(=7R5z-nD6W>JrA#pu7ayk9d}! zh`@W|PXS>l5DP$&pNRbOWO<-5fVN&DiOSZ-$hHtN;MI@AQ~^J1yAa zM=OAX`!=IKs5yI}z?aE15bkKvJv1VHZByi!`JrBx294!rps(wCmWvle0ziAQ@16Fj zC5dawnI@`3RL(KTom6l69pdRMAJ?bm6Wd;ti%bCz*Hf{K+YBn7LtaAThIpFKdZVnu z^Q{pe;rYHKwL^q(fuw}qhRgW#h%q6n?P~FY`jrgkDdJb*1i=Mu7r%a`=)zpyji)ED zd}Q^StS`NioPn=A;T3;6y5mqF^w`+cK%XU^Us6x^$E%@irOTLfC(ZvvGXzcEG2Ia>_)*x0gWp1JaiU<>@+YeXVc6>MUuN%^erL`f$3 zu0?g0VWP21aES17gmhANAf|fDb+B02@sONKO}1Y}fqPrAx1&Zc-jFsEff^Qh`#8-O z7nB9^N_d|2hG81-Z?5T;T+ev@2z86H^eqqpXmln?w8+3Y;#d!O_+uf?6O*Ucr${QpR`+0Kw{|h$`kx`O-GV#v1^<6m#iAx-HzI{YGu>{N zP$NT9&)wafjW%kQgH(l><{_z^v_7$S!?a|WWT)T~J}4D<0mWLfk8GPFErR(DdEh5C; zb12{z`Q^ zbJ*_WvsP*QYpp7oLM)xnNcM%R36cQX=G3cr$(H>{ z6&f`)+};Qpm8KxSWZ3)WoEUszt8@{4T2IOUau-Xx(LT_1GtdwdBHXZRE6)r-y^s{C*kXZ`y z!xI6=wV@g{##;7Cpx@oG;|1RAU|1vF~2(X@~C^gfQ7KBfP=i|7C>_PBX{q$(Vn;NJ;6ZNQT8shz>$B+WC`Vp~=HaK)O#hBK^L-9f+;F z_`50-2#C))#L!?yZ-~LH#Sn!{U&VpY(-CnGy*lWBt57v<$%{lLz zS`6TKMeR?%m-<_Qr@A@FK#V_7@+j^mOLn&WF0i(~asowC?A|Un+mptG;(jejJ=!n*kw{I8{`U`~e9P&M@!S1c z-O-%H_nMoFiwl=_+8Xl_EetJUtM=Su8F5!Kt8GO=ia^3N5ZIwhMC7BinV*JcCu1Up zn1+hb^h2D{5+8@+9sh^rcxkN5OGwQl1Zgn**<8KIC`A{k$ijBDRrBVt#oRw&W}Z-r zCQ`AYAKoW>_tR*y53$hUsP-aCTI~2S_|5fUQw!*Bo&(e371x>$Oq+Yx|I$gUS7EUN>@fBOfA6v?y3FJRV zcU`?V!P%m`r7!GpS(L|huKQeTKh`-&zP~0TcTiGcwLEG)iTi(k!3D*^zR4J=f3rq) zQ>O8JufI>HDt>&x8|U0Gug{3_OEq@w-ff^}bXN=~As$rHls9@|+(=!;Sx$jPN5axS6@AFFP z&Wx&JurQmRe@Xx++sfaKnqT%9o5J`*ZqxRuJn8t-8{?i$^pzC5vFDqRlh0q>;PKgmQ zV~`kSwdS-legL2o0-=oVi>?dN9Fs3?=-$AuWg=UbeSN{_cvQve@bb{&wcKns?&FYS zouX%DbUBA1vAQHupQ{tukP#U=N$n0i2^sE&yPxWHY{gtzP?-WSv8?QfkTLLFuj6aD z@a`k|ho&G1FGdpoud-97vc}cIC zg-rtnkMZl)y?^&D(H$lziXX59I;1r%Ah!PlZ?2#9b%Q1N|AognZ8jlJHhT1po!JSg z`D)#YFo6!*7|D%LPjBx%9p9V8fBemmw ztp+p_x64a=cNKM^Ww{!+bId7p1D`c~Jxz(5U%y%Z?7qGJYMRy&|2>&6g?m3aKRfeN z{1^<Dqjom;|-{djhXgtQP%MuTOS^wuWbpI4t@_t3<) zb&|BuiD4CsejCYNBvUAruz%6m)1#xK>nIRXcQE}oxEf$uQ)Ku;3B`x!7u6qutwBy` zbF6Q}%Cn$aEZ~KT82Pf)B$X8<)d7ytr^Le^x}|mCQwgCzG=qG1sp=0)<%a;GsU_GZ zCZdy09;ognn-(q+vO!16TFS`w+R{%qiOBCNA=b1q0L8jet)w++WojkI{MSYiYq44) zg*SZ%y+#3%qGuFkH{&^qMqh(ij%`&8?(t7b3jK+^Z(YSjn3d3x8iADYM(o?BHHyq? zHbly-W6gir?2m9T23O}rgAgZOg^Ye$h*L`c`~d@kBBZOcuC7!1lfzFbHn5gL=2FV; zCvI}Fv9i`>@?yowxn4QZbf85MUPQGli%0aEO~y$&D-^5Imb6COxeF}%zL9=L8EKFI zT8~`goMPZe*B)BQt+Wew`we?8~&$QrSZ)WygBB6!StnMc@%lQ6OYM#5q zHXQ6~g(PclD^NTqj2Oemp_DQS$pR}Y)ry}CoIbCmOm63z&m0zV{+o1*mX38?w!Ha< z@m)|ElsPxSOo;lP#kn?Lb}n^bipFEi$X7t@aRa4p!d0o3MXH-ncyY?S{Y{m>Jyg52+*lseJh?s9@u9OkpxDL2N9Z%Rh#}5r-h@4MXg$VYvsF zcza8N@hQo6i+Yn&#*KU9&m_!Z==jg)yc(o$nDEB#{qX)g^fQZl+u;jrdiCgJ<6}in zZs^Co>u4MX>zJGKMD77fEk-E5lojLE=??PXuB4TeG)`^sObaQXw#EDOPN)+q{0;}iw%7SAwfMfCn72&zsI|L&s61Kc z@BOuV!-g!2d=-`Rh#4+V<)?MO$h~!6QZdn@?kC3u+a#?M)N^{E*aviqatSPZ<41+`}SG-`v7iB0W|W_xSm3cALFt2%_Ejtc$9<$roJ+Nie?cf9xN*$&yX_MOE@DY?F2_z1+Vg-D;I|W9%UVOaXJ59zpXL*4m_kB(lrI9wn9S z+eCv2iwPI2>@~v{RDK|mhVlCE|9+&rtNatvKe79lck;69hsD9^_Hj}$Nu1$W;m+$4 z&lXIK=F=ooj^ECrkNyw!H|OxX@VpHAe8HaUBUIGf?)X=H0=uh5^{<=!hms1c&?R=2BdE73{ zoCYRXz{BldJ#WLh*YaDfOB7o(5_A$gMVG0%W>$WZt;ja9M6#NZm1ueL;qDvtp=2HRT$U zyn&y|L*pMBEg9{N%&7Th>^w-aJ8I%G(w&BAhnW0H&<~qzT!(T?YEG2%2iLS@wp=?& z4n;aYoC8zaX3Si<{b<8%t&0Wdm&uR59$F~C7$r>B^1<&3tISPhVe74D7s=?|lL_t@ zHW&VXkFKZ+9bJ5P99rRq?07!i$xKxSeV!noScAWzj2JIUpu!F^TQ^oRKDwZ3u53k3m!XHx2c>7u&YFZ!U^yjI=i|r%ooKt(>j-I8(sWB%Az5?W7Ok*B$4;;T`8&4G zxJ&D<)M&5nM|2ncoa4?Lcz)FHc0}a~roOdu+FxYC zO4?}c6+>e`g!tJBKDJOtDa5v&)1UaE)gCKs-7mB-)z&)pTCgL){bdKf8?k9`)Ybmh zi>zfF(~6{iweO#OQ!r!1wDhY3K2rWgHY>!-on&~;w3k)tcr)e?+V41BSEZBMRRGF& zDQFW}@h4;ASPUlrbOvj{afV%i9HuC*?_Rd ziG?3x^9BC~msbHPGRLHETpCf>m~>97%XZqohM4?45I=w{+ZdBy)a}0%@-Nb+&h%P( zw4I{(d6siV-uJ4~$2+X)5Kdh`aZYX-CG(bZQgqtjSY4N?xAn)Tb8@;PUEL0I^sIdQzi=NaKnB4)_3r7n z9iK&i&VTVe2?+_^7-64-K=jY_vif*J*T&b0*6YurXd_FjLXM)yKLka-ApC3hGMKUw z7ye9dl}b?vBR!HqmnlT)_1m_7N4|!FBE2JhZUw@Q9<8MQ0v}BH5qwf)ufj|kV;KM_ zzy-1fghUa&@8HQR_f`MKf($yvr5=ZCjPeJukALz7IoaWzwSVc@jd2s1#jXW~ydVL{ zNo7!%0CtPG!mPmiAQ_UYC&R(yF-45Hq82_-CTY+%-Ryf#3ODc);0bs(9z9!pw29sFX8KPi4!D;g=@LUqNF4uf-GBI`-7=moXrIB?W(vALL9 z6e$&Als70(h(Vc14rCjSp5QeJGqGx}Og|0O6@vRAoZ0c8YX;8x2@xpBj=IdMv>3cO z9&Sq#E5UE%Y?@VzqxI}6IH36T@&>_4k_16EXoIZ$g9;-eEYoS@tngKL*6oUfQ{D{- zpOyGV<#G)Z>?2PH=Rm7kHB)2~MCJypJ!Mc+T&z9(4= zn^rp~dy}B_gv?D*RnekTfsZ~KnVk;w2qZrkt1{P6*il7U^ z&*d4CJ@%WKoGPRY+>edeXZ_BO|Ff>V)`Cn3^_yrD{`o$dyy>`)+wf-^MtZqZQb9CG zjLGQLl-T#|>F+n#RtpmV1jmE$;Qq`={4h~v(Zx@)*j$i7df2d3#e*b9*3`2Z;B`(B z$wOj<+dVem9Xfp3QQCso!tYq7wNe>UyGvo-zWe~sv(B zN8+p$CU6!Axg^{i_M0m{lZ{b>^IB?Gks1?ars zcQs6o-Cty@^@dDROpNTkgth8taZBjRaQ{NykIMp?%nwHJl!p1Cv?vHjxSz|r1KSCB z$n7w13o0YsoNVhi zWP%F;?bvnsU|6SFELre}X(wRmo(V5es~#tBMZ&;uD?^4N2g67_=X-4*Qo!&Ctj}Do z?uG?K4r$Kl!?y!jqLV-OqHf}&r;ESHKDmZE z6QyjQD6`Mqq~R=oRBB*>Q(XLZc6#P&8BTg$`6&&Q7Ofcw_5l<^(4%s-QFVjJK8HjCY~5Q=|eZV=oY z>eX(=?^y-pcMN?mp?dlI{fC}YqMVsozzDxY;HBWR7x-X_O^5+9rN04!hFn9oAa!fu z%S2ERMI0jp6~a5`d+Q)pD_w-dH>f8S>IRn5trq^-@R3;zwN{1C+LYA`9^xT zJUGjK4gEgFk^Z&Vgz1LjUupH4($|p{(fhhH7o7lb%*t38HkQqV`H)$3L-EUX&-u2= z!FH!oX;i?9jsD9NTQY#{l*8RIed0Fa>{j$UZ8vD_R=9mdpaTyy{&{dRV^`OaC3NAhjgGQ%$KW0oWC05B4v#mXRT+5e$ zi-PegZ`_BqegmU>9qCFB)&}N&rA1w?w$c!6dNL??`xI+bUV@vD2v5#*62yD^!!jM|?Sp5Lqv=aSqtJrFL;_D?jAK*zQ|s%#y5=4IUT_r&0ph)+PFfV*NIJxHa}{s_McEtjDT#Y0J`hFcJa zxc3~5x_2SjTj!r})Vik79<2@Wc;c1_`vx(M-S@Taj0J~-48IHV#B*M%{$HW?7VUc%i*^ZXhf(9leLs6kqp zOxtDKo1B1s_qb5gKLrxdT>Zidnp>9187>ZhOKnt0Z&`5ahw$}yTk z)=nP$L0NHHV6!MES{~Re~M6rahVw$YI9ZbE`N^U)jciNHK61H1QJ%TqL zGzQM~1@&SONU#0FWwKCl2c2qt6*i1QV^g zA8|SbkB|1u^YDmNrHzofAuXS}`g^$vaoWc0b?ige2bh>i;H{j>>~B}%(gP=*LK#~K-AV#o3O{#9z8p`I1d$2GHIke%GeMcpz#+@?aV6`p zxi}_9ZD~FL3MJ3Rb>*2%CzNsiZmmSrzHIT-_n3JuaaekX#3Yvie(#O?`xT-xCO16N zN5|l4v@Ke7tQudIQ4soYr$f?vuJ1C^ux4$`|2z@lv0?Wy{k!)*M<9ccQnbvUC)@M> zth>88{0#h0N8*?}`11-|^-m=8d!PFJN%FpGEKD|zBv`>D<{8ns-Mdeki9!WD2Tdf$ zNXMg|108@al5Yxr3mhYjT0IcqShE*`NZVweL3;m~BU4LfD2mBYiuAB;Zk+9U`JE4g z8}Hm&82V)<%|Z^!mMhEWk@d-(6?;&A2B$zPD+SpTl|{;bo;9emN#oIa%pAq|IlGiI zDMSF88F-7};^C?FN&4S4#m`T=X7t6fDp~sGbj%&ocR#Pyi>saSV&b~ndR@%L6(=Tz z`I@qumc_m1QN_43@5y9EH}C^3=ef+umy>~ffzv(^r(kybLD67Z>EL9k0^AiSB61ITQ&UP2y^BfASHc*if}p!m8AZT^W|Ye^fm8a zt-dZocH`ampXT(5jr~62d$bF5#NxPDCHvBq(Pdh_uggHEx1NwJH(}Y;bc~4dcJevn zJ_~a$$^`1r$*j%bKW`3GBhFn`AeE=9F9)VDp>@`q89wzxq7!At;u3r9tZPy4_=6w+ zEEQw&*K@1&W)P{>zC%$*Pr35nE)!-+Wo|B!iy;SxNa0^Vvj}Q*`O@WPQ!pOS`LSP( z4fDg&*#*w4gJjcXZ>J6ab4A4G6I7`W-OtK$#>`4*-8iQV@dYW&$b7kV8(C{fad;>h z<#7q(q+9`I3@1JEzc4jSDq8#gQeU4V$<((vl0iyeNJ!|P{|JU3&zg=A`Zs*}FF{@Y z*?%86Bg}!**3;MTHMGrOCzZX(URz)9!N72whp6LfrN`WBlfPZ!%WmDjc=itpef;e8 z6R?Bwp@fCTwcAf3KTs+N5^17(k~K~6RF{`SK_385Kb7eMMEdsmV5CVM?%2+<-{2|{ zjPhl@SXLAqmLL@DWR#D5gBdoCHSwB=2{O0_|9Fmfb1hnnvGpc1b-(*o^V8oKaYM1v zMA_r~M{OKjyo!>`aR&5Sbtu&v zND^prrp?`in^V}R`p>Y7=^kp>cW~UV^L53*%5)!(?Wv{0+y@F=1r8t2Vl7$RC{Did zq+?rZ+CC`oKV{!G%!>R@;Y-4dck9OQRkROJ|9(69W>{#9Vurb+j-f@#cXGHUVB&6M zaU3Ux_t-ob&zySO`L$A$>g`;YAYGwA;s=6q9+YL{BFb7+Ye(Zw+h^26CLIrVuJ~1~ zY-!tyLB^THWoX)4VAh}^u9-7|fwbY?O?2Ii_J@UFPP%MfqJkpEkQhp=XJ$2w#ua;> zzi(1}DRl;=b9tfSvpp9S&xWS|^bN#5e{BEpG! zKM)hgG5X!haeKTtUOiQ$XW=HK>;Pkf^?wh6&c8#jO#bWYO(~aWJGn}-h4*38`D_>o z#No$&y>aYlN#lzAJ&l8lRe0z^fFCIl{xW%&qi-j`tN>=JU>X!WePOqEqUM5R!~38= zt^5EkFqkZ3e0z4(bUYLB!F#BJ<^QWI3O%P~n%I6QMmTr=N;O2X-l7??Zh@Zw6F?26 z5daSrkhz62YGDLqQEt}RL>A+vQ=#Drq1wAQAxUv977DlEyg0jyYRZH zW00xSC@8XZmvR`4A@0s`mMnRk!gX<U0U#gxOx>$A4j69ay=l#k1=Sd*DZ{Ahy#l zaSl`gM)1hE#A_)fbfIOLa)av6UzO&lpyzNyPz-)jzUI8p7?!FYM!&3tw5Z-tV>lHv zE+K!U`on2nP(v%rYor-;Q1y}13kFV{`K+gp>t)pjniK<@fZ7dMKQ$YDwHCz92V1gq z#+?m9#AjRo+Dw^j2(EV1#=~cI@H(klLK|qEt$2|3;~;ZY14Odiu6*2-pN8Xt)hzQ; zY7oY=+bwFLsLbn11>ZOLk6DITc2t0tfAXvO-~dY$c}tlht;N|v3jH+4@5x-YEUYHY z%Y?p*HyM&AJm3E`5?d#mrPutzieXPp-43%jrKJnr=AHaES_dO$#%LdfOu1;pv$4uG8xul359)|+-_=ti~@uLR*rN6 zs~O}UImxZDjFF5;@@(>{2VD;R%(&bD5mJostK+Gx*r)f?gC+U4^Tq3;UiuHVH}yL5 z{jnkO%pIwCj>^_0EF^2$O^^x5a(=-!Jy;G9++Y*Oh+_wkq+3D<=?WzHnitOQ8Wp1D~NEn|q;bqZ=gSo5iw@SjsrL{%}K z0C;+}CH}+-oWE4u1p%o8zQ|F{U#a0CLVqT{S204gqeO{lC^KQte^;SK&}p7-pleyt5cNAcsx;eZ`5 zwx#Jvz{dNNmDa~vn_o6kiaaQJKTObIKlC?l>b$YIJY97vODn)YWr7}=l2~l^kC!O5 zdul#>Nz-SA=;Co-$_*l1jP2>@4GOaukgE%W{ni8Vwh3>nGPQAAJ_qFS1FuR2Q?f6Q zngLu2{h_(dOSZt#VcDII6Cwa68@iM@U}(qbub;o#Ti!!|f=8c!fD(pKXLEYx4b4o4 zHZSmq_stH`Tlyh1sU2if`!@*D{D!|(>C+&10C0DzrX>F|OQ1n)1c3zy-&U)EFOM1g zp+CBrwz{T2@t+77UWYUTmO`8}pJ}xF3q?J=4jK{hxv;M{U(T>56CE>7bmEC9#z+DA z&Zy0I0erETn1$x+?$N{MI))TN40-!uwK-t`k0{pIwMno3w~N%z#^C?F*{1k;Fi*B@ z{8#KEALjpzj*YGF)eO}OboIn@_L2NJWSLr&()sSSXQwP|VFmC(^`5){Uf}0J6ypv7 zY)D5xN2FSN(TT~M-Jz$V#JEDroTg78UCCRJe#mEdCi4=}E;oooNJOSkW(j%P!jEzn zP$zD+quC#atV=>eV&x|Nd-W9|;3PM(NEZM*jNeogi4UdA@n-im%MD1%JGVHsyjZm; zd`ghx0%?F!Utz8KJ~I?S=ROmGP`v|1{;3QUI6Z2~k>mKRZ}fzI*=z5+s&Ay5^t8Z* zL{T)IwK9>If62DEV}^ZY=Khg95;Ls<0^_GDQ9G=S`v4Eg_mw7ns*)-R-DF0=_W+q?8NYO)Cq9ufNRmcM?ACxR zYQ_L$fE0K{RE!;sTtLe78#42>l2dkB4tXPXj(E z;6a83nWbG5;A(&>`^h(7C)#;f7R%a7)AbwgP%6MSC_Ml{Qe9*A*=a1l&oHCe6BDT#>(q zMC8+N%Y<&I$3yQ;VPg-jGR}#1t6z{X^O;@azwbys(OhCc`Y>Hm#63gQVzR*eD&G(; zAj#zRvA~{wT4vgEojB7S$#MLM(T09;B>-Fq5-5MOYJ;x3zA zQ?s}muuWxfXFd_FJBrO(@{nCxSwKWkKv47d(>UUL7NwR}iC>p#ea!*P$S35eqe@aZ|B~ba zo2tbP2g@7{%a7Btz-5UT?CxlLUL(q^kOD}c3I$Y;`hPv@aO=F_BS3jPqGpClK>Fag zpugyTkdZk$jtPwoRg}Wd5GJLSv8lNyZHQK8agFpwf|Yr^a1H>i?lkWg)FBOIm%}RL zbzz36d1O#MQywjpAOu_4oyqH7UsrP16-U#rr!pLYs9-x*f1K%-QCuZ2!I%dD))4`PlSiFSv{JDzcc!>h3Nz@Mx~R!1#G@SnoKpwx}jV?$e&5PA-YQ9WU()l z&By5P_DDhKhy)udL=7)Y4g}OUXotfPN|y=0ggb=0{-)?NiW+pxEz9=0XTM$qUGa=N z-gaE|S6hJO6SB1?U$HWoKf*Zs4*22jRhiPWWDmlg_rHxqCI682i1fN3$tmxDJNiOA zGdxT82sTVVQmE%KI?#1CuVuW&uXJP2dVa$5aFB+HnKPn-6gD`mOMfVT6%>$D0WYco zi^>^2$dd zKt4kXAm5+>Go+Ja*)xP5tNRh`+PiUsz4J;pty(z86pyb;>_MkX(?)pChgSq{WH71< z@?%z}B^+F#*k~a|en<;$3+NN>6ObSHo@M*2^RTboGkS;HV*ELCi;30^fMWYYHCB`Jn_1-(dynfNdo ze)y*}TZ%xdw(!}bT~;M5G$pe)P|rY*q^ZYUO%uGvO`eE$9Z0w%Ls5;&Mw4&b9HUSO zmq$!+4LbZ)Z1oerBWbL@?s%~c6&+_6tTRch{@SK~TX55rT61dCOFKp+-4bM&?3-p* zET=zo-k!-iuHx+RiJ2>|NG`mxuKoyp$vt z^^4e#Ig(Nf(kdH-4S!d~%EAm(&_aUII1@1Hg0QJywkd9*#!{yi{lb033TB@59KzNgYcKv2rj8{(V-WgcM>UkWMT~ zC01k(51#&FhIrX zP`w*89*z!(@lhS0UJ!-wroG~Mzi043h+6e?PHQ*KC#8hK8Uop!9?&NoT_J4oOqbd* znvzq92LxJcZ#Swl9bTJEvn^ML#2!0Y+1-GASj^e-KZ~812=H@Jez6(tPfw55>gkxc++(h5$p1W1VfJxzfh6dU{P) zTHwCLH{74CD?to6f8Q?jcJ_}Dp9{iy6vDOaz8>S0!}7@)4{V_^e;c?ig@>1K>(wRV5ZH#A& z++btY6}cGv>T$S{Oj@4i%)FKSALC_?)h-&o!1if=qv_h3Rs zdSbM#H1-#4p7D)+(-g=3xa5&6Fo)gIZHQ22=|JZb_d!2P4JcGV+r=53C~>`7Vrr^+ zbQ0{tbaKyM&?SBE=VE}4jtS3?z2+ZlbuPR^GUw?;(-`Ne?L=}Rx8M6t2Pc{TOQs!P zA^x#xlom1*$%?q^vJP^brhfHjXnv)a*)FC9wyH494VDlEp@g`$0D-%-Pmx59MgV4{f zod6l(IoJ*!aKzb; z9pMkdQQT~bP52A1fk=p7E{|B=qkeT^QhDhkfm{NwTCdGFwd5#)`H2kflqN8rk%Q}k#fu&o%k%+9)Kf;9;xE2dnI#mtgNHcE36rjZ4 z3JSN#zPmY09$*z@hRHpp;(8x*$|*oE665rDk8k$uMROG^Giw+5}_4xmUKN~&D* z+bw57fo%psF~rNvd`W9Qig^{MjFZCB{!Y&YRU_2_nO>GauxBdi86GXxrl#*YwxLd4 zGPg)E_==uSH%T**>p2I`tI0CdskabwpfJML`$R0l4s!}6kKZvKZ~7mX`6Gp9N$|nY zVLpJqP5CFf7t?&>VN=1>Y50-2{>>ajtL||2+v(jv-6L~d(z9ujSGrFI{o*+M4iJfm z@-~=@%dkW{`v%#N?Bb8jsUX4j)OSdu%n7m!tpCT>Uq)5ky#1+-q8MeG45~fj(MwwIl+4p^W$$=#r)|5!dLK3Iaa}hn9Vq9MX6F_ z7O4lg$1WGg=jXXW{x^HoBr^bl;jLZI#e9+(z5Tud=jOH47#5oA*V&zY-G_zX^L>9$ z@s;9}U-Uy?WDQ4VP`Cal2d>Hj@MawW+jbUvdfWf#)_E`fJh2>)C2JQzsgrYYsbBHC z7z5b+&j2VelO|2iB~s7t>_=io24T_VJuNOf)Z%BZk|Hr(TsW%j^ye=oi#Pi_jytEr z1#v?uS1?l;W<2o>j2J4IN#*wzA=8|DuyaDvXGO_RRyw%wNNSa5Jz(x!!IX_(@?H=!H9q3U9sy^?RS z&DiBnsI!SDq|XQXX6F27o=>q6$zHDlD|B~oXBpcmlMwCCaj@b{s*?eP?6vvU+hqXd zL#zh+u3K6n6Fiqt>)A=KEQSxH9ywtXE{WOrH0Cx93MAp?a2>7VK(K;%+Q5Ss@#`-( zFT+iHR3qxk%-=a+*P?gR-2|(2YWLJtu=uc`ZP1HU#i{Db`=zEJ?lk zyj!@u2aaRtMi4_LKp(eJWQ=b*M`5;w3M&FuiBw5sMhH5#6H7svcv{IB+q|~<&j0o zylnE-S3?R7PL>ozw%nUJA9C(uc^BK^4fQ=W3QX2&uZDx&I%|2cXP z-&EcoEGy6B-+BG|nYqpxY4QsPoEHaK^c&Mrj*ZNyCejy#kZ2c6RXn(=0mA~EFTpOO z{kI#PBx=7St7*J3UUBKS=1DP`826I2FDUXi=aiX2%JLZ=!GK-?OGiCdWhY}MpZ_pP zUsQ_VCI=dG5&1sbfs(-}VsCYZ?@UsRX&JS7f~Yrp>BmE)(%WmSpV}6}GD|Zx?_eo1Vt~O!pVio?ITU=H;33 z8kC>>PycuO-rv1kzSA@1YJV0?<5DI>pY<>W_b9kJUrMsetE+iyT7ebI!jelD@(<$p zLrywL<4>l0NnwN?5?B&>vA4c`ZeqAi`eQ18(h&$|BV3=TNxhu~(5>MqTCjP=-hU>X zL)juX>T7dM4k{p#RbWR!z|JQ*FI0fSnb#5}d&BShdtrf9pn`TPVyl(b$S4$|a^==m z>?Z_MCdu%kx0w702ac?;lg9}MOs{L^vOt}L8?$;omj@B{-X`=`T?@7zm z$s41+U2vk7FlAQ5a3Ib}d>GtY8$byPzgMw9k@{lFgQR1H?_LPWkFN5xveroV)C?;D zA0!0MM@M*TuvC7la{+OOh{DYs@Te^fL-I*>NGKu+G0X}bL3|#?0~xh|~C>4ITUd1d>~DZB$&Q8)#jNMZVGg>q=gOjN6KI?r1;hAFIV(l5?M zY^Z3ohWBZfvEEqu2+68^OUSh*^cK9<8R{QdwC{xq#K#j>1T?L z5y5`!qhoC(&X*JEh7346{hMnhqvoN0$Wq=RT2BPp@{)KAd4r9aLH z+97pE(H8lk;5R%2A6sGxrI^S#QoJVi{8xg5;(B8EP@E7YQ%&>V+=bV|nGyvjPd3e! zkGJR(xfW<7hZ{TQs@|hI^%){eWD_;boGJ9!hLV0_jKaWSKvTC0fP&GzJ-B|{+UJZa z6=UqkN@jtujZt(61jBaGCO-?-GlC3cAgqmXSD6cEZ;iU!6soQQde2T1dm48LCWFCB zIUGxi?&?wX`n(+1`U)DNUUMfWc<)2yW^++cl7V5Dn}my~l`<%xXnC1-<8R+{20m3r8d8%6F3t5H85BaRzcn zj(yY(mv;r9PEL%z-DzZ+2*TN++OpUpz2x(@=7cvMMeQtnE+=-)gta1NZ~C;nMijb& zTk--9fOMCbB^vAEa<2GDK@QJ`D+4GlvE1pyDe0XmUEWNj;)fRUIF=o>39`p-2naht z6cppLp76o&7d>7HA%wUHnP{s{$_JScrz)_|l3ZqR$#iAH74y@pJXc}vkK|%>=4{j6 zy7?DGaiXw^^e(9Rc|o8R^`FUINX@a&*W!&u`1o^XRXlrSyz`aGt^#^e(_srlu6N(; zSh&Z}atoywa?+esR@G-B|CP~iNofl=Ok=Dlvc~8T3s~xTS$IEz+b_Z0F@9j@XkmZE zbVR4A-Amnq=A_PoE>O+(NW)KGqzP%Cc!03R^2?H6aWJ!a%Dxgu`Y|2rQo5y&?Xmav ztaFQWi2uwX-*4&b^Ryq1ou2H7UZG(tX8i1?UG)X&MX>98a;N9}{sEEQT;J-^bbw-9 zs}1w2gFHW6B(A+VNxrhhk5S zw% zGPA4)j*F(`_CFg}?xV6bV2iOJyK8KbP{5rY6kmx?&qNHao0rbM=@{oYqPeV6_6Q5T z--rn*P(mSwM&E;&H_6|ugK9x7;o|z~2^QE;_U>`Qa-{e&@+%}(qgrC8UxG`l`4-#3 zv3jB)A{qEkh2tb!iU?u_ff!mgq>BY9f(g%1UTsdbLwTaPyx#o4jYH$=&tod#u#TdJ zC*zhtfj^b&2lsD(5-?a-VR5K@RCCjIYO=oa-;s+<=DHu7#_D@h%sU^1fLB(k47G%^ zfbjesRt=ZfvbPoyTfhb!_yp|{0dOKMao)pP(~hGo>$u%f58Z^(q_tRV%Ev8n`ZBT0$oQgd;^&dz^MmP#hXM_hE#){ z%h)EP{z0t;1o5Z1No$eIP;S9w=j9&w7c0ezn_;V{dG5Xs%s0 zK{g@&btlS`v>nSi=zK4GDt=iqZXb(Dd>Yr z514761{keQirkMI6~lo-; z$(Arm^!rO<75uZ+B9_s8Y=sM1fl-bFd4cHPtN)JJ96Rp6yySPr1#a{Rokv(ybpYix z*Sn;O?aNK}|1G}K<|pWZ%~w3Z0ezmIs*>>4Cq{sHlI76$6GDZe&ceVDU*H*=%;+78 zG|fK8&dG5PLYyA1C~|ZNBPv1VY_A`l)9Q`rKgH~jXIJMy;)qR~os%>6$s~jl{O;yF z?>p@SAxwg)*)`5oDM|0x31x#fA}QsFqDMk)?A{m**tyqI3ovkr$Nc)F?I6`ufkpws z!a+BH?OUOVA)VkItOzq{S;|ktA46ZeXR?K{-w{Vl4y>QSLzWr16ibq&$4*yaip`^w zo%yiwO!@(yQ|ML4PDRhE#)z5o6{HD<@6 zpDPYEJ&up-od+N7DhHI?<-XabA+A*#`u?0%LTw0%(#-f)*-6vD>()-XQxui|m&IciX}b+Rmw)2P-KKC&5jAfCPn;T%-8 zXS#!x*O>7nRpflp@6Xu`TG;vWFDtLjJkk?)!m6y~{>u|qQc|kus^)fsL>I~lhUnJC zmVl%f&j5A{qS^L4AU|nIa4JnSXV=iyy8Ksr?3eeTFG{zZ4xgz05a(`@v9Q1n;R*dZ z*+z2(Z;?#Aw>l5+F6Sj_Z~F+0+WqOwG(@~PACl|73Id!T_|#-3;j!bxnO*AlzH>h(W@yVi356Q7#)vU`GXegAMKm z-5ND+IDalch4za57=fFhfkaBABQaAaqix}sCW-C_g`6!8AAj(&r=Y+W8;&;VKnB5+ zP%00@)z9oVF>`64V!0c;aa5~?l`ziQdU3oy)~p=d7QZDTWAz%DbbuvcU-b+jo;#zj zxL`qb7f4&wO1#x9DKL$Y<0vKmg2Ib_pbYSrtX@v*0R}sUUX?SmUMPJfCc7+Av|Y3V z-U{+%t&`9l7+qU0SNXV9SWL*~6{J5N2{dWxB@2G1t%lAZowLU^#U+(DM#Q2fFVdXK zT@3$^j8*zlsCTJwHo1W9f#=rZQLyd#qf4)aWaWcUr;p5lf*%d=O`_%>9Gpk@G3M4E z6`hK$W4v7A*PLe$u^3mSDcul?f_4RVbNYlB5kjsFrj#G20wB%xm~{&#EMd%q+^-UyYi0v56JxWI=#$mY1fE{XT;M!5OI?HQ-n zsgd`?*DAETP+HjN=4pUT|YkkQ=-sDEdnf2}VQdQ$xQ+ZgDjRuxT2$s}2M|A+(J# zrs%qmLljH+aqyo#_}&YxH8d@$we_D81WZ@m#E7^*1wFmG);T1FI8qr!^$f?4EcPMh zd*r}XvLob#B_^{LPNsbeVyS*tm!q7;-<4YuU zLWg&xtZBp(nYen^IzoSQ*ys&bnD~Lv!hLIh`&@61`U6F8I|kPDiN!>UEo^8Iks#sc0p6QpK=Z+` zA7O1L$hKYU^p9Tx>Rifps@BGM0gt1uB{cfbPN5dq2zzV$X=*V3eko?vHVDDMSwNub znNxww1W)h+)&Q{>Y>BxYlMRpFN~m#V5K;tHphOcpE@~QLCHS;gJ2P*9NY6psmx4GS z%N*fQWkWo*#{A9PkY^?7hgE3RTu7_U>I_#%sMmGze#c)o)J-Zg45zSC60*-ROxczc z20kF6V`}}|$@qcU?keFQe8(b6zzgh2-exj-x_yyJ1?F?7z}cePsU*qqL9Tq#tR2G z1K$1bDMR*h%6w8&qkggFhmv3IPfI&=-dP9$qv6;(5wBf3p^5Fm@}HFRfHO{AOD5q( zmUQKaPkYAV4CXC!suPuN#`gTZRp(TUNXK8@EB~avtL#E>f_F=qZ@4i1Ty+>WPef+s zwF)4pV!b{)v*n@iOM82TZU`Xj!Mg#4HiJZPP;f8ye2@o=I5FIe3M`HI{u$JY0S-#` zl?m_L9^mRqp&dilKWhIF`>>Ulg=7gV+`5VuE_Z=C#k$|$(*Wd7`*B-EQE~B4rWzQP z(BInNl>ne-@Vol|Nli6*9}8ULG|{lhT!4BT&b`?tTg?nU$K25zp?UPWm6a8W*@IrR zg(i|lmN9R zT9O5Epa8$Li;#qe1-7+mOroQujZ4B)^|?}gHOWdPeC%^!36H}szMUf^Gu!HtXtrgF zI6*eHnmpDgdkPx&ZYcQLQNrH7s;IP7UQ#mH5AgAF+Rjx{6#sW(p?sNG4h{}z@S+x- z<>bD2i<+64RX+5Abk(}q`jyhW>YWefcwG(q3v0Zv@vw$q0RkQTM=|SV)})iR6YG1s zuWkFlcbU|4*?q((`30fGxMBAXd#z*FWf%8#5;vA2Tlxj_fAC22RzvlL?5*x!ERdRa zA_{%sXg3~TJePJNL_4vj+kKBFaXnk!2?vV%KrH6da!+J%3@l@Yc&0-((;HcpZ!m~g zoydmmQ`RM(`YuB@l5$;nJB_#S-)s9R?}_f8v08Y8rWVG_ePY~c?=VBNxN5-&)-7>4 zx!P}_mm#y^gJqxMWWy~v2EB*@WXrMzXYxo#)Ito8Ox{{YxE-gFYp`oxzHZ`9JNL3Y8@ji@!zIMq_;O|4W?FE) zh1KQsEVL&B2Na}I71ASq13b3>3 z_59o1oIKl;X)vG>POfv#mD8qk21UTC0HOt!ynK7eRex>zB~=`&Jx2ZgQc=-R z{gTdMLu@mqS#VG(v%P2Nj`*@27yc2}v3bWpaZ`ndxWSu>hEC6Ro_XulXspLy>mIms zep-QV>bBU4d)Qg+)sm`4t!l|=YEct%ucx|-EYf5=3Kh!*J#Q0&eG=oAgBHgSd!H@UHMIXN^cOQ|m=aH0;WeLO9GM!h zJ6yUJT8Q~)95PdiJuX{krQ<|n4UWpc7v-X_cN6(F=dGjkdp>Uj*>i=#U0$wekkwc2 zcQm=#&J4L3fJ^$WNLF88|JUIEP8qhE=e(B(^9#P`0eB%d>8pohlD^BbtB=%k`AOTH zeglsMF`9=3to7z&QBHOZh%y(_MK^7ggwQWv1o|%k*f*5;kqfo8WLptJNJ?AY`n?i62GHbt5x_$v-2RSWLL_$39@dcs#H78;{Lfr9=tf=uxcv-o z2g|lzRm5F<{>G&hjQrLb3K63b!~GK?7JKRhN`Ut-M?%?`yvI`M_iqgSod^~uTng-F z0g)Q-UPfMdPKu7wuM-n@P4eCc3#!nI(OCn%1;Ly{OdQ}n6qo|H)sLI#j3!OdAlVFn zEk_t68~qlPaL*-miQ(<86t{4j{ApeW|L8l>SQhVOzyMp~%qs?5(EH+m6)AFjY7Cp}1zyLSK(v29;eMpSiR1=GxY9D{Y zM+MC)to-N`sF%ASc^R>5uzooq&fEk-CD=BDK3d+nl1|IlH3b=fsH{y%k8(_7)04azU|CLHQ{$^yB7U6rP=+hhW=_J;S*wjN5?Kok?$qkfN-9)th!BBe+Jn zj_5>;8r=+*44^zhjAJ$?&K|x{wQe7E>E4a~TJ={-6m=(KZYZ3!DBJQ6rR;P9%yqv; zk%K=SYEHzkrmf60BZ*?W=NP_CYD;{rs@b(t%~Sm4Z$pu*hVRcOvE`?Nkx~Jj7X8l( zB%dsE)i2)~=ol|>Q^eR7@DZjZ;pk-WX@qkle*;-UX$Mdk`sugApdX`|^2)2k6ha8X zg2I)cGE zO!fAv=kQA#Fq&233zYsgqKE7-L^W>1r^A18xq*;Uiz&C2>^W+qx z9x8M9Q^;Zp_uv|V`$!KJ&HRO_%%zk;_w9lSL{k}ZxIwv7ziAP8qjTZfFOcabbQo@x zzR$Q;g6OVTKx~L{c&=15+tRti{j%%puJ$F*wjBkciBbpeIt&R(<%v z>&g#wd%dKNTm}d&WdZ^^SNJzI1ORkl4fm3S@;mf?Y`+k(SMX`4oUBP?TW_~s2NO!N zE0BMFhb{&)zMMq&u1*Mp-LWx8{o@G0Fo_S(ZLgI~Tb&*A9-=r9ZzcF+0Y;v`#bXHS zQ7izVp!*;*qY%1HBJoQt5QlN+(pVsvDjeQ;9mmt&fJRTLdb!?Rg1#z+Oz($>4tx|n zr@%M@IjpNo`j;Vx`Rx5hQ0dk}k^t$nV4a4E#~P#C^-hjYb9-G)1~!JzO(Qn~*j9bn zN}o77zVZPL0o4~Uu5CvTpVy8NZ2B;A_C(%dERaQC?cI1AGt@hTqm3PM@LTXYk!Ds2 zMYYP%JOQ4D$6wy|rWuP)rf4O`-1TxFRS z>~;JzuPvUQBED_1r15PGXW*iX?6k;H>b!DgvDF8^@4ZqdYGbR?)bLv4npOR-=#1eSn zldJ$GV~J^LmizyG@U*?$()WO`%k25_Ce4cbU7EfJ@L2S`n$?uIScbGdbp}RV?z7!l zm+veF{fd2^{WXlsfQMi~;VqDwe3KqoY~u%?ijt#C(#;40N~lbU(-Gfq`r>iW8+M}% za5}-i9+&bNwG<_!A(AMKDG zfS|xH&$T5Oveuy+gua(Jxy^k-l7OQdA~#*?E_{l+r{D8#+L3;C=5XIn(b(N#pfts2 zlwa+E7_|^X->*&5yQiGU1wZjfBkDW4u&a)+Rk)tMv1+ke+*O6$o>9!+t55n6FT$4V zc2bgVm12@RGzk5s8{0_YnL4l>3jGiAoy>&|R9Q(9&nyi%$q8@{td0GAVq6Ep0xbN} zqZ)HMk>NPV)003N=SHKa5@t_aaTs)mLu#0-A4k0hvMx#By`k#S9Fj;dNlFM@HCP-2 z-9|g&>^sM#Eu|gY%4W(yiz}P!*jNxkmhTKL*}E##tjWyo$dL`&+z*+>a< znMAtEcDJV+=YWrPp$X_((>iWDWMyPvsCBI&kNN|aiY2j@N2HJtkAs}cEWh8lDJoYh z&7@y>;nxVAz#2YjYK{PqJl180_9_U#@!%aegpd4>qf>DN@O&3xi9V>ririaiH``^b z0PQsAigPDD9OCQ01jh_Vo{GDJhXN}XdQII4T%O!c%%mWMFr@?Ci>LtSr-E~v|iubUr989 zr~pbGz}IpxZ?a3wvW_>FRjev@o+ffEp}Bzj3XxblbuzW5$16Y{<}d4M(=ajq>~%xH zJnaK#3Dso&3N#~(O{oP+0QEyqp8F`o-(Yhuiq}MztBRRelMH%dzd`W^r5em6aT3bZ z-(F=0b(ql$u+a_El3-eer>PEd&%JiN8P`8AhY0K&rb@eB&QP*x$xux)q6hV*(&3&x zp~ekGi9%i%>2t`(s@;uE*|dt3UkEXPm{podpWFSN5Vgx@{teat zEYH^`k`O6x>DO`-|0a3+Cl6s+VTOS@D*;#PiJ6)2f^Qa; zJMS({8Ch6T05wNjNpPPg@;y~**MH^+YA1Su7&jSBx~U*}<=AY!-Iw_%mBeKiCKBZ{q? zg}R>`t`4EOzC*J@2DL8CXNkJ?U;`KGToM{@Qq|xFbrYp911Z?-=RP3ACo3Y`HC4fS z%#TYEY^!I^y7{5C`I4ml0U+eUY6Iwi`8Qc6C|JI+Dto^70`)9~U|qiWT}xF-YoLY4+W^{oDYd2<+r4m36vQ zWC24P!uNt#F;G>dD$R2agLL2#gabA>dcupzzNu<8`iqF-j>b?3_ygulduQoWva)Q* zkt+FAdw|EG8r9SUV6u9_J?`>Od}UB zyWwQv;`({iFVqCFIeDnRS&R2{Y!^=?CN_%-#!9*~^rMO@QEbxJ07uv%0onBb&)3!T zi~KwFLN6O6ag8R7sWc8rc$(97{8^%lnLH1~Flm@{IcFC7g5iR3segOxwID8@)fzRY zgGmT7BT#Y4i1|^_RcrDL$F8g-6~(zP)u7qnH;)LsAk1`f5V06#cddZWpUJu@UY0c& z$TCok@_R0qz-@{36+t|$wBFh@4408Se}oRJ**e(1c7qqoC`NRL@s>$$$o<_R+8lBA zUVN^N82kwZl+zXl_5n#&#sC{5_f9N6PNUVd{)5X!r`*)PUWA`bVRDNPL5lodN+=iu zw#nBYE=4>#5o*_)`gbU|6=mE$y2o6Z8%t#Zf;z92r1sx1`3N5K@fsImp4x!T2dmM1 zUb6fmWW2fp1mmIYLD!M$5>Q5n)h8(fzfOgK3-v?3Pm`9Wgg!@#iHn|U!2*|rS2S1> z)nH!8LPR68QO$RTx)_6gXE1{7x*^EUr07WdM z=DU(?os*-7Qn7wcqrMo!K*X6*n$`}ye-EVO_!4pJr%vQdoKI3N2eQdW%=R4$x; zIYhHvHHf>fS?LH+eU_!Wt^cDmRbC%ectTMw9{U{^b9VpvvL;&F$~BrVA&h`9Vkx#$S=sZuqGVUr(mx|5$`d zUm{{ucsS43%Z~rALkMwES>O-uG7lERcVPLD9s~d(zEd>KJ5m~fR7}RUR4(3qF?%l6 z49(*$F37@2Fuf$e2jSlH8K1@;5WMpBy5I; zZf!G~AF5VVGDu&U{Tr!Hdh5^EpkfcxwC7WQWYx1w=q#FG;47|{qKkn^b_QM#5_{5= zTFRW5Dy9DIz)bArZAFqfYbgYpt)O{h@3nS+RSE2Y-l(9j4~(~rDoboIMoqd?>?j;9 zJN2OtFbHt;fCz==;i5nq0BvnD@eoQgka~`~h#+`|@QW38DpAALPm~eTKK;C{Omxtb zu0p^2Gb?|0Tqxdo=cjeWMbAz&+3sPsaj8MK-F!56Rada%rLeu?RBuC5hif5^pylQ2 zx&X6w+b5vTLMs*a_=Q_TQ`=vqqS0;NZz(jf?U5C4M`;;qd8tm^@!en-&Q(6k_^u9& za*=$`86M;`ljm&OKmsLm|6_1&Dzce?-d|J=Z7a^?n{Ye%i(bJu!Ofn!Ytz$lm*VriE1SWGXslJMD8TX9(q>Wov+~t$$ACNJ zoL}maF+a4fl#L{+dP5~Ta{1K$db{{2;2`I4xZ;=n~xqH3_@ zs6Fi8RHBad^OR;ZyuV;W{qQ~Xx8uID1bfhXHzoreug0_JUwPdcxdPQ&A7%8*smV-c z0KDUSyQ)X|KqBnf^PlKOQqNQLjY;voQ}KM=aU5T(yJ2rg9U(&m^ts2Mssd34hJx?8 zG<$hit0tPBgG^?EcfVXQ@?-?@8);R=l0TwYnRoDtm@bW@+mFCb=toHB4X6z}FH#Rx z)W664``LsQoeFdKJ=Pc3#FfD{ig6$%^!mzNWGfOVdf~eu!B-4Ku?1^S%)}F)%a<3s`$5v#cfujiUj=GBp7?WX(sh(K#oDjFEe*bIZPEC|?@;JI`KhUHe#^0xmC(urTjd|Q*ay-w>VhVwZ-t!K2P50lySZ~rq8c?ho@v6Yq^xL(RJ^6& z1g~L^L9p%U+UCt#GMgje6E$1A$MRo>;PDofFD~bm!d_WmAf!&YzQWBny>sbV{BaSc zm>NU@dxc7gSp6$d43aCfG%d{Z``DbsJIrff`ie{X0%;gLSw`)>=`GzZE1yy6`|~31 zJMGbLPNZ5}}tK`#RWquv(I*6Y4(H?ML~ z+$r6LK{o+X(W;5DhPG^EDrOBC1G4cvX-H@7Ne8*4ty_8+9@gSPJ`UD^?8&Bo*pnud0SFrm{Ba8}_#5 z)TDQB*Wes!5~K}s1L4DrKqR1dP{Lf^^q(FIo;=F8(LUnGV!9>u@I zUt2WfT%ujR4Sz)PL)m@n3MF-F#l$US(+ZEd0~f)UaYz*zgC8FvbWPDGq~`4VBxBCZ z9^%o^W(7(vUK=G;xFSyQ+~c26<86ocf(K4HsS%QzH#nsA)2S~injR2x;!+(yZ`08J zbYY3RLnVNZ*bqQ^Z=zI7%waxOS;?E<56k)Z(cB!A1L}!c!t7-T>Pr4epj;6lSDGo8 z;WdcCdD3@N`DANzI6a=yGnhjoo9UP^htDwJip0R2%b`ftz72=wkCBp^z$nQI(?TM5 zZfqP;;4}IV!9bQHMshI1CEk8pN-MdHg1JDrQXB?UqjM8}%H~@9p3U+@TmR z`lSNT6ZlQ{clK-y$G7MY<$u(XP@zPk$bg~IMJxem`K3MFX-K8M!|)2!UM%$$x!4`?~P=h7s-~*lJP|-m}0`zAP{%P)kaY zfH=F#a03Z_Cg_1c2sf7c73E%lGAT>cS4H?nf1kgsX^w%p-Xb5B?~#Yz>+UO~$<93F zJv}*l-!4lBx6jr1`;gPMyNNC=<$ZO9YW}i}!ylQkOhaVM)X4I$FFNhkTgHWQP$D>I zTzfW;lMnbByN}*eXbxhcj39xUt)V49MqbsFTMO3Qo0aN5V_TqTO-lxQ74W^iXmwNy z8;u$;ldaV7+4n144T<8s?xw;gS{R0s8>Q}oYmtmh9|hJ80qG}~^!ShO4*3-)R+G`F zc2~?fI1tlh<5#)+FUVPQlvVqb8|EU(^hr?5b`Sjo@&v_QeJ*LAeydw#w*ON3`Mo@w z_S2b(a4koiDCNK7rqU~%$Ik=G4;o=Peu;i(ce@_3_m}(B-`4`d{}x+=r5Y)-OGj<1 zTN^}UZ_hRXVKn|@q12*JmKDIQYG8i`tPaY8p2rXEL6%)1cx(pD^ZK4SEY={utu>T; zc=j8h&~+H7PY+K1j}}V&?!{7)>$QoBrmhbtq0s~!5@bGmly{p^Y-WSMZ{iQ7;!;K% zBYF_f6)v{RzYrF6_k~_XpT0MZp}`x(>O%);9<+GI$W~wwKhhMojTApU2yFEOGg+Sn zSB+WERqT+t+}@6Tq8Vt4)Q~<#HUP2cl-B3sKsx+32hd=cEJd($Pr-~q^#p{yRZLD^UVxG zJT3*XuyPeDgF~0Bv^UzEFDbh}|0Y1KK?57M&Bd_`9G~Q7u)2N?>Eb2oF05(IduWx? zudq!Uwyw#syW^7%T)sS+5)SkgI?jBZ0F-K0eZOEuFq)Erq3j<@i-`W5;wkD3a+35T_XBVbn)cDAQoK;122G0EZOC$DMRA-4VS92jZKp zsvjiVBFA-C-RWpcSSx7xrglPyE0*GZ@wgYMofhL<-%oSlOX}tbT%!-YLR+s6NJ5IW z2C^+tyA^UrKkhJl??o-`keQ6PQhP@8@2YpQ@_*9Pvm zS~NBts}kSy$6HOUymgkFec-Wu22k%Db6v{I%f)T}b75j6yr_IFXvGiXbIEa1H=-E4#0MdJrI5=uPs$u9 zk#8AClv3ndT6{>EB|YgRA7(11yw9CU=5uTa3F+6fo<5^Ob7lVJ;ijP6#M1T7c&-nAg8z2E%T@L6cS#(?xDX_fT4$wP~wbS&z9u(g=(eY%S5()C^oS`nVQ zW8^;=MV6=Uj1CCYy7o?Vv=noWco@E zzA|(R_seC0CIdw@_0Cn>d%{CFqb_L{ty(c9p`*qo2?0nBCgfD?4mcOK%S&@#RSSZ* z7DBzJ75OlL4?(Er%1{FJpG0}q1c0swokmOgW`Sioup?F@nvon0duy5&?Lvnm4Oh$MOOnUHNuwj6G z8)*%s{ue4Euo89Z0BXy^ zz3$HNk*5xoy&m5K?&6cK zXM-@nl$19Z`n6h_<@G=v?-I|v-n1P7{uc~FhxQ}h<*)EQn{2rXbbw`6?xu6~RT zuo0S_Z~t`JPLS4Nuyt^7`2U_oUi{8efzSU81PmsgYG8{Bq-02 zXp-Mfun+%`$DBp<-VFUfUY7y)XR>A{%9MiMePAnoyJ+hlw$lDQQgij~9-fe6EFHT4 zh=_M()@L}o&TcyNv0t?;u?famn3P3>F9uI_n{T#A5Fk&=mIar*`gn0?8h|D}$BTs`{a77MrVs?|1^%CudP zHGp*X#x!O*jl!J}&?}$*46eQ$aVXaH2vj%$2 zZJZ6nIIye1K-RJ$`Iah?ozVV+LDJkVzqt5An~b#B;-J+{(8xlP2g_( zszx^A`#jM9y71MAq~O5|o)>XzVdb-v#@tp>-X`Mqwot&s0`|x2KWT;z#Pqd?SDJ?Y zZ~ZQ&w*xSp;I33U}GZMdKOvWb;4^|*>bSgOs?4E|Fxl~` zgK+O2RSe7zJL>{Sv*6cR!tqyOR!v7=1e(4M&lUE4%KmDN|7kv5nvn9FYa`6czpx5} zS9e5DL)UiI->YZ#o3rfRL4CJt+|>#S?T3(t)IEWM+7Rb@Fyg-amBW;zBD4|Dx4%>%gsaDRtw3(prkC)(IDC&xpV<@1__KR1+I z_07Oe_K_FPm){h+&nAd@D}D zBtT1(sL;Y=Ra3Ji6|RBdUj`j*Z9=`fIxWi+;Ax)rh$Sdy14BF>g5Hy_?HacVH82pjM)k($oI; zT~oRBb--pgc(tmy$w3X9cVOf9hgBH8_xJVI5uvo3Hz&laF<$)AS3GKqjPy%&8m9>G4;qTwXQ>e#kh(KooDWqsVNkovIrS!jY++7Kvw4EH~KE)fr2Qtp&w*PYFo9z7-mU$is@K` znegeN)ATq0)c?cQTZKg#_FdmIbR!_$Afa?iBS@#9ba$t~(1WDXA>G~GE#2LXba&Tx z`Mlrz-1o+N?r^X%8*|JR=lNf2{T6KA8AX?R&&PKuv4=4-3`YcGye{rEoV8}ANfk@R z(xJ{9%bMnp97^s_9m!$NOY|XO)Mx#hIDVY`iRcvABTBieo`2s<(la|}jwWwafyGM+ zTS;rv5Ke#C>!9+_Jnms03~;%O6bMhK$mqZxJD4J5z76dBN0p93DC)_6+|fu9;l+(2BLXff}TYwH1B5o)=@Dzacr~PetJ-8;+k={aF{cJo$IWqiy9Zor$KM!f^AG&=#V)c+1}M z!~shATzAMF#}J9j-dwDhLx0_mp_zu~(o{W`&U*yZY>hn` zg~_^nq8)?rq60@tjd^Ynxq-)lLWttJC}UK$UH%r+g^fg4qC*pydkdJ;qQ{dam6P@Z z$Ks{MY1a^6$7%WcpNKm$|=t({%={lA(i+Px{$Uf&IT>x_~et=FvL^aiuAS|y)G`U^R`rNqFPtP zV^fv455I0{y=2@~J#sMjRAzIZ%1V?kR8)=xM;@S43;!8kJHMVM837Ge)DlvM+&0tn#qo)_Gj+(IjdX~Ve!rm<%;<;dH@zZVd+@;q zXAYQs1bz^6keQU9D}ls2Rut+KkHx}I!MB=KL`w^n?_gTbZa@j(aaL8fJhlX<=olLv zZf^IENHhFtc*_nL)aK%e;5pJjmolOlIir>Z)^}{*3sEaV9}I@8M@ek{Wb}a$LYayX zG8)n8h9PqTpm5DtFJ(mvgyx{XUtl~tgAqxh@UJO2OhBamYRcEWd1Fq zMJ3!6zHI0s_Q_)J5;xEmC|DkX&laVW84`8sq<-Nq6NG9{4fZeSOjfyai9n+ib;qnOq4uGgBXR=q5k(9rV%?LoPv+%BEa{(^|==G;_8w-xv0)MrYHn1f38g z-oxc~1Pj`@?$*{nxga%Mg~d*koCZf>>i=%+n}=zf_xE=PS6bHCLgWMV zhZYO&IWR3ypZhOsYw~oRraWqf)zaNGCA96!J~PaYaJyRiOfoAyT^2rcxh%Od!!Wo+XA=3rpxp!vkMpMl4*m4%#o@55M zQ^Gko1qVfORe(Q~a*S25y9G9I>UG#>SGqT4tl}2+l(9FuZFJ^5`vo!*?HVX#HM}4p z-~Rn-g?;m$uB6SX=$mGfwey1Wq)CvDu|q`+yW7QT!FZkIFT8$y9$n_#HAR$@@pIX+ z$Q9cbl`O9Z+4#`lHlF3ckHdZT80>3=JJ_XTH50dkX4#VPt|4eb&jN&yUt;|Z43?-q<0##wKi$MNW5Nt;2 zQKRYYt}*G-&4g*o!Lm%Nn7(bw88of-iL^ssH7o3H&Ea zzZ2L}5C*hBz~{&`9lUZe|LGK9sMKC(AsHF*b$d*5($Fd<@VzwfqO@ARkucb^sb=oU zXCo&T>?7!_KyS_X3t!O@EG_~Xq$2G#XL#O95nwa4aBbxVA&K&z(ZVJv>6(8I;{OeU zh$X>B;p@R>4raUpiNJwBoqf!dyU0vimTnWl%Rqkvqex7FS^@eflAQMRB78C4EyPwAej|qS+|2GS0J}(N1T+aOfv)ev6uW_^(;3JxOVtp&ZT`BnJu_)8r7HynP%Y z55>GSw`|U@Y8Hde46oCuG|ur}Ii=w|>pz>cge?dc7JWvihHR>^MXh!M{5HZCZ$~$= zq=M&g4YsF!-6C97zb^Un(DUO>A%9Yskd-IV(!3n-3m*2%T+ zE_8L_D#5eDl~935Tfv;hW?Ljo@q93=3jhxscPNiVoF-&@b}DFKm%PPnZf^SIk(?s_ z_0m>)aM(pyp#+4`m_P!;Tkhne}J3g1zOM5x~`c#9PL^iIdC535iMn-jOOXa^B&;mOJ8N(_Y zyjv&aDIa{M7t!p+R-9F*-gp=-P87=Xf%=DXtU_|?-SV$V98NSYwl5WBfjk!wf*Xpa zk+l{S6@^q+SC^9gXV;`V68~?i1WcfS{B6Hcgdi;dZR3vMosHz%%kUd6=o}ZNJVNOj zW9?vDPoSq68LR% zU02!Pn_b*YBWlyiBVpEE#d4cARM)+Ao7@!<<{s{N3})Mp`fa)@)A1u|PmSHi;4;I| zaWQU^`PB|Xd7u2*x1NULeYNtV+xM`XIK-dHN+t$BJZoiBIk#vN`eNPS4?a%N)wGt9 z!G;#F=;{S~8#2Qrk$7Um;tW#~8?_Qb{PJR2$E2rcJf*Tt8jcNE!^hbbh+C z+nqCZD;Ar%G=Vi&@l&U$5M0fPy+qwR<=pZ?!JrusRm!}2^+`>bQ@KlTBRB}?>t+s2DlFkw+fWo-X5q{Sq~Z$Uf*ugG<6H!!fU-qW3=C63`{ua zlf=}@?O>lW@8CHlx=^-6?knz4f}GsNr}dfBqCt*39m>x+axJlm;%kiM73fY4_;yA+ zrQSB1M4hs|@nN2WP&d67wN+AwR?hAs^p5jWWMb{7$FZOD)I}Ej$H9(LewlK_$Ywo}E1%IdLTxe>2v86{uD7V8JAzP- zQ*|^-^sI!ucUx@n0IB58<*u2J8g1X9=Sp(g*mARHPaMMQNH z6iw)}gX#4<(+R^)P_#`e|6@4=1bTGsMRC<*}?uu4rz4Tt6GE)z4eMMguSC zjzYOw<9o00%DT2_=?3LX3;L!s5%4K+qv+T^21}rVx%1KMlQ2vWax-THo4n-Rjdm&V z=Cn=(pAnXBsrf+oTB?=kaKij+-HMAAfGv>B@rq|=ciEwG^O#`g*kU_kT?83-kX%Z95lcKI za3H8BXh#_R3MD{u5CKza5S(-%cDu_1e~QQ~;W&;#`Vgl#X;Ntf(9vc(>BW3rdx-^t zDuUTUWQ;h2ZWtJ>ND7u{Ymp4mu(P+dLdc`m>VKMC3r#bW)2&NU(;?&LF~c3*B6MPY z_79|rFsm#zsPhtO{t)c&zS|+r^0Ixb%fL+`C_aA+4A!D0|1hfJDdOZQ-OC@s1=Hj&WbS6 z*AX(#Z+Daxw6n)%i>F5%SJqT!;7PkLWqfbBihv0iuD8j7jx+9ufsRR+UVq^^Vt`BrCpBOB z(wM#T{$+K|uZB-f9tS8j%p3r+9&{u=EuMg3$R!+TPy6t%&g!V;a&&ThoPsBUfHGd! z)8Xv+1F8MGuj6Td)MTcY2S4VeG4oj{1qH5?Z!L17>##$Hb+%B@l_1R3Sq_^bq_<(v zBf#jyAT2u3jMDsvpkgTUDL9Q|2X_q3q&n{%lu$nc@!dWouMn|stF(T;HRV#^LSf@0 zT;=dLf$o>f`E1ADbFu5eMJ~%>F~|P3@QPhjb8!zs*Oq6f&u~)s!)Vj)8s^|WUD~>> zvdwaPyTH}_X4RK+T~!uDv%?z9b7NWV4hdb=`t4lDn?$qz>Q^_$2Cc2a-SqfB9>+G% z!>y3!FHWm;E!l*q#Ng*GjSb!{!kmbG*M~SxjF(2U_}9J6@ukFRxT^r^sDHtP^0eFIGCe4pQs%F^;i+o1_i zJ+``W6l?B-XMbaW4I!?ei`U>LKyF9>P%3+cYLT=ke-%h<%PNBVYo#RppO$`XEh91k z*wvRWkevVV#o1xo5y9*8QI9}MrFI*=faNeU4S0h5!(kGq{8y=~WgE%JnI%>ybZ~4e z9zcBXBlc#FH;6(kD?t3?#Q<*2Iwi({jB@2llU$HC6laW8G#80~+r2>oC-dtv>YGiX z4U1*jJ%)|2oYSmy5cgy?8UFSLyjWXK&lEg?R09=7*mXEaP426}-r3P#l8m4}vNz$v zqIXha3rKN+Jm_ifVteS^{u08zb+W)l>j>zpS%4;{;q0J5x)|t$TET++F01^WW4J>1 zqh5#I4oE9^J_m%I5nKi&e+RS7EBP$~QP`Kt{T=rDcwcUarVXkA@e**~6@W`7U@`~tXOqwjUqCjr#iaQV~V=eTRkDM(POGMrC^-HynvOOJlmCKORif?Azpq_5B*==le0A zxav_phL2h_c$ah}mq0f#a@iBxS1ql_Z1Q(5%MOyLJYj0{-l9@;3MuqM@htW2(lN9H z0raj^=?jZMIa}d>3kI3!m>K5 zR7fX1bmoRNFv8<*G|&->BhptPnN2gwx12?*<>L7Er1eEzonEJ@gbV>AR;&8;KVPsV zDefPO)Bkg+g;K4}lIq~#;17=SHD!2>5m?8P`kVGFbQCQnP2otf67+gX%b&WAP^y;3 zS-8*U$u@PBXZ_AUYiZ6i0A+jX2Sc%c-z-!8vf<&#b2;+a&4eU*Dca16K@jOb$@5Qr zu~j|5dU!L#CHQM!u?54|*=Dh(vi;@xaVQvz+IxD=I`G`}Sn>g9zDJLqTOAba5a!GX zHnRR0HB+`?X@U*IZ?i$A@m0s@(0a6_piW15SEAVD?*&SthK7xmgLiF>HtpU$9Zl{< zZ)fhsTJ-kC(=xW3=IbhpF7w#IuHO`XzfpC_*3Ic||MA*>y0i*z3N9Qz|*VUH=!w{yU<-_`KD#Vm;U>*)KBjC)0b?Dk$ysJS32KoP^WIkFf z?iNzY2WDsO#5unhY;yNs+H}YGaralB_(%)%S}{xC{ma>qd6a1CvA!kKirA}OEzF<* zF!DD2w3r#R-YXknKX_CdW~sySXNbY^{6HWNm`rcr&{twTHN;~Nb zquH{3bq@a9MTLqI18M$++~2olHcHv(#wy9;-?(P+S<8P_DZ4#34VgUf+rjbfC#*p7 zOXdx=mU@2IZI1NraBoTaR50&k6(!gRbv>k5TZ^S%O1@U{qEmO|an&j0rOk2g5x{R} zKLziU-k+0N`9vdnEz$^5=>S~iW*1)7cH}i57EEpL$`;@i!SMR5-!~IP?yU~QM}+zR zOH{N>18!&os;8eis^maL?r(%|5oCf}*K>ODfEc{kIA>RW{f8ZjyMFLmtcTODa}GrR z{$BC;RXZ~*Tl`K${tVj7cyr(nH5M9HiQq>9hz}JT6%|I|4%H>8sz1>*T(xx$ zC>h%$^=na65dzv-R@SQatJge(!lQzcK<^2WeWoq02-P#jdae3pzno08K&ub~QB1&8 z{-C^BDl<;6*FJmj)cbgy_mAmUuF_LYQ$a(P2S=%s@2L$l!>^=G9i!i>HLt|(7XycC zT9zwkHyxy+`2fO#deJ2%x}S?N?-!*WX!G=PEIhD{W|ZHS#tr@zSN@_(YeLhboY^OS zxhuQbHA;7f(M1S47&FTxipZMOKCF30 z9mys3rF{Tca<lNC>lPNw(ih?nfc9#|DY4zptq zlIa{6(*dOA`BqB{IYEuAjhvR-b#^oKr>ovEj6TP_445XSri1YK+WP$6y>{4t|M#xn zuJr~E^_|@?JD^7XlLn*h(V~?m=NKR$FXFP|tj2%)aNHwyKUu?rZU_V*HIdiL7B@U$ zKYL=%|0$3lSlJjYC82&H?-JykYz(Et=mZI0hoNpA{>|fwn$LPRbv(4?0otAkMVK;B z0NqKM0eIY5A@K9BG5?&=&|H7ZNhN-om~Yc?;3sP$J@epd)Z%%zGAWqf(RpbuxqJ0> zDB`+g-WeZ)^P_@A5^vxM(}yIwk@>ozuJt>kRJA7F6S9QbjX2op=8tP+>=00 zg|VLwl0A3*2UD9|A6diNIx$wGPedR|KW{K3vwR>%$Y>Z3z`fL6t7XN`%@RWm=ky1E zTHHe;Ep6xkN~K1g1;J{{ma!F&Tde|o8!y3TZ(`&6Buhz=L-SjewO=xcF0ZM|7n3Tg zb~O`NeX=){VmZ#Laob={2C0a>Cn?qlra{C#HZ=$bLB_Oac1-Wk(NdtS&cJ~cMxBgo ze45#dm~nC{&8JiN8&+RKpW`zpj^8%E@i&{%cEDSQga?6@z z_?tf&I++gsS|pNA;E_E5o^y4yw9eIeveav@D1)np4DZR?QTT4!?=%ON+!QU!jkL;~ z*oZ=;ugzY6laqNV4Vo&TDwis+(k4sC1Frm4j}wN4<3(csql{Y^$gZlYY<iu%<+|$eK>&wwq_~Cmz-aezbmi_Yutua znxcF?5WFuO^}z6{7Z|~*7)Y_kmyXL#s?+VODIHBsP*CXQ^`xsv=Ij%&+bEm4bSA6Z z8980t=-Td*?33a|nt<=DtXu8D*K3aB9@`YbcxE=^FE-2WHu zEiP-a+&0`eN|WqA0RFeyWs>js$t74Z`}VBskN?acJTiF^5~2IFS18+--ydyDedGw* zUA6$(psu*%N7-%3oqxtG|JzaPvAGjwzr?87i;*JTWYJKW6++UkDza$ z_o40}5r$I4>#VXA*r@__Y3I`1QbrHiL76qj#4_=H-ezf|MSWO|4vIy2;Yr$-KT7#m z!AyK(*9u&P%6A2IjZb}>wcNj5u%$;6=ueW1b&a`A?Kne}#MvT7X(|+e51<>i4 z0xai6Ycd^%z=hy`0`Bl{v6i{FQQmFHW7S{|-q{@_OOlanw7y&NNXxDbdvaDGEy(h=!R|;5 zb7-Is(^;<|oc9IN_&CZ>!^Jd`w!!HYH;`V#96INw#2yX-+M?D4Jli89G20|tJj^5b zY4Lf?I!DN~i@xnA22tM8ja-fiG4zpmT@9}2X+)ewieW?n<(AHV+!g<66|md~Hv0iT zH(r365UVpLq8?{YxKu8!|YrwI$oL@nkSzwiwt*Y#HBVdO_4u2WS*Rukbi@ogyI+bNrEKk;{F zwQax%@(zg&Ldk^p70v`cU%0EK+T&?0aS53*&IQ!x0lr;pf4Yf-HAA z!F{z}RvwxOD7jV5cJ2Yk+tS!emKLerP$I(ECYb=8=D~zYBNMvDj4JoNx9m@ft`lj*p5S%OiLArMO1Iie=Kl ztE1Wb0HbFxWwPg8(Ey&PCrfNMkP>oQD zQEW-X8(@*3r-9Q@CRNZ*uqLJ42!H-W(63U7W<*yCxEZ(W;94AIgTmVpit_n>fGB{S zp^;ZC(5O&C@&|UVrlB*p}%sB5d3!Fln;+J!C<-a7IrOE30Eq_-(wG;9Ed zn(5cC$*#DdXzzUMNe8s~jTjwD{&!5V2Si+ZF`Ba8s&=xlXodpk7vOW;oZO_KbW?-p z;blsJSeL1KXhBXD?#1d^BevGx9VwN;QN=i&a{AaZ9rhB;eM$kGbK`F6aCWfPu+zia z4wP;f$QNekZvN==yyH-=aXbe!z~Sa`AO5n71NPSt4!HC=r(o5bU7_c=@*W z*Y#NZ>9(~qs_f?D6a#~URaU^3>>s|iA0W!;?`F=ABitc`X1`>5%Tn-|48G+(s_5EU zvReUU!Mz7yiu7dOH?mqG^rMu4b>JWJNUU;(roz+0tLW+m$ zjHK&jw&}Pm7JD}XolO}`_(Lp^*B^30h3B$pz8)lGz{Jrh+Sp!`w+bWx6!&OELb+k0 zq+m0$ZLS#XV{6B4A*be6J}QgZyOfS{uh}I&aaL;+@ze3}55Cq3cUNRq{ubX#ea>KD zVc2&_PDah_XIH?_~Y#7SnZpvEM#mDGXtu^9 ziHOcL-Ol_caVPIOL-9!c^@m~WER~C{;ASWXV3SuZl@EeSfD(c0Ldv#rJ8s?b(%;P1 z#ih>XgNnMk`CQZYeJc1r3KdWK9enYnKX@aPk}QdltqY(I|56a103+H3qlB2(G3S^M z{qs|P))=st#hTYdIGPUX>a#ocm6@n+;)Ryo*F7iw5e@E;17n6H}<6$lUa_l)HNq;R0g1 zm#;vpej$-98)~UB&u9HN>j4#ljM4&iNMmpf8{(fD=mJy!6n#d_g1XKp$}!$an?nuZ z9C0Cit`OLBatWF@sA6yE{Q!(UP*(@T7=>x_1w(>bA06|3sB{OBNYHi78Euzr*i$2h zd9scM&9hT=3CRb)a}+3;(VzxfcaV4WOHIJxbkK#bbS$zqoa4sK=X-*ZBLwL*#?|l* znKltN5iDnYw(kO`cg+5BkaAw7oieN>nb)c^5;D)&05cMFic^;)o(TG9`PD0cE4w(s z{SaEAZkuts&m&4)T#E)RJhZT>K@UdN5hr-@>pe2)lmD5js7S`z{XkDLXD>IG3+cbM z`sckLh^CsYv(o(kwTgPha`d^sJt5nG@DNjJ)Q6z<8K{M&j}U%o0FLyCj(>mBA*iV# zpO!Jz&5Qo)-riqpZ~s#d(23LGX1Tu(&%MbSOXg9Oh#;emk}5iCe|?#3R@D31Q*`VF z(IbhZhP$1o6gx`T{hf#w3ImD4@1vA*O=kB$?BP1_$o|u|>jo$1gvJOve@V8HDy{<& zy2J7_OIopc?{_Pk*j9ehe1Uzx{|V~2EWHQyE%tA!tbk3ZSd z_ZWhE30S;_a^SyTQiGrv>GG@bDnrGLv4rIYEqdqJ+o|FOT&HTQ0sbeh3Qok1a_>WA zB1$+dw42n08a@1n-4D6cz~4-pJsUUlvbV0<$=+(8|A(AzDFc}PlvaFRpB(|D@zOtP zF^NMr7W>nvhw)ZufMv(bK)mb_8fzk5B2g-&Xr!nhE^UD@IxjF)D_ag-nd=3l2Bk&g zi$w49KQXX&`QrDc3r8d%9zj=SD>?OVsM_#0cj0@}P)AGz=Drn}<+2d7ND_SCBTW0}GJc5S-G6^AGht zw7b4+Ux%cu*}6-F@6L$+3r*G!(n)+?Kh8|WVt?+ES?oyqB0s;5&d< ziaD-Z)2&-@x3XAkYZbD>=%fZ=MIgQ2fo_mt5%3(s``*KhUWS9M9RhBVP6;yDJA&WX zrL75g)w#`q+8`&4UXeVj1yB!#d3#?oa{aJ;vj*wjzrSSMHUc*;4yZ9T8qN2D`AuS4 zZ|jYqc=qW}GBt98pi$V#0a!)7bzEWnikEe&)^IgOCZ|&`DmKiC zeb^}Bc3c9=%;Y<6I-BrhJ4~O*>oSw%0?X1SQ75!lzNmnoB>!lE*g;0n|M>gXyoj4b ze~j%Jse4zjCj#zD(2DjV8^w#@rQ?&}!a%&MpfI!j$f~n@`ZH_hoKwv+0K83JR$?(r zcg_=Fcdy|*a4i6^`E_5EoZpZ~uNUK$jj1%*>}m$63F#<&-tJH*9U~BvtZR zxCQufg(`;1iK2n!3Ctls-rW3rKP!$d(8LDJVfDp`W*-QW*Gd zRg<7v9YO$wq=9ZaS7Z;bh*WSuy|)CDRw%G+aC+x`y7E?H(B=Q59&wE&pVUtWLIyIi z6fqvsucD_UN1#(lD03N`8tVk*@8RC<@QPBFP+_LA&01|~AV^g&z*0RCl{1Opj8Ttq zjImfWA!J5C6mawSPmAs2^`S)fPH3@zt92}Y*+31}C5M>GOL;K0E{Uc*z#>o{k+=Fl z7rK7HPUQ(zns$pYNUa4EWB~Cw7kstz~l~cz1sV| z(Vqt59uKxf|BSPfEId=|^LL1^G*0A=={w0Ttq-Qsua_q~@(A5jHAyR8JOiVw_Pv;} zSLBiCr)*!y+suS zHy~<+GXe2>@746&0(NAPik1@m$m~x|<1vjoJz~9cd?4hLr?KMg>@0iLTx+@7A?;N= z_esBc4B0*J>>Dpf`PFREx+C}iN?$#R>#{@pLa)ewY+bKb|D>5;lzLUhKaYUvzy%;j z5=2saqO!z?lk#(0M6wypR_wRD^j%59IT9bxxUM?{IF6s|sE%IOj(9*3U<~bt3D01` zzDHWmTZAwWkRfOcB9|0|Kgad^57slr9Sp>jRAe2Ewb(}H7cN=`3MG-%X=Nd7nmm+w z7TisZN`N!bg6x10_=Tk<8>$`KUQ@RU#fU_*`*0APKXqhYTLH_sssM4)xXamrU$)fF zbhGq^Bu>;N{+>bDw16ecf-=scpdIFatGdSV6$O$w;=gS|C%zmaz0H31x196_VXgnF zuFb>j;y4Q3qo052etzyIT&xfr7{rXPP z{4y!@P{fCXo3ESH3Ks7iE5ux_?qKa@^tYJP^9WmZTd7qQz8dq1h@%t>uX1PY_5W4H zovW2SaXcRSkxqC~jyK0-cy~0FK~eBIH1zQTb!p;ZT?{iOIJ}zMAocI+*$#GpE`=!bZM=pZUlWOpzrFyKHd3Ws&&I1?%7}W`5(Z}IrxkE+o7Hu)5zE&t51twrl zs#Bl(JMsCE*Oc^gXNj+=NQtLlZ!zN$$2#7#yb!c{_5s-(MXVC}OO62dO@aKRnOP{V5~^KUZf)%-4r6rD zwIyeNem-ECF@V@smJzOp3oi|*p2GhCgGLxsrzXo3_OTw*fCus+mE*AHPya|2vxkuD z$vu@Fn9Xu&>lUStubuaA$vB1x^bYXe>Bw*OJvadJn-l)mj$A-Y7Win@MnLTH8D5S_ zt8TcgGKL{p|LSmVY&4mAb?AQpezbMWYr?Phidv_aw-k&0P1z-M!O-OVbnhm&k^lJc z-MIc?e3gF3#}5H&0}Ic}_n1^W;6Sr;Jzj68$8Y!E@CLEYqq@6m@~b0jl$d;RC(;~E zh8Tge#3~~aW(iU|EIWt{ghB!nl+2Sl%OJwa8vq~m=oJ{tzFIHpf1jUX$bVGDQ1V~C zk*R-=>=5w=wznFH!Adi1V*(6*2pBbyA49D!k0yjc;74Z|nKyx)QwS9LeeUSlcy|@p z+AbaOgwRK{9!G%k1^zE2#P^rZz)e z_!qaUbOZstVQXG!jw*uL83ZOe)?$UV9yt}2Cv;s`1ZzA@iN7V|?19Q>w%@XNdx{){ zUFLwfeTghEjwwCi_$FDkMnR$OGS^*Bn5De1z6uOiBHRN3ZSTqUhChJ7dps=xNQlAeqHAv&LgNvTv9tT1%c$UVN0 zYF?oC=M27XxTsyZB3%!#|NP+6S%pG4PCK-NzW>{mf>T4ffhJ>zvoU+T( z*N1l-uk+2ApyndW*G>L`tHdh_Q3|lAic-bn=OdIG;SWMz-{Qi%{mRJDFGmVC^vcL8 z$S9yUbjzAYb%D>B16oV{ujJCDFV@nXPkh1B?4OikpEtv9mz{1Fo>N+$Tdhh{<92WS zOf(0!tLkQxqsx;OQ9T|m1gw7DJ6oN|5>p(-J}%&tkoUO2)(@jQjR+2!wBnsFI`ToW zJ)1L|g^vX?smuH_cT#W6n;VCJ*we?C`jF_gHPH!LANWHM?SGSwS{zp1hE^WM%#pd3 zd|F-%`1ZtgQhxCj0SW0{$ZZ|fZ9rp=9sc!IKB=QduN1!x2}f}$*PzMozKbz}eew)D zXYV?f!D}A18O-JB7p{Avgo04nm%E^=Fh4zP=NwY9%Z95g9HF=*S_PCya|LtOV)1=J zJ5IVWOvT+vffpU#^6hxt6y3TpmCZ#d!Gm*;KIR;b`ZOFHj=4|P`5j`r|i^1vkmB?GNUOukT#xF*?LF3RToxScIxIz^4^SmHZY4hcS$C zua*U$6i=6NvWCG29hLf6Cw@qUJY%$T!Oi3V$4vw3fdcE<#O6~a;Z)B31L^m-uiwZM z5T?J7pZpR*gQ)fN6UE?N|2my{n-K_)12G0;aQj9*c%1)Q%TJC=`Hi~N^76Prm*;Fm zm#cBVYAL5~9X9e@MLA+?hpJSJu8kh1X!FSw4VjgVd^lpik@;dhTEn;Kg9MQjy((dF zm&p_fEar!hl8xopzbRp1-bH^C2r=Uv+@2hHp|NFCv%=2~;(XV84B1B$<}YG&Iby;s zP9RF7($f*G%g@BaK9};zq{SZUM%&z~c#(^VhcOW&Zbgi1y>Q}t+^k=^ zoqkX8BkWs$SL(Wf#5rl~P~m?a`_Y&e#@6Q~v=bMd_3B8r3VQ+`3niUXW7S;PsrtV9 zc97G@Gkpb8zjyod{^dm*;|&Y>uE^Dco3h;{JXB53gk|Wu1YA(JW^0hxCqg1PxcTV1MlUCA2QP)%s;&ED?t@UREp?%}aVuZmGA+r+g zB=3uGp4?nDwM)p3LUYb;`q@uTn^hOEOc>6P*ljgQXyxd!v9EaysgaJK`&f(XROd-s zg=GzYEoYkA@p$>-cG7*0&;{4c!Cq?rhuLK~>XFKJzy->;h0CG{;NUf;BhsF>=<=OL zdFkX+K2|#975wiqSNR}v0xl7LIgi*EXL0|cS!4bsiPcTUeL1QxPf~FA-ojaTPjk82 zv50BvLX#119fWU18FFG#%DAS?IQfSGwVwF0QV~^e{}UQWlJ&8IeW0kc23k#g@nc2w z?L18NGEYlp6@j4xwfC%iD=b#QN>-G(TzC1PbA|e{iKtnV{q`b=A8$Us>;OY4d(?UT ze$gH2p=mPxYdq~-8!<euP5 znPZl6h2WJ!BdR{ZdO5vZ3(J!~tVm|1CQse!LL`z_xHt|(FN!In1g^i>9II=shEDfi zy5F3tEI;xci_PV%rPSA)+gv`lt~gx3Fkaf%Feh<3+9s&Y&|=IyIh3aP)OOT8Xdjau zHJb(h)fl*kCTUx4e-T`|cN-f6gAQ%Sj;ppACb1CPKm0YHbzeiK%X<~Ns(`3f2E#wA zKZ0WydkiDEHV!fe4`%p_UG-VLHo7;b@P%D&$5cJc)Z7P$^nTw6-i_Ccgj$?q6w$EQ z{H^m?nNiDUY2WvmtU{p3c~*RsNqQa+LVSY|_DN*S)7n4k@;n>a{NxGO%6;;wEW9ET zP8_U#igaoWYDQ>VjTmfs*Dh8+wx7Ry1!{05DHc7Yx7}JL*DpX9X$VqWWla%!DvHld zW_fbTc6l#&;t(MVY_Hw_LAr>|08YyPUEH}aTVx$XBqVa>UdL8b@oiVRcQ5Vf&(`h( z3>Y%0ZW|`5(-}Q5^>tfV>B#di&gy|0!@lwzktWqWny$J>w&o(q6?sD;{CHgPWk(nl zJo&9$Oh?BN;`IT?*DI}9Z_=EXe$=*tqeVFJn0Z5LSXt+GyL&WnZrPWGsqXSXCvR zLEGAM*GJBZP&#E@IL{H=6!#kz2SMl4zCQku$I80sYoT*mC7e^L zwLf*9@4c_iPR@lcPaIaB&$C6m$=%ZV=mdw1`#|qx#cXfATR@zxx2;{DB+Fjq8RGL5 zTh1#uzxS+V*>VC~-|v9GJRiW*Xa7GQ7MYou-={14@>DK6D;pbmTmJ$~ZvNHlQBKY> z-jeDampaL#_aVaLzlIV665)+-%dNFV-Z85(Dl+cmm=t!RD4@|-wyS%8oz?pNjp(jN zX7ks#6^nXl9dKQl&Qy%4Yh8fVZ}x`xU$Q2?s42d-CHiogLB-w9Fl}2y?qV(U+YDo| z81%F6ZdA94_<45eY~xL=)Kj)O@p9f_?lYM)X*arqjTnz>h76r^mbJRrDNdNhpA z^lH=;XdA0v1#oDjB0q+=3@DYIj2AFF&b57=ii|~WVGwD?vF^KQ9(sJX z?h7BoR9~A}-{p>OAZPOv7ZGfv-Fft}5X0D)-iOuBNNKpcEqO{@0~3y-K3COITQ%ao z`=rPD8e9aAiuYM=MEGd~GmPWC;BDg=IxDwPuOMtK_wfCmq%cu)gzd1VEho%L+j*GX zvYpGHljB2K#MZyKSRA%G-uP2T3)NG7LN}F2eo9~ech$JzQrv>#L{?rOSIBd2NgN;t zdf&wsPb|h{%H8{#Rpzb;4KjNLe25XBMRZH z2+bvAKvlIU85ZHK9&w&33uoX~9-Xt*7r#wiy*|XuKh^c{-dyUXaaqRH{cgIs)Sg~9 zEpu{TzRdkh1GfQ!H;gh#I6)uDW?pe;f`mB;pFb#D2Nx>x(9##ixFsTTEgk+Q7#{fM;{^3WdF z{nNwC>eWVl8;#c^v7VxsAMTm0l@+Ra17NZb%+>qyziT4z8*~{~y<{PdQ7`Icx3*k* z?d7I^%4Nwe-5av%X7LivAIR__qjyc3FQg{xl|)bpN%S)7zi)gSr6Qmrod%+GcZqLG8U#j{NHfOh9P&m~Qjw5W=@<>8 zQMv|RIfi_>l_8 zr{_7srEbOHD!wvIkb~68wCoT(YadfUudg6l@8{c{c&9pQGu=)4l}IcDw5`jH!_r9S z`E+--uH!^a-nIXz=EWJIR#hK%SAR&+p zS=cLp7^7!6|Luud*|ef9ezTMOY+m1or23WmHrG%vAMWJOZ{lPs{Tz26gwOwFJ=>;W z7@6zLyX@O;omXUIvItD{bfNT0w;&sHoJ_XBS5KDja(Z)hYAzt}oj+H9-W^6KW~EQl zn9BDgjD-21wRj62Br1rtGm$v$|Nrr{py*fZ>~ZTtz1|JQ$#*H@Id%gzf@fM5r;rwh zxusE~@_ZL()3IzzQV0!?qcLAhJFjH>#UD5A^0ke8h{9L!zy;ZU;*G%CC-L*_(ei(g zp)r+vbVipuVRvx{MS-cE2Jot^*CyZ@Wc7zPe(Bk{A#Y+}??r+ArgStE3UkeE^_aLv zMfTSzQ{O?KD5~_PEb0w#r)Io$Zz^sPwkDY?3urFFTrpjoDUSmD$dMm$NKwZw^e}Bc z!Hvo#b87Y!5Nf=>W%Vdl{Ho@;W7-5}aI2Dkx=^u@G+_zZE+iL9$7@AVBebM1FQrR% z-)o~w`GvK++-LHy&!M#G1D3?=6_;7?)rmm@7zS=n3rm>Wpx=fECsT_?B`b5nh#w)| z?U5ukmx1SeRhU@_KqYg*V`7|fnG8It+wZx>Wy4h!&ojTD1qnecO=iV3e{9uKOp)&7 z6LQ{aX}3!Ivy!H)ARInyUhig-Ul0(!aq2s}4AFUZhJ5|n@yGkh{~3piH+D_nR)(aD zSt(`luuxjf+w19w^67WF!X_9_3c+~6ONgXg+u`SLA|9FdDIT^dah9+eocU6_sB({3 zJ3ayNqhzTy&&t0~X}-nUoK;xnPT+3#0LV&1r{&4WwANCy6m}ZzZ&XpF!i@yJBA*_w zhnT;GYQLZabhU{}y&NE^gtAq#b>aO<6wigqY_mi~g(Q5I z50TN-PAFhn8@R8-2Is$}`xz#O`O1!#^2(w2$vA2(^Qz zz&+woIWJn@M>{5!Uu`&&6+Q5qL z((DTj>%(}_4O9@wpYT=qP_az@_vkPg8`Bz8blss3m?3!9taNb}(4H-H+BrAj-KFYf zWf_85ZW7j{lRKqxC7vRf=kyib(jFVj$Nu*$`u_b+IcXaG1zHX#mFW~k(aJqu2t62a zU2F})^D3WdVMx9R)+d)|V)q(fo=J&axa@FTf4W2acHSi5dG1v=6q7DcIQ3Oe`A*(^ zwpEOc3T5MKewFJB)|U6fQ2HE`Jpt4kL_e@@v<`gy4W{zUPrlMJd{R zfg-FNdp!&2x(dvFh!ZoNXSqL>o~sk8qr%lAV_`fMVL3q`w#yn@-g}F(JN@T0JAmB4 zKIP>Lvzs^Hq)ZdDPCA?2hDjlu4O;I5ZC1i{T{xMxKQ8k2f2lm$Tv?2Kdz(_CVld3y z@X{tr%a)~E z?Je+qc9qs^DeSsQ_1wNBOyeq;Hm;<}?$TxG>l>aNS#H`ae_b!n=hD7r zsewcTPGUDnZT-igWqy?4zLS|bDC$rAjS0<#eoi5U7uAOuN+XKlIsWOq1R62)NDu;V zIUTtE!I_Z3b;W(L(|uBKx#M;MW|Q3_{vbm~LL&5$l{+Hs4-_2;|8D&G532RG!wl%7 zh9|`jYL5o?ii7%fKa26Sk*)=u%HR=qV|N&Z5@!GP1PEy{TL6Zeeg8hw7gQA~@ULTJ z22(Pl*U`%KYY(j}6@lY?=X%4gjQSwan>mxzidAoU-k%pZ0zq%!q5?W9?9|WU_CW}? zB)fYRUW{3G|H8@+RHs#0w*bDKI6d|~ z$`}muGIESWC|g@*ZRYI?PD4Bd#so{TbUye9>Tv21Pdl|*Pa)f-YAf`~zTpn;>U6!X zFv2`;uCVSPuCJhNy@O8$UY(tB&_MR!@t4Fy$w(??o6Dt2dP|e+#(A4SF%Agg&A6QN{}kSMbA>x8=UP-}c+av`c)ekOid3SfVJn z2b>~();E4hHeK4Xw#^YL64{a;Db@1ZtrV0sPn=t&D!sDrad=|I1j{C4KB6m-?CNsu z+v6}yO}C-TnPk`&dqdQp8ynhYGajI`$ST~59lU@- z#FsW^mT|a>vy7lG`oqGwks?%KVbzO+tsp75(1raXnHRC|Jo97UKk$fyt}L>KEb8=( zO_$4B74cM2CRj^+$6*fSz}1G6_h{b(wc~RAm-A&=i_`|M>!(UOtYfQrc~CC|g{?)+ zH6*)Z-xLeS%7i&;IPcP8eb?l4M?BFQ>xpM{BoW7=F0c`%3^$hiO{P>JYJO*N63>if3?*l6pGw)1t{y z=(yDHp@VL|-(QmZG?s##;T{bClrQQoep!qcpX1|~7b+(9w`l!oN_LBJwrREuK9IjZ zs!jU}#Cim+Ol5KFw8G9hg*cARtM#a@8IQ)-Sb|?Ng(NkHcRa&&0jH<#(8Ui--WNf)!Iu8uylF;h z#z+SRa~I27Lqk6*rG+mA*Gu7Rjt?$=w0hSkG38!|+o^%(&DkybEd^dv3H&1

    Y(FvSI^f44A;EaijzTm{-D}G*prtC0R-+IOOU- zuS8N>JQM=~3hfN+VHSZautwPge1W}J^~fE(<{P^eN~$-Lc^GFVKlQ>-uVg9ApPL;9 zPZrvecBL)`nfi*ENIjI1y2CW#mclEgrL?(23MrKs%sqx|3&lQ&i#62}+PYOrRf zo3gR7QcK~k5!T3<77`!kNBGQ+K^POSaA&|*d{x-xh4H4B!kog;fX{}9IyXu!;7xsj zKRXLw3)keLiOHQ8D4N$@Ju%PJBDvQg`Dv zZA_XaUx&+3`lZwvo!|PMKMG-Z`=c1SQCHVsqIFf0#7C^cBRY} z!1x!d4Pi8Hxw-9~o&(%dytEN5>*z7M81pNGPZzd?mXW1qTeHmSl8D}NDY+yr;anmU z&Q>QNQ_C~JIX+5w!j>}O2L-0-(!rj#CQJ#gdf-+v$@DUe{rpasK{ABbQ(=Ioc@Elt zD8is@ylNiBwWd8V1?cuuIP$PR`H*ZWANl-u|Kh(Vp}!LIcRRkmp?N#og1r3JBGJTC zQ!^I8ydJp~ueSH%)2A}nk3B6@`1E6v%MRL3|wY(;B#Czdt&ZXcb*|MWlqyLh?19}7z3{U;yA?Yj?rPZWwT zvS!B+cYGZ(f$#OLkb^oQnDEid;_tjWL1Qc{pv^ZT2tg1af8Y*J0uO_^#9d=MZxA?z ze!^vV5rr|YG%4N~0hH>Q0vnF2Vb`{JTGeHCZrW)f=sQ2XP}*ZLZ=oEk)5p9E1b87h zzY@>EPIHcbrb6s4XO-;#`fvYT{OXq<$K5-3;)4&LL~~(D{q$CxtIjCDP&TrXot5|; zG1*Z17K$rj7IbwG4E2v(H+JdxsAmxr_*yUgx@4i(u@`x2;$Q)2u7Bg%~)M&co*5cV8D@#d0&s(;OxS}N;*HvN`#3*5Fe4p zf+d6~tlZ`(F7BpT6Yt8=Snd72c=p++UU5vjAsC`P;J-SZ!)UkmJfB!!U$-!dU0&cS zZNe@c6r~?Mc`u&4ch7D9T6vydPsHXyFLw5O2|wZV(qi5ZhOo)Uaf?rzVxbcS77Ud9=7A@(_hEV-mdt~>)^Pjk3RY+9zJ+r zCFs@lsFf7YpFNM~pMNTNAuYgv)PonahH2;a_ee6yO%p#<}eNwoxSi)vTemV0_W{p@M< zd)-*!2z0@jqxnAm)yJ{Ayb^cr-HAK5?*w6bnZO8pywJoCJxqn?lcV@C>nJ!x7XFMACO!GmT&1HoP9 z5T55KUr>SLJn3KNcN7*uE4v-xJt%{Z)j}b}!cm8zpXEs!^exAM7719Dhmw=iL(z-^ z-SZtiEG|^xa(GqREXunQZZcFePrjx3GrJg8msjKN-8-U}ONK{Vb69qKp=d!dPro5N z^9bfX>|8iixjBXoK`AT$p=k($54%Tkp!jXg=YiKL%2MGyFkzl{OxurL)U9EtE_TC7b5rCyq?L0!%6aAX zLZF+*ofIGr?6gsqBg5F${x^o4$Va(3U%a73$<*cow+}VMMQI zr^e&Q-~Ui!!g~Dj<4@wxe(|yLn~0UQ4d0bVTV9LqdbbI?^sJb@FnxaS{(5}xgS)Z1 zFcUq|Ms{}m@{VzDQOsOAZA2JYV7s#FTHXmpfQJ6_kPRc}{!+nh1%~fGY_*`&N z`ncemvJmJV;Y8y_r&ypfDY}(PW8$cP#<8=xC^{H8b4S#A+J#pf35S?gBRT%6qRcgw4D6n@h{yf$ZIJDyIm7!e?7i|EiFrjaW3sj!YJS zfYZq0I2x2bKtASuD}L|*Z}3TFWhW?jn@V1lQM7+{;yTtB8u7v7NAcj^ZS~<$kf2oLveU2T^U5PAt8F_uCH;PD= zUe&=MYskeYY4=+N8^)bC>~FODn|_%3?f1ZI$gP;S<6%5TzhU0Q;jc393OB4Td6)U7 zX=A=k*ms%VtlRIW$$EZuS-s=yCqMr2&k5{~RN@Rr_G(^z`wMqJ`iFoy953EV0Gg2r z4E$<%zsW>zhvyS_8+Xh6#sV_)vJZdBNaPm=Uu^QxD{Xp6yZqIBG9Tqcryz@uKQSu`@JL%On z$+Y>d<#8E!u%csv{=jCR!b`IjKrvV%8!pY`j zgmyE7sJ3LlF$1f?ipdj`Mh2N&VZk8AHw2ymQN_Yf@gdF-TI?A>PRFk<%(t_*^FC&R<8ATjM?NMKlc8n|+BBlhp!xDE6}^VxipYzX^yILDVG zooNHdzSg9PHllobXm`${mxq}(u$xJR@kALiz%x;% zJt@RBd3n$$Eya-?=EXRm0bDKUa$%@Lu7pZ_B`kdoWhsoeu*>aDy5z@k60jaj*r*p1 zQMZfYQa)a!1%qSQz=WyZcu;N_2_BN94a`94&wWx(oY|ak&55*%V*D(bBurEm_d@j< znr?amp~j3EpHzHh8)2O4HL%Pi+<$SxZYLVP+WEmhziL=Bwss;lhZ3$hME<3d-qaAk zK`8rWI#{sVlpK3t{}t@>eb ztubm^)t|Sqzy;KIDP#J`CeMUb*5CML588wr@#9A!ct|Xx`uisB%*W;Mw;r`)Dx7$# zDJhZ`VPs0l^{#o>A0DNuGG`kSO&0fo;V@}3jSOR-!4K~mC&LXsNK}buy0qO*1!+61 zhPv$vml^1Xh-o$aa8kHZ1O4i)APz-5oJ*JtTSI2+VI0IidTxr5#&$x=gFyTfrkWBl zVUHhS$-UN_cVZBqF7v=ny!^)90EIw$zgg&IE7iuH5eT85w3nYWq>+{(=Ntcd`Kt>5wG@#U}C)G;m_Guxa;4)(+DRqGlfSs8kA#-w>N zIF9JW)_(lz(--k-XFrZlSX_c|f^k@LWQ~LD`axg~8whKH;2#A8$8c@$bu3K#V!P$z z=Gb&|cFrQC3-f*m^cyoApEx02bTk&0mScH!#R9}nKl?mB`Sqv4u``S8QdnJ#xfzbj z*2oTigLCu@6+Vv;gkJ>KrO)85v7E8hN9MsB$sJyh+9zMCI_r;dA6~^m0VR$Qnq!YS z+R68CvHPsSMgC3kQ!^G0T$~=oVVgU7y0Ns>wBQonb4vWpt+f&baJShc z0u1;m0SbW>i?29Rtji_+EFhD8X1*DB?!One@7#$E@opR!hXB!nHN~41ufR^Fm8FIS zhaA1fJdaiQ>>xqOL0iyH{Ude^<^2#Cgl43}@o$Kr5Q4y0+x@t2p}!#mEaaX-tP#b( zvLb`KOf76u+0XPwpw7-21V8LB>78E1VgEdiR0fVuJW)K3)=H5G4`Y*Hpa(t`h0bDA zby;2zZ>Dmbp1K{m59x#V9>$1Z^{4;wKg9p?Z~l$w$S3)II@?qL0Gk za}o!~4g&iWRx>wA;V*(>1bi043QstOAEh$F$o`SqTMszPoPhFro&en_yg}Znm3_m) zP~`{TP>XV0;KtI@qK}(fTU(B$MRvI~ z++HZZ$OkyElg-C+DG%Utu(ub_gs;z@J&l(yUc~P1j$qbxIZ(vVcC-~-2=&0?-7v~? zN~kOeM*sl-^hrcPRP+a&%7ul5khkg!E#YA-asBiLH-RDcoLA*8C~(AMgkVBjc>X4f z$Eadxi&T6ieMT|CBL{^ST>{VWQ#j9Ylmg}Of?9u9I-lwDeUpCDd$*tZ6!maADCYGI zO+=Z=oROV`OUo-UJJ(Qtxlp1SQnNBp<)EK1k0V`RM%{ozX3Y=sigE9*Y&7NtLyjxU zMVaibWibeJl_HYAcNbYnGUYo1IYM=5ao+gF&L{5JVizFyG2UHY@$r_(nAmLvec?WH zluj%xKq)mpH?4Fyf|DaJS)hW_NcEeZl$-jg#$V_>>2kLoutH#t%*J#_<)k01t}ZLR zhUpM@dHL8=^~XCK>%zem*SRW_I1(GhpOvgC7rT_XAFS0u!HU9^-Ax)PHC`QQoZ=3| z{nnwwGTz_aSk@Z_7E0|)-$}>L6Be{^$D*i&=)<=AGGk=LE8<%Qr1GO!sdp!F_tEY3 zOp}Eu9MQJ2ylAC7?a$nv-EPQ?xV`{Id_MHi3*nQ{Pkn<$6L;@!#QnSLKK_wA)i{oo z9bPEr=$FfCue*ZDebM(j8*A#P3vPS*Ch$fP(VWerBu!V8xbe;iqkbp4Mf=fzQudYj zj#3YLqXHYRIMpV{amH%3*SPwqXar-1VN$~KhS#y&MRgccALf|TX^j)~Ytp7INQ*E@ z!?W+XZ{V-8r96Wqlm6l7egth*7+^iC`h&aRl=Gv%(znC|Sk|gEh)4Tlw_H$oO&!61 zXrB9p-lR=AXd{$VxsbjgcnhA4jnE^;6=)tbi+r4ZmJiYmOsN+;t7segH02}?cGBbC zM8XgU*fS3BO}|Dl2c2Mivf}aLTxDj_lg3lgH0nYV`y2Rfs9OfKsi;%q?K83 z$Rq}LIAmxKHrkZ7rhVp=H}sMn*_%79Xo&~l$Yjbhr!u0*pA#<%?GpxykJ*b?;%{Dx zU)Vo5^f@piF%aj6O@KL7W=IVX+tY z`eYg<&^t`c<0eKvMEQ;UhYWu8d6)UBxR|&7hsQX~*To+;Ul;c6y1nbce49M~GEC%Yv}NyquC$NICge4}O`3 zl})y#p)-{vhtehbRfHp+`z|SE zxiC2U8;eZljbn+Al{9g8TzxybBRZ@Fd?lXCW7rbjDH0fq({>E9!$CjQw>goAL75tLSP%dC7tDsec$4(uCME5pljM z1A_+x5_d%9N;DJ$IS4Z#uYJJ&kbgttUR#U)%?%lqc6%c- zFvFt|Qs6hqwtgN4Sxti0Zm)S2wU4;~eu4>1S2Dm{xSA6)aEpN)STb2)btOU#m|I|o z0Z(b$y4u@qsE6=%Cl?AO%#0W=R`XCi+J<~#47fnLG77*N<_3SSW`sc_f`DY^Pu03q zTe0HO6B;oC)FE*TD-4EEP=l=*K9$`L_A3k|54BSnDJOrFn~9r}G9Ivclhsh%EyuAq z)TyqxK~YCJnH;kM4n~aKhu|P(&+QrDxu}N9K;66>OyR(5aGy9lE|)5og0@<>Ycr{H zVnEpeXJwK6+$T#6%2_^4tN1RT3QPFJgN(yZK9%OBQ*|d6q3|DeD&cLlOB#pqkK3Sr zSNcIn|5iVKsKdaiS{QHaP)f_2$g;~qcn4J*5zIewbbqk}WRZ3(VX+Xm`Z>k4+ntEc zM{b01@QhP}*q;m>3J3o4r5`7dA975$d@_vwC`+Q3%Tq#?Um4;#t|MeT!-fzy;jv+8 z$^6Z4?2e;{y8F)#@}ernZGzR5@|TxgYGhKRtoFC3-3Q)0HaH}Va!j;U4`FkR*MIrO zhRHJLSJq%)D?!{gCH_r2m0FUI@Q8fTfP;F zdn+@3tw)wSZS}Xh<5S(qFuy1_R*zd5)Kzhod}Hcc##VXo_HPYnH~ZfF;%0c@!nZwS zvXrTC%F0theq9gOC(BXe@G`IGkAx47#NppzYr0tNo=?7T*PnynknLnV2IhR!46C1h z2#&%2xBaNYwg3&2aTa0Y__AD)nL7sV0^CXR06NG6{wAUA{v z@CJl||L{1XxCn4?_aYqez3@Z6V**$pyqOgb#ly<$nJJ|`8IAdwSZL10xaK7^_xMSytgb69gp5%TGt4s0W2T$Th zKm1YLyQg|6&Bo$#tgLM4S&K#S?TbsxF(Y0*1^nu3?#m;Fjql!dyNM?kIL|J`PYYHE zk*i`FK{joVz?ft5=<9ub@9wo?XTR;c#TpAMnn%qDM(VF8@WRSR<>RAbwE(w>b@5#gP)jxR?j`e~`L;oL4P42;@^Wc1266@FW8{Aep>>fFq>>=>%ZCOctkh zI<5HSFMr|jiE$geLrKQboh-^YD&rJoM4>F~^+_-6d=_xb69@#}g-AHyPajq5yZvcv zS!IgC+VX}F{H9`kb=it9j>_HGSX2F1)mIm+Tmes56b${NOzae*9iTh3FM0b&U6t9m zE%XG2;GcJE4)9jcGd?l~q}_A{qi^~Yv;u_%_z1rM-Jl$c8c$gKfQ*5$&-b$`zbUmd zVfY5;sV8uyKeB_$_0%`{lP3VkER*(Gv7{$y8RKU5-|R>144&4wH7`6*1qyv0H~1Oz zSKyTDlXHfIGjtkbT4;dFP3b|q!DaY5pSDBZ3QHRBTa3euWAr1AzjdEMIi+?4{){2i z2SZ;)Q8wd6OeiW*nvpi;;waYaJM;_UGnSAZJ3VPL>@0pEed=E62W>(=^i$)S@8~;m z-vwYO4dK&J-lcL>INfZBr{E;4Nu_t;1tnY`1Dx5d$s!KuG-D~W8(Pg+PWmho@qnU# zQ4rNE$4@V&5IqKN&@W(2U1%d{1;-wmo+&(V<6j#4$Qi0&gp zynTlq=yzg%b}nA4{_G4}S(uBv>x;3mvS@`JeezP}1{Rpoq<#Z0kUZV^$#x$$Z+_RX zNxL1Rd^;ViZ-wXotJ6#~>~>=V@A66S^m$kOH_S~mKVKXEE%R-{f7`U*Wk}(7kp zGXJkGgB4#t`^is!4)WF^9wg_B$ac|>zerFIZ@bITKL%m*RleyEdh-o&8`vum%I}Pn zZ~ql9J7K|{O#BT(CZW6umT40&OP%%%fIai`A1lr6uQzT=HwBjZx1IXr+pDm!@MP?K z^CC;V`0$_K#m#={mi{wr+mxKDz53tm|bYb;>wC9 z&I^LG7+fajf+>sxu!OOquO@@TL|iaceDElHsB8?bdb4`X=OhbW?BwzQE+&EYAq**2gK$4B~j4duh+&h>}k zRfx(+=uG9AjW=EQc#$>`;^Rcb1t?hm)JU?VnMcgX(GTjHjP09f9(d zw5K@nEtp|R@BH&Op0?i9g@1?Qje7>bF~d_g|D{P=y4=9aPW&slYoLF=Zj9SaF$QTn zbSbB-bxd?P;BWT~Rm0F_H--tDt{S;Fe(v0#bop6w|@zU(QAMjyo&P>l>NAL4wDeE z@4%CG84g>1^~yMUYE!4zo5pUyI|J7^{AL|8btRFWer4%0*E9~PpXyTKz&CbJ`>H=4 zz}`;!Q$(B+esXmCr$f3?#|)d1GQ7j^T{5;mody4)zhC?<-|=NQ{WTc!9nKq@d#Wrn z8FsJY)%Y_ysfl)s$E%&g_|>n!h*w*CvG04F5d3TWvuqO{vG##9brmvvUR`mV3rkX1 z##rKGel*^}gP|Ou0E`C+(z$Pd9XtpInbdPsns-iUTt#rm_=s?QuY)pfH(tDY=^Z>r z{bMUdFz}2Blx}&K>Sb`>3HOe$q8nb*LO=5$@F(NqM^#Q$V!}tnpeWK9EWU-EUGO$3 zIGnH$lU)x};uj_eLwv^(+?3DN#c6O6|A$ZBkMDf=*!ImAU&Md<5C1;?>_7c!wD)#n zg&i1k^X4~4Reuyb@H-q+!$th;4w~RDAi;y90liXPyfs47-ccUUba>RKF)f$@dI(>* zw}`uGS*$~SfS37>%X2T#L6AZ?gf(8EqxcBleB6!r!&|Bcd=+B~f@^rU6x!0)SqvsV znfQ9(r)X!7S*ip4B78FZ53A`>Zmp~?d*=zl)LHU?#}~}Gdu7fFL+;t)=sLM+UZCO{ zk5CfKz?;TZoS*c?Yn_UBI`eTpuQ*NOdNfw=+>0mQ`F?z)=kEPSv3}=%EN|Qs134A# z{zV+J1Cc5UmMCChTiJcq?w-Wx_)LsV!v9W3V{u8}Q*m-N8vQfzcO&C*@mjp9(pg;H zh_&1IVz#-Yl8k8{#9c}kad|zia1$!Wt>~#AfV04cyJx5u^`z|t%s@HG(NqGFU=Dn! zr+D143Ez*lt@^OKn%z+sf+2Ssb9c{!ySIgBv;_*LTUOMubL(7o6<+u&91)zR!9VpY zx*|L1xW9?EnVM8vDlL?I2)ulOJ@~6O1;{9>I7U##j*f7NJA!!HoufEbJ%JY}!tM=r zr)}@-MN4x%juGV^x8qa6xOW`;t)B0v+HG}&nA$X(@)8DOllbd&- z2;LmS$lYpLkzp4WgtB`AK{xY{zUFS6 zP6AGOH;dW>ejUXFG>G&_gFa$<12AOB3)s;&m=h4zcrKH3N^l?gk-MkZ*A9GmN1?hH%gbxA zEWBLw@qnUJf-`gq;Vg4l6u0aEXzSVA-;Z64ry^)ZZ^%YpCs(H01m*-5~h zhO|+H0XGzu;0x`>@qg?xArA9F&o>xX^yHks2*34T-3bev##AnZ{3wl>$IeJB%A^s`IWb6&Z#cmdkUI0tT}a*N|M z!3*^}B>`-5zDxaiv&b~l08YeXTwqM39>Cs;2-%Hm3X3otI*-z(t9In5K5%Gpu^H=Y zt3HkmdK!#-q7S&UQwrtQ-0Y0TLBSdtB|JVk>c&yGqjs9`SmnFDM4wMYJiEtd?w{a* z75W-GIU$C5I|?>nj-r6MJi95u_vNJ}-&cjA2<6wY`ab1W@l~%&(@65ba4i5lJ$=&i zXu%q#e2cpY_fX89T2682_Ij)?FDk!Lk6(=O%=uBoW_@P7*kf*%>k3A#NI-#r();?=qRo>mn4K{1U`3YQx`z2d>$JBc*zpdj~7CY8lFuDpPOcU~!+k9k#F zq5y;E7!%GXo~jSRpC~+hkv?cJ)g#MGpyVx*-=ghv_ZRdnc|UNsD#b|?7=XuB$%WD! z1sDn+@Q7nGQNA)xsi^7$*-t$0bD!nSu$p`aG#6!3uZNtj8$IqI6wT+TP0MM7CyZaf zo%RIBsFP`ro}@vk1k0;1$RlY+_BG|NH+`C%;gfiPB6*<1;;2*VMcJT_^o1(dfZyU& zf|Ijj(^tw1%zOfn>Q6ZMF#O1ev4|rxlV5o4oy{CI%Z3AX{?^@y@UvdnE!Z+v2;c&4 z;x>zP+(xt=Wnv727Ah~o(k?7MCok#>?asP#jfwh}9%hE#Q7(FnoU9|*?ux(OQ=dFN zyVQ7;ay!PKJGa;3$3Oah{NOuJ;_-vqK7RH4AH63YcTW95cr|uy`5pAZyEzLq!NY9L zVsPM*Yi(!DupRSN-vhhagXhNY%`~g|%Cvai5of5NHt!Deo93H_tLEE;|F&tr%aFqF zBAwsHWd2`W1}nb)@Fze0IpGLTq>RU#hS%Hu?j%4;&*BEa?5A|9zyI{%df}8lSp3+J{CF4lw5P=>0_+k1cjt*ySssmj zV9H0r35GwRXlK_O`+NUQ_^$h<>4i`GWeTVGGWnx2t$C93x=5Oy$pur z&wXDAB}gn4UJOK|CfGp245rd$;3K>G=+5Lo4^8CKk;&`LwJK^0ggd+^-Fv}=Y zsVGb$jExyUm5F-6fKxBpo_LhW=$7K76ND4|taT{#KY8 z4;Nd>N*3Jhrgy1!x|0TY;4u18VbWgmtKn#8M;bEKU%w?cS<`m&*pp!zS2M2 zF#lw;H=g-zyYaLdxtDThIQ|EK8S)3dW$eO^Ur~@bjQ?&-{Tg;pdx@J4gS7dO)o(YQ z9z#l&`e$Fp^|bjnYs-@%GHw0v?{eB9>&!QHdpiKXeugn1UGYxL$nrUO`Vvo1;-G!( z?{fPqztb;Gx|3Rk{Y}W5I_N1sZ=_*sPV%Z>mPt?k=Xc>z9IX6i+W7?yNViNQOHxDT zUw%|uaVyS#+g{w9XW9oas!#c;_+nrGFfp~oZ)_Egd<}39cfLy>#|dATIY0cJ_12qw zil5yL3V$SC5yqZ3;oKU88H!t>Mmu5$eNh=8;a6Z`9u$_r%e9<9et3kR2dbF+Igm zGiR!~c$@PR^?{36(Bytv{1tZ?@NBFu#{=#`+E|Om+;r@0ZN{Je>3@iiKmKK$og69r zeB4=I_pwm$McloS$8QUUx5NYALQpng{$zLWAYQz96!7C!D z1V*facRKLx2w@f$yu#l{X3dLNQ5@nS*hcV%vJinAGznga#bkLjT^^4$IRT#BigDRd zHUba22iOF^IeHC`1YWXZN%Ilak^3V!RDxwg9Lt1a>qPUA{@G=8k2PQEpT)Ug$