From cc3a7a49556cb012c1ba398610bcde908e1c2fcb Mon Sep 17 00:00:00 2001 From: Perseus Date: Thu, 11 Apr 2024 19:57:30 +0800 Subject: [PATCH 01/20] add RigidCylinder & RigidCube --- Project.toml | 1 + examples/robots/jixiebi.jl | 126 +++++++-- jixiebi2.jl | 0 src/control/actuators.jl | 3 - src/mechanics/contact.jl | 102 +++++-- src/mechanics/dynamics.jl | 62 +++-- ...hong06_CCP_constant_mass_cluster_cables.jl | 37 +-- .../Zhong06_constant_mass_cluster_cables.jl | 29 +- src/members/forces/spring_dampers.jl | 1 - src/members/loci.jl | 2 +- src/postprocess/vis.jl | 15 +- src/structures/structure.jl | 2 +- test/vis.jl | 8 +- yard/jixiebi/CA.jl | 191 +++++++++++++ yard/jixiebi/Group1.jl | 12 +- yard/jixiebi/Group2_1.jl | 255 +++++++++++++----- yard/jixiebi/Group2_2.jl | 240 +++++++++++++---- yard/jixiebi/plot_policy.jl | 17 ++ yard/jixiebi/test.jl | 18 +- yard/temp/structure.jl | 229 ++++++++++++++++ 20 files changed, 1113 insertions(+), 237 deletions(-) create mode 100644 jixiebi2.jl create mode 100644 yard/jixiebi/CA.jl create mode 100644 yard/jixiebi/plot_policy.jl create mode 100644 yard/temp/structure.jl diff --git a/Project.toml b/Project.toml index 18a36de..7716ec8 100644 --- a/Project.toml +++ b/Project.toml @@ -12,6 +12,7 @@ Clarabel = "61c947e1-3e6d-4ee4-985a-eec8c727bd6e" ColorTypes = "3da002f7-5984-5a60-b8a6-cbb66c0b333f" ComponentArrays = "b0b7db55-cfe3-40fc-9ded-d10e2dbeff66" CoordinateTransformations = "150eb455-5306-5404-9cee-2592286d6298" +DifferentiableCollisions = "64b45163-ce2a-43f6-8f64-55d720633796" DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae" DynamicPolynomials = "7c1d4256-1411-5781-91ec-d7bc3513ac07" EponymTuples = "97e2ac4a-e175-5f49-beb1-4d6866a6cdc3" diff --git a/examples/robots/jixiebi.jl b/examples/robots/jixiebi.jl index 6ab160a..d0bcb7b 100644 --- a/examples/robots/jixiebi.jl +++ b/examples/robots/jixiebi.jl @@ -188,7 +188,7 @@ function build_jixiebi(n; ks1=80.0, restlens1=50.0, end ncluster = 3 cluster_segs = [[RB.DistanceSpringDamperSegment(restlencs[i], kc, prestress=pre) for i in 1:5n-1] for _ in 1:ncluster] - cluster_sps = [[RB.SlidingPoint(0.01) for i in 1:5n-2] for _ in 1:ncluster] + cluster_sps = [[RB.SlidingPoint(0.001) for i in 1:5n-2] for _ in 1:ncluster] matrix_cnt_raw = Vector{Matrix{Int}}() @@ -293,9 +293,11 @@ function build_jixiebi(n; ks1=80.0, restlens1=50.0, end -function build_small_jixiebi(n; ks1=80.0, restlens1=0.050, - ks2=1.00, restlens2=0.1, - kc=1.20, restlenc=0.160, pre=383.65, +function build_small_jixiebi(n; ks1=8.0, restlens1=0.018007, + ks2=1.00, restlens2=0.08, + # kc=8.00, restlenc=0.160, pre=520.0-0.35, + # kc=4.00, restlenc=0.160, pre=480.0-0.35, + kc=2.0, restlenc=0.14, pre=57.6343395, delta=-0.02) @@ -334,10 +336,10 @@ function build_small_jixiebi(n; ks1=80.0, restlens1=0.050, r̄g2 = [0.0, 0.0, 0.0] r̄g3 = [0.0, 0.0, 0.0] r̄g4 = [0.0, 0.0, 0.0] - m1 = 0.85 - m2 = 0.05 - m3 = 1.0 - m4 = 0.15 + m1 = 0.85 + m2 = 0.05 + m3 = 1.0 + m4 = 0.15 i1 = [4575.03 0 0; 0 5114.84 0; 0 0 4575.03] / scale i2 = [372.01 0 0; 0 358.79 0; 0 0 372.01] / scale @@ -395,10 +397,11 @@ function build_small_jixiebi(n; ks1=80.0, restlens1=0.050, [len42, r2 * sqrt(3) / 2, -r2 / 2], [len42, -r2 * sqrt(3) / 2, -r2 / 2]] - mesh1 = load(RB.assetpath("jixiebi/m1.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale) - mesh2 = load(RB.assetpath("jixiebi/m2.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale) - mesh3 = load(RB.assetpath("jixiebi/m3.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale) - mesh4 = load(RB.assetpath("jixiebi/m4.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale) + rigid_color = :darkgreen + mesh1 = load(RB.assetpath("jixiebi/m1.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale, color=rigid_color) + mesh2 = load(RB.assetpath("jixiebi/m2.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale, color=rigid_color) + mesh3 = load(RB.assetpath("jixiebi/m3.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale, color=rigid_color) + mesh4 = load(RB.assetpath("jixiebi/m4.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6), scale=1 / scale, color=rigid_color) rd1 = RigidData(r̄g1, m1, i1, r̄l1, mesh1) rd2 = RigidData(r̄g2, m2, i2, r̄l2, mesh2) @@ -483,8 +486,8 @@ function build_small_jixiebi(n; ks1=80.0, restlens1=0.050, sin(theta) cos(theta) 0; 0 0 1] r̄g = [0.0 0.0 0.0] - m = 0.1 - I = [1.0 0 0; 0 1.0 0; 0 0 1.0] + m = 10.0 + I = [100.0 0 0; 0 100.0 0; 0 0 100.0] nrp = length(aps) ṙo = zeros(3) ω = zeros(Float64, 3) @@ -507,8 +510,92 @@ function build_small_jixiebi(n; ks1=80.0, restlens1=0.050, sphere_mesh = simple_mesh |> RB.simple2mesh rb = RB.RigidBody(prop, state, coords, sphere_mesh) end + function rigidCylinder(pos, radius, halflen, thetaX, thetaY, thetaZ, id) + contactable = false + visible = true + ci = Int[] + Φi = collect(1:6) + + ri = pos + aps = [[radius halflen 0.0] for _ in 1:20] + # INFO 2: 第一个aps保留这个物体的特征长度,其他的aps备用 + α = [cos(thetaZ) -sin(thetaZ) 0; + sin(thetaZ) cos(thetaZ) 0; + 0 0 1] * [cos(thetaY) 0 sin(thetaY); + 0 1 0; + -sin(thetaY) 0 cos(thetaY)] * [1 0 0; + 0 cos(thetaX) -sin(thetaX); + 0 sin(thetaX) cos(thetaX)] + @show α + r̄g = [0.0 0.0 0.0] + m = 10.0 + I = [1.0 0 0; 0 1.0 0; 0 0 1.0] + nrp = length(aps) + ṙo = zeros(3) + ω = zeros(Float64, 3) + prop = RB.RigidBodyProperty( + id, + contactable, + m, + SMatrix{3,3}(I), + SVector{3}(r̄g), + [SVector{3}(aps[i]) for i in 1:nrp]; + visible + ) + ro = SVector{3}(ri) + + state = RB.RigidBodyState(prop, ri, α, ṙo, ω) + nmcs = RB.NCF.NC1P3V(SVector{3}(ri)) + coords = RB.NonminimalCoordinates(nmcs, ci, Φi) + p1 = Meshes.Plane((halflen, 0.0, 0.0), (1.0, 0.0, 0.0)) + p2 = Meshes.Plane((-halflen, 0.0, 0.0), (1.0, 0.0, 0.0)) + sphere = Meshes.CylinderSurface(p1, p2, radius) + simple_mesh = Meshes.discretize(sphere, Meshes.RegularDiscretization(30, 30)) + sphere_mesh = simple_mesh |> RB.simple2mesh + rb = RB.RigidBody(prop, state, coords, sphere_mesh) + end + function rigidCube(pos, hxyz, id) + contactable = false + visible = true + ci = Int[] + Φi = collect(1:6) + + ri = pos + aps = [hxyz for _ in 1:10] + # INFO 2: 第一个aps保留这个物体的特征长度,其他的aps备用 + theta = 0 + α = [cos(theta) -sin(theta) 0; + sin(theta) cos(theta) 0; + 0 0 1] + r̄g = [0.0 0.0 0.0] + m = 10.0 + I = [100.0 0 0; 0 100.0 0; 0 0 100.0] + nrp = length(aps) + ṙo = zeros(3) + ω = zeros(Float64, 3) + prop = RB.RigidBodyProperty( + id, + contactable, + m, + SMatrix{3,3}(I), + SVector{3}(r̄g), + [SVector{3}(aps[i]) for i in 1:nrp]; + visible + ) + ro = SVector{3}(ri) + + state = RB.RigidBodyState(prop, ri, α, ṙo, ω) + nmcs = RB.NCF.NC1P3V(SVector{3}(ri)) + coords = RB.NonminimalCoordinates(nmcs, ci, Φi) + cube = Meshes.Box((-hxyz[1], -hxyz[2], -hxyz[3]), (hxyz[1], hxyz[2], hxyz[3])) + simple_mesh = Meshes.discretize(cube, Meshes.RegularDiscretization(30, 30)) + sphere_mesh = simple_mesh |> RB.simple2mesh + rb = RB.RigidBody(prop, state, coords, sphere_mesh) + end rbs1 = [rigidbody(i, rds[i], r̄s[i]) for i in 1:nb] - rbs2 = [rigidSphere([1.8, 0.0, -0.45], 0.2, length(rbs1) + 1)] + # rbs2 = [rigidCube([1.05, 0.0, -0.55], [0.4, 0.4, 0.4], length(rbs1)+1)] + rbs2 = [rigidSphere([0.65, 0.0, -0.55], 0.4, length(rbs1) + 1)] + # rbs2 = [rigidCylinder([1.05, 0.0, -0.5], 0.3, 1.2, 0.0, pi/6, pi/2, length(rbs1) + 1)] rbs = vcat(rbs1, rbs2) # rbs = vcat(rbs, [rigidbody(nb+1, rds[nb], r̄s[nb])]) @@ -520,10 +607,10 @@ function build_small_jixiebi(n; ks1=80.0, restlens1=0.050, restlens1 = restlens1 ks2 = ks2 restlens2 = restlens2 - spring_dampers = [(i <= 12n) ? RB.DistanceSpringDamper3D(restlens1, ks1, 0.02) : RB.DistanceSpringDamper3D(restlens2, ks2, 0.02) for i in 1:nstrings] + spring_dampers = [(i <= 12n) ? RB.DistanceSpringDamper3D(restlens1, ks1, 0.2) : RB.DistanceSpringDamper3D(restlens2, ks2, 0.2) for i in 1:nstrings] restlencs = zeros(Float64, 5n - 1) - restlenc1 = 266.77 / scale + restlenc1 = 256.77 / scale for i in 1:5n-1 if (mod(i, 5) == 0) restlencs[i] = restlenc1 @@ -605,6 +692,7 @@ function build_small_jixiebi(n; ks1=80.0, restlens1=0.050, connecting_cluster_matrix = [reduce(vcat, matrix_cnt_raw[k]) for k in 1:ncluster] cables, clusters = RB.connect_spring_and_clusters(bodies, spring_dampers, cluster_sps, cluster_segs, connecting_matrix, connecting_cluster_matrix, istart=ncluster + 1) cst1 = RB.FixedBodyConstraint(ncluster + 1, rbs[1]) + cst2 = RB.FixedBodyConstraint(77, rbs[14]) apparatuses = TypeSortedCollection(vcat([cst1], cables, clusters)) indexed = RB.index(bodies, apparatuses;) @@ -787,7 +875,7 @@ function build_4_jixiebis(n; ks1=80.0, restlens1=0.050, end # theta = 0 - theta2 = -pi/6 + theta2 = -pi/4 α2 = [cos(theta2) 0 -sin(theta2) ; 0 1 0; sin(theta2) 0 cos(theta2)] @@ -862,7 +950,7 @@ function build_4_jixiebis(n; ks1=80.0, restlens1=0.050, rbs2 = [rigidbody(i + nb, rds[i], r̄s[i], pi / 4, [0.45, 0.45, 0.05]) for i in 1:nb] rbs3 = [rigidbody(i + 2nb, rds[i], r̄s[i], 3pi/4, [-0.45, 0.45, 0.05]) for i in 1:nb] rbs4 = [rigidbody(i + 3nb, rds[i], r̄s[i], -3pi / 4, [-0.45, -0.45, 0.05]) for i in 1:nb] - rbs5 = [rigidSphere([0.0, 0.0, -1.7], 1.6, 4nb+1)] + rbs5 = [rigidSphere([0.0, 0.0, -1.0], 1.0, 4nb+1)] rbs = vcat(rbs1, rbs2, rbs3, rbs4, rbs5) # rbs = vcat(rbs, [rigidbody(nb+1, rds[nb], r̄s[nb])]) diff --git a/jixiebi2.jl b/jixiebi2.jl new file mode 100644 index 0000000..e69de29 diff --git a/src/control/actuators.jl b/src/control/actuators.jl index 99214b4..9edc267 100644 --- a/src/control/actuators.jl +++ b/src/control/actuators.jl @@ -97,13 +97,10 @@ function generalized_force_jacobian!(∂F∂u, structure::Structure,actuator::Ex ∂F∂u .= transpose(C)*force end -#DONE? 重要的地方 function execute!(structure::Structure,actuator::ExternalForceActuator{<:Apparatus{<:ClusterJoint},<:NaiveOperator},u) (;id,signifier,operator,force) = actuator (;state) = structure - (;t) = state.system segs = signifier.force - #用驱动量u和joint的相关变量和参数, 计算驱动力, 加到系统中 segs[1].force.state.restlen = segs[1].force.original_restlen - u[1] end diff --git a/src/mechanics/contact.jl b/src/mechanics/contact.jl index 78aef16..bbbafb0 100644 --- a/src/mechanics/contact.jl +++ b/src/mechanics/contact.jl @@ -7,7 +7,7 @@ end function Contact(id,μ,e) active = false - persistent = true + persistent = false i = one(μ) o = zero(μ) gap = i @@ -62,10 +62,29 @@ abstract type ContactRigid end mutable struct RigidSphere{T} <: ContactRigid bid::T pid::T + init_pid::T end function RigidSphere(id) - return RigidSphere(id, one(id)) + return RigidSphere(id, one(id), one(id)) end +mutable struct RigidCylinder{T} <: ContactRigid + bid::T + pid::T + init_pid::T +end +function RigidCylinder(id) + return RigidCylinder(id, one(id), one(id)) +end +mutable struct RigidCube{T} <: ContactRigid + bid::T + pid::T + init_pid::T +end +function RigidCube(id) + return RigidCube(id, one(id), one(id)) +end + + abstract type StaticContactEnvironment <: AbstractContactEnvironment end struct StaticContactSurfaces{surfacesType} <: StaticContactEnvironment surfaces::surfacesType @@ -180,11 +199,6 @@ function contact_gap_and_normal(x::AbstractVector,p::Sphere) (; r, radius) = p gap = norm(x-r) - radius normal = (x-r)/norm(x-r) - # if gap < 0 - # @show gap, normal, x, r - # @show x-r - # @show norm(x-r) - # end gap, normal end @@ -263,12 +277,14 @@ function contact_gap_and_normal(x::AbstractVector, contact_bodies::Vector{<:Cont ncb = length(contact_bodies) gaps = zeros(Float64, ncb) normals = Vector{SVector{3,Float64}}(undef, ncb) + local_poss = Vector{SVector{3,Float64}}(undef, ncb) contact_ids = Vector{Int}(undef, ncb) for (i, contact) in enumerate(contact_bodies) if isa(contact, RigidSphere) (; bid) = contact foreach(bodies) do body if (body.prop.id == bid) + (;X) = body.state.origin_frame.axes r = body.state.origin_frame.position radius = body.prop.loci[1].position[1] gap = norm(x - r) - radius @@ -276,26 +292,82 @@ function contact_gap_and_normal(x::AbstractVector, contact_bodies::Vector{<:Cont gaps[i] = gap normals[i] = normal contact_ids[i] = i + local_poss[i] = inv(X)*(x - r) + end + end + elseif isa(contact, RigidCylinder) + (; bid) = contact + foreach(bodies) do body + if (body.prop.id == bid) + (;X) = body.state.origin_frame.axes + rc = body.state.origin_frame.position + p = x - rc + px, py, pz = inv(X) * p + radius = body.prop.loci[1].position[1] + halflen = body.prop.loci[1].position[2] + if abs(px) > halflen + gap = 1.0 + normal = SVector(1.0, 0.0, 0.0) + elseif norm(SVector(py, pz)) > radius + gap = 1.0 + normal = SVector(1.0, 0.0, 0.0) + else + gap = norm(SVector(py, pz)) - radius + normal = X*SVector(0.0, py, pz) + end + if gap < 0 + @show gap + end + gaps[i] = gap + normals[i] = normal / norm(normal) + contact_ids[i] = i + local_poss[i] = SVector(px, py, pz) + end + end + elseif isa(contact, RigidCube) + (; bid) = contact + foreach(bodies) do body + if (body.prop.id == bid) + (;X) = body.state.origin_frame.axes + rc = body.state.origin_frame.position + p = x - rc + px, py, pz = inv(X) * p + hx, hy, hz= body.prop.loci[1].position + if (abs(px) > hx) || (abs(py) > hy) || (abs(pz) > hz) + gap = 1.0 + normal = SVector(1.0, 0.0, 0.0) + else + normal_vector = [SVector(1.0, 0.0, 0.0), + SVector(-1.0, 0.0, 0.0), + SVector(0.0, 1.0, 0.0), + SVector(0.0, -1.0, 0.0), + SVector(0.0, 0.0, 1.0), + SVector(0.0, 0.0, -1.0)] + gap_vector = [hx-px, px+hx, hy-py, py+hy, hz-pz, pz+hz] + min_idx = argmin(gap_vector) + gap = - gap_vector[min_idx] + normal = X*normal_vector[min_idx] + # @show px, py, pz + # @show gap + end + gaps[i] = gap + normals[i] = normal + contact_ids[i] = i + local_poss[i] = SVector(px, py, pz) end end end - # gap, normal = contact_gap_and_normal(x, contact, bodies) - # gaps[i] = gap - # normals[i] = normal - # contact_ids[i] = i - # INFO 1: 不能写成上面的形式,感觉应该是TypeSortedCollections的原因 end if all(gaps .< 0) icb = argmax(gaps) contact_bodies[icb].pid += 1 - return gaps[icb], normals[icb], contact_ids[icb] + return gaps[icb], normals[icb], contact_ids[icb], local_poss[icb] else idx = findall((x) -> x >= 0, gaps) positive_gaps = @view gaps[idx] positive_normals = @view normals[idx] positive_contact_body_ids = @view contact_ids[idx] icb = argmin(positive_gaps) - return positive_gaps[icb], positive_normals[icb], positive_contact_body_ids[icb] + return positive_gaps[icb], positive_normals[icb], positive_contact_body_ids[icb], local_poss[icb] end - end diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index 401e583..66c3728 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -141,7 +141,7 @@ function activate_frictional_contacts!(structure,contact_env::ContactRigidBodies nq = length(q) na = 0 for contact in contact_bodies - contact.pid = 1 + contact.pid = contact.init_pid # INFO 3: 第一个loci不动,从第二个开始 end update_bodies!(structure,q) @@ -151,27 +151,17 @@ function activate_frictional_contacts!(structure,contact_env::ContactRigidBodies bid = prop.id contacts_bits[bodyid2sys_loci_idx[bid]] .= false persistent_bits[bodyid2sys_loci_idx[bid]] .= false - for contact in contact_bodies - if contact.bid == bid - for locus in body.state.loci_states - locus.contact_state.active = false - end - end - end - # INFO 4: 重置所有的contact_state end foreach(structure.bodies) do body (;prop,state) = body bid = prop.id (;loci_states) = state - # contacts_bits[bodyid2sys_loci_idx[bid]] .= false - # persistent_bits[bodyid2sys_loci_idx[bid]] .= false if body.prop.contactable for pid in eachindex(loci_states) locus_state = loci_states[pid] (;frame,contact_state) = locus_state - gap, normal, cid = contact_gap_and_normal(frame.position,contact_bodies,bodies) + gap, normal, cid, local_pos = contact_gap_and_normal(frame.position,contact_bodies,bodies) if !checkpersist contact_state.active = false end @@ -179,28 +169,54 @@ function activate_frictional_contacts!(structure,contact_env::ContactRigidBodies if contact_state.active contacts_bits[bodyid2sys_loci_idx[bid][pid]] = true contact_state.axes = spatial_axes(normal) - contacts_bits[bodyid2sys_loci_idx[contact_bodies[cid].bid][contact_bodies[cid].pid]] = true - persistent_bits[bodyid2sys_loci_idx[contact_bodies[cid].bid][contact_bodies[cid].pid]] = true + if contact_state.persistent + persistent_bits[bodyid2sys_loci_idx[bid][pid]] = true + end foreach(bodies) do ibody if ibody.prop.id == contact_bodies[cid].bid - activate!(ibody.state.loci_states[contact_bodies[cid].pid].contact_state, gap) - ibody.state.loci_states[contact_bodies[cid].pid].contact_state.axes = spatial_axes(-normal) - nmcs = ibody.coords.nmcs + icontact_state = ibody.state.loci_states[contact_bodies[cid].pid].contact_state + ibid = contact_bodies[cid].bid + ipid = contact_bodies[cid].pid + activate!(icontact_state, gap) + contacts_bits[bodyid2sys_loci_idx[ibid][ipid]] = true + icontact_state.axes = spatial_axes(-normal) + + (;axes, friction_coefficient, restitution_coefficient) = ibody.prop.loci[ipid] + ibody.prop.loci[ipid] = Locus(local_pos, axes, friction_coefficient, restitution_coefficient) + ibody.state.loci_states[ipid].frame.position = frame.position + (;nmcs) = ibody.coords + ncoords = get_num_of_coords(nmcs) + iq = @MVector zeros(ncoords) c(x) = NCF.to_local_coords(nmcs,x) - C(c) = NCF.to_position_jacobian(nmcs,q,c) - ibody.cache.Cps[contact_bodies[cid].pid] = C(c(frame.position)) - # INFO 5: 更新Cps,这里的q当前的q。 + C(c) = NCF.to_position_jacobian(nmcs,iq,c) + + ibody.cache.Cps[ipid] = C(c(local_pos)) + + if icontact_state.persistent + persistent_bits[bodyid2sys_loci_idx[ibid][ipid]] = true + end end end - if contact_state.persistent - persistent_bits[bodyid2sys_loci_idx[bid][pid]] = true - end na += 2 # INFO 6: 一个碰撞对应两个na end end end end + + foreach(structure.bodies) do body + (;prop) = body + bid = prop.id + for contact in contact_bodies + if contact.bid == bid + ipid = contact.pid + for locus in body.state.loci_states[ipid+1:end] + locus.contact_state.active = false + end + end + end + end + inv_friction_coefficients = ones(T,3na) for (i,μ) in enumerate(μs_sys[contacts_bits]) inv_friction_coefficients[3(i-1)+1] = 1/μ diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index e5243c3..1f0f4a2 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -69,7 +69,7 @@ end function make_step_k( solver_cache::Zhong06_CCP_Constant_Mass_Cluster_Cables_Cache, nq,nλ,ns,na, - qₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁, + qₖ₋₁,sₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁, pₖ,vₖ, invM, h,mass_norm) @@ -89,15 +89,15 @@ function make_step_k( contact_cache, timestep,iteration,doin=true ) - # @show timestep, iteration, na qₖ = @view x[ 1:n1] λₘ = @view x[n1+1:n2] sₖ = @view x[nq+nλ+1:nx] qₘ = (qₖ.+qₖ₋₁)./2 + sₘ = (sₖ.+sₖ₋₁)./2 q̇ₘ = (qₖ.-qₖ₋₁)./h vₘ = q̇ₘ tₘ = tₖ₋₁+h/2 - F!(Fₘ,qₘ,sₖ,q̇ₘ,tₘ) + F!(Fₘ,qₘ,sₘ,q̇ₘ,tₘ) Jac_F!(∂F∂q,∂F∂q̇,qₘ,q̇ₘ,tₘ) Aₖ₋₁ = A(qₖ₋₁) @@ -117,7 +117,9 @@ function make_step_k( n = length(ζ) ∂s̄∂s̄ = I(n) ∂F∂s̄ = build_∂Q̌∂s̄(structure) - κ₁ = 10; κ₂ = 10 + κ₁ = 10; κ₂ = 100 + cosₘ = 1/2 + coqₘ = 1/2 coes = diagm([((ζ[i]/κ₁)^2 + (κ₂*sₖ[i])^2)^(-1/2) for i in 1:n]) coζ = coes*diagm([ζ[i]/κ₁^2 for i in 1:n]) - diagm([1/κ₁ for i in 1:n]) cos̄ = coes*diagm([κ₂^2*sₖ[i] for i in 1:n]) - diagm([κ₂ for i in 1:n]) @@ -125,15 +127,15 @@ function make_step_k( 𝐉 .= 0.0 𝐉[ 1:nq , 1:nq ] .= M.-(h^2)/2 .*(1/2 .*∂F∂q.+1/h.*∂F∂q̇) 𝐉[ 1:nq ,nq+1:nq+nλ] .= mass_norm.*transpose(Aₖ₋₁) - 𝐉[ 1:nq ,nq+nλ+1:end] .= -1/2 * h^2 .* ∂F∂s̄ + 𝐉[ 1:nq ,nq+nλ+1:end] .= -1/2 * h^2 .* ∂F∂s̄ * cosₘ 𝐉[nq+1:nq+nλ, 1:nq ] .= mass_norm.*Aₖ 𝐉[nq+1:nq+nλ, nq+1:nq+nλ ] .= 0.0 𝐉[nq+1:nq+nλ, nq+nλ+1:end ] .= 0.0 - 𝐉[nq+nλ+1:end,1:nq] .= 1/2 * coζ*∂ζ∂q + 𝐉[nq+nλ+1:end,1:nq] .= coqₘ * coζ*∂ζ∂q 𝐉[nq+nλ+1:end,nq+1:nq+nλ] .= 0.0 - 𝐉[nq+nλ+1:end,nq+nλ+1:end] .= coζ*∂ζ∂s̄ + cos̄*∂s̄∂s̄ + 𝐉[nq+nλ+1:end,nq+nλ+1:end] .= coζ*∂ζ∂s̄*cosₘ + cos̄*∂s̄∂s̄ lu𝐉 = lu(𝐉) @@ -176,22 +178,11 @@ function make_step_k( 𝐜ᵀ[is+1:is+3, 1:n1] .+= ∂v́⁺∂qₖ[is+1:is+3,:] 𝐜ᵀ[is+1:is+3,n1+1:n2] .= Dⁱₖ*∂vₖ∂λₘ end - if timestep == 3092 - ## @show v́⁺, (v́⁺+𝐛), α - ## @show 𝐜ᵀ - ## @show vₙⁱₖ₋₁, restitution_coefficients - ## @show restitution_coefficients[i]*min(vₙⁱₖ₋₁,0) - end # 𝐜ᵀinv𝐉 = 𝐜ᵀ*inv(𝐉) 𝐲 .= (v́⁺ + 𝐛) end end lu𝐉 - # debug - # @show norm(D*vₖ + 𝐛), norm(𝐫𝐞𝐬) - # @show Λₖ, D*vₖ, 𝐛 - # @show Λₖ[1:3]⋅(D*vₖ + 𝐛)[1:3] - end ns_stepk! end @@ -280,7 +271,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C ns_stepk! = make_step_k( solver_cache, nq,nλ,ns,na, - qₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁, + qₖ₋₁,sₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁, pₖ,q̇ₖ, invM, dt,mass_norm @@ -295,14 +286,6 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C Λʳₖ .= Λₖ Nmax = maxiters for iteration = 1:maxiters - if timestep == 3092 - ## @show L - # @show timestep, iteration - ## @show 𝐍 - @show iteration - # @show qr(L).R |> diag - ## @show :befor, size(𝐍), rank(𝐍), cond(𝐍) - end luJac = ns_stepk!( Res,Jac, F,∂F∂q,∂F∂q̇, diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl index 6f7ada7..285cd11 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl @@ -13,7 +13,7 @@ function generate_cache( (;bot,policy) = prob (;traj,structure) = bot options = merge( - (gravity=true,factor=1,checkpersist=true), #default + (gravity=false,factor=1,checkpersist=true), #default prob.options, solver.options, ) @@ -78,15 +78,16 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache mass_norm = mr h = dt T = get_numbertype(bot) - function make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ,qₖ₋₁,p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) + function make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ,qₖ₋₁,sₖ₋₁, p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) @inline @inbounds function inner_Res_stepk!(Res,x) q̌ₖ .= x[ 1:nq̌ ] λₖ .= x[nq̌+1:nq̌+nλ] sₖ .= x[nq̌+nλ+1:nx] qₘ = (qₖ.+qₖ₋₁)./2 + sₘ = (sₖ.+sₖ₋₁)./2 q̇ₘ = (qₖ.-qₖ₋₁)./h tₘ = tₖ₋₁+h/2 - F!(F̌,qₘ, sₖ, q̇ₘ, tₘ) + F!(F̌,qₘ, sₘ, q̇ₘ, tₘ) Res[ 1:nq̌ ] .= Ḿ*(qₖ.-qₖ₋₁) .- h.*p̌ₖ₋₁ .- (h^2)/2 .*F̌ .+ @@ -96,12 +97,13 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache end end - function Jac_stepk!(Jac,x,qₖ,sₖ,q̌ₖ,qₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) + function Jac_stepk!(Jac,x,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁, ∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) q̌ₖ .= x[1:nq̌] sₖ .= x[nq̌+nλ+1:end] qₘ = (qₖ.+qₖ₋₁)./2 q̇ₘ = (qₖ.-qₖ₋₁)./h tₘ = tₖ₋₁+h/2 + sₘ = (sₖ.+sₖ₋₁)./2 Jac_F!(∂F∂q̌,∂F∂q̌̇,qₘ,q̇ₘ,tₘ) ζ = build_ζ(bot.structure) ∂ζ∂q = build_∂ζ∂q(bot.structure) @@ -109,22 +111,24 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache n = length(ζ) ∂s̄∂s̄ = I(n) ∂F∂s̄ = build_∂Q̌∂s̄(bot.structure) - κ₁ = 10; κ₂ = 10 + κ₁ = 10; κ₂ = 100 + cosₘ = 1/2 + coqₘ = 1/2 coes = diagm([((ζ[i]/κ₁)^2 + (κ₂*sₖ[i])^2)^(-1/2) for i in 1:n]) coζ = coes*diagm([ζ[i]/κ₁^2 for i in 1:n]) - diagm([1/κ₁ for i in 1:n]) cos̄ = coes*diagm([κ₂^2*sₖ[i] for i in 1:n]) - diagm([κ₂ for i in 1:n]) Jac[ 1:nq̌ , 1:nq̌ ] .= M̌.-(h^2)/2 .*(1/2 .*∂F∂q̌.+1/h.*∂F∂q̌̇) Jac[ 1:nq̌ ,nq̌+1:nq̌+nλ] .= mass_norm.*Aᵀₖ₋₁ - Jac[ 1:nq̌ ,nq̌+nλ+1:end] .= -1/2 * dt^2 .* ∂F∂s̄ + Jac[ 1:nq̌ ,nq̌+nλ+1:end] .= -1/2 * h^2 .* ∂F∂s̄ * cosₘ Jac[nq̌+1:nq̌+nλ, 1:nq̌ ] .= mass_norm.*A(qₖ) Jac[nq̌+1:nq̌+nλ, nq̌+1:nq̌+nλ ] .= 0.0 Jac[nq̌+1:nq̌+nλ, nq̌+nλ+1:end ] .= 0.0 - Jac[nq̌+nλ+1:end,1:nq̌] .= 1/2 * coζ*∂ζ∂q + Jac[nq̌+nλ+1:end,1:nq̌] .= coζ*∂ζ∂q*coqₘ Jac[nq̌+nλ+1:end,nq̌+1:nq̌+nλ] .= 0.0 - Jac[nq̌+nλ+1:end,nq̌+nλ+1:end] .= coζ*∂ζ∂s̄ + cos̄*∂s̄∂s̄ + Jac[nq̌+nλ+1:end,nq̌+nλ+1:end] .= coζ*∂ζ∂s̄*cosₘ + cos̄*∂s̄∂s̄ end iteration_break = 0 @@ -157,7 +161,7 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache xₖ[nq̌+1:nq̌+nλ] .= 0 xₖ[nq̌+nλ+1:nx] .= sₖ₋₁ Aᵀₖ₋₁ = transpose(A(qₖ₋₁)) - Res_stepk! = make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ₋₁,qₖ₋₁,p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) + Res_stepk! = make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ,qₖ₋₁,sₖ₋₁,p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) isconverged = false normRes = typemax(T) if false#Jac_F! isa Missing @@ -177,13 +181,18 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache break end # FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) - Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) + Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) xₖ .+= Jac\(-Res) end # dfk = OnceDifferentiable(Res_stepk!,Jac_stepk!,xₖ,Res) end if !isconverged + Res_stepk!(Res,xₖ) + Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) + write("j1.bin", Jac) + FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) + write("j2.bin", Jac) if exception error("Not Converged! Step=$timestep, normRes=$normRes") else diff --git a/src/members/forces/spring_dampers.jl b/src/members/forces/spring_dampers.jl index f004f34..6e6212a 100644 --- a/src/members/forces/spring_dampers.jl +++ b/src/members/forces/spring_dampers.jl @@ -278,7 +278,6 @@ struct ClusterDistanceSpringDampers{spsType,segsType} end function ClusterDistanceSpringDampers(segs; μ=0.0) - @show 11 nsp = length(segs) - 1 sps = StructArray([SlidingPoint(μ) for i = 1:nsp]) ClusterDistanceSpringDampers(sps, segs) diff --git a/src/members/loci.jl b/src/members/loci.jl index 719f934..b75c609 100644 --- a/src/members/loci.jl +++ b/src/members/loci.jl @@ -267,7 +267,7 @@ function update_contacts!(loci, loci_previous, v, Λ) rel_vel_split = split_by_lengths(v,3) forces_split = split_by_lengths(Λ,3) for (ac,acp,va,Λa) in zip(loci, loci_previous, rel_vel_split,forces_split) - if acp.state.active + if acp.state.active # == ac.state.active ac.state.persistent = true end ac.state.active = true diff --git a/src/postprocess/vis.jl b/src/postprocess/vis.jl index c5c6dd7..ad01b5c 100644 --- a/src/postprocess/vis.jl +++ b/src/postprocess/vis.jl @@ -21,7 +21,7 @@ MakieCore.@recipe(Viz, structure) do scene refcolor=:lightgrey, cablewidth=0.6, meshcolor=:slategrey, - fontsize = 12, + fontsize = 15, ) end @@ -125,11 +125,12 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; # slackonly=false, # noslackonly=true linestyle_ob = lift(cable_appar_ob) do cab - if cab.force.state.length > cab.force.state.restlen - return :solid - else - return viz.slack_linestyle[] - end + # if cab.force.state.length > cab.force.state.restlen + # return :solid + # else + # return viz.slack_linestyle[] + # end + return :solid end MakieCore.linesegments!( @@ -197,7 +198,7 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; (;num_of_bodies,) = connectivity.indexed cable_apparatuses_ob = lift(tgob) do tgob filter(sort(tgob.apparatuses)) do appar - appar.joint isa Union{CableJoint, ClusterJoint} + appar.joint isa Union{CableJoint, ClusterJoint} end end diff --git a/src/structures/structure.jl b/src/structures/structure.jl index f01af77..6e5c01d 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -425,7 +425,7 @@ function build_ψ(structure::AbstractStructure) (;apparatuses) = structure nclustercables = 0 ns = 0 - FB = FischerBurmeister(1e-14, 10., 10.) + FB = FischerBurmeister(1e-14, 10., 100.) foreach(apparatuses) do appar if isa(appar, Apparatus{<:ClusterJoint}) nclustercables += 1 diff --git a/test/vis.jl b/test/vis.jl index 1b156fc..b8c08d5 100644 --- a/test/vis.jl +++ b/test/vis.jl @@ -251,9 +251,11 @@ function plot_traj!(bot::RB.Robot; showinfo = false # ax = LScene(fig[1,1], show_axis=false, scenekw = (clear=true,)) ax = LScene(fig[1,1],) # - # cam = Makie.camera(ax.scene) - # cam = cam3d!(ax.scene, projectiontype=Makie.Orthographic) - # update_cam!(ax.scene, cam) + cam = Makie.camera(ax.scene) + cam = cam3d!(ax.scene, projectiontype=Makie.Orthographic) + update_cam!(ax.scene, cam, pi/2, pi/8) + + # update_cam!(ax.scene, cam, pi/5, pi/12) # ax = LScene(fig[1,1],show_axis=false) # # scale = 1e3 # m0_yellow = load("yard/jixiebi/m0_yellow.STL") |> RB.make_patch(;rot=RotY(pi/2),trans=[-0.50, 0.0, 0.8],scale=1/scale,color=:yellow) diff --git a/yard/jixiebi/CA.jl b/yard/jixiebi/CA.jl new file mode 100644 index 0000000..e50db7c --- /dev/null +++ b/yard/jixiebi/CA.jl @@ -0,0 +1,191 @@ +using TestEnv +TestEnv.activate() + +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/tensegrity.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = joinpath(pathof(RB),"../../tmp") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl + +dt = 1e-2 + +policy = RB.TimePolicy( + @eponymtuple( + # f = (t) -> [0.0, t<3 ? 3t : 3, t<3 ? 3t : 3] + f = (t) -> [0.0, 0.0, 0.0] + ) +) +policy2 = RB.TimePolicy( + @eponymtuple( + f = (t) -> [0.0, 0.1t, 0.1t] + # f = (t) -> [0.0, 0.0, 0.0] + ) +) + +rigid_contacts = RB.ContactRigidBodies( + [ + RB.RigidSphere(18) + ] +) + +θ=0.0 +ground_plane = RB.StaticContactSurfaces( + [ + # RB.HalfSpace([-tan(θ),0,1],[0.0,0.0,-150.0]), + RB.Sphere(0.400, [2.2000,0.0,-0.50-1e-3 ]) + ] +); +restitution_coefficients = 0.5 +friction_coefficients = 0.1 +bot_small = build_small_jixiebi(2) +RB.solve!( + RB.DynamicsProblem( + bot_small,policy2, + # ground_plane, + # RB.RestitutionFrictionCombined( + # RB.NewtonRestitution(), + # RB.CoulombFriction(), + # ), + RB.EulerEytelwein(), + ), + RB.DynamicsSolver( + RB.Zhong06(), + # RB.InnerLayerContactSolver( + # RB.InteriorPointMethod() + # ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan=(0.0, 1.0), + dt, + ftol=1e-7,verbose=true, + maxiters=50 +) +plot_traj!(bot_small; + ground=ground_plane, + showground = false, + xlims=(-1.0, 4.0), + ylims = (-1.,1.), + zlims = (-2.,1.), + showlabels = false, + showpoints = false, +) + +bot_small_new = build_small_jixiebi(2) +RB.set_new_initial!(bot_small_new, bot_small.traj.q[end], bot_small.traj.q̇[end]) +RB.solve!( + RB.DynamicsProblem( + bot_small_new,policy2, + # ground_plane, + # RB.RestitutionFrictionCombined( + # RB.NewtonRestitution(), + # RB.CoulombFriction(), + # ), + RB.EulerEytelwein(), + ), + RB.DynamicsSolver( + RB.Zhong06(), + # RB.InnerLayerContactSolver( + # RB.InteriorPointMethod() + # ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan=(0.0, 1.0), + dt, + ftol=1e-7,verbose=true, + maxiters=50 +) +plot_traj!(bot_small_new; + ground=ground_plane, + showground = false, + xlims=(-1.0, 4.0), + ylims = (-1.,1.), + zlims = (-2.,1.), + showlabels = false, + showpoints = false, +) + + + +dts = [2e-3, 1e-3, 5e-4, 1e-4,1e-5] +pm_dts2 = [] +for dt in dts + push!(pm_dts2, RB.solve!( + RB.DynamicsProblem( + deepcopy(bot_small),policy2, + # ground_plane, + # rigid_contacts, + # RB.RestitutionFrictionCombined( + # RB.NewtonRestitution(), + # RB.CoulombFriction(), + # ), + RB.EulerEytelwein(), + ), + RB.DynamicsSolver( + RB.Zhong06(), + # RB.InnerLayerContactSolver( + # RB.InteriorPointMethod() + # ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan=(0.0, 1.0), + dt, + ftol= dt<1e-4 ? 1e-11 : 1e-8 ,verbose=true, + maxiters=50 + )[1].prob.bot) +end +# pm_dts = [RB.solve!( +# RB.DynamicsProblem( +# deepcopy(bot_small),policy, +# # ground_plane, +# # rigid_contacts, +# # RB.RestitutionFrictionCombined( +# # RB.NewtonRestitution(), +# # RB.CoulombFriction(), +# # ), +# RB.EulerEytelwein(), +# ), +# RB.DynamicsSolver( +# RB.Zhong06(), +# # RB.InnerLayerContactSolver( +# # RB.InteriorPointMethod() +# # ), +# RB.MonolithicApparatusSolver( +# RB.SmoothedFischerBurmeister() +# ), +# ); +# tspan=(0.0, 1.0), +# dt, +# ftol= dt<1e-3 ? 1e-9 : 1e-7 ,verbose=true, +# maxiters=50 +# )[1].prob.bot for dt in dts] + +fig = Figure() +ax = Axis(fig[1,1],ylabel = "Abs. Err.") +_,err_nmsi = RB.get_err_avg(pm_dts2[:];bid=8,pid=1,di=3) +# plot_convergence_order!(ax,dts[begin:end-1][2:end],err_nmsi[2:end];orders=[1, 2],label="NMSI") +plot_convergence_order!(ax,dts[begin:end-1],err_nmsi;orders=[1, 2],label="NMSI") +fig +savefig(fig, "../small_accurate_new") + +tr1 = RB.get_trajectory!(pm_dts[end], 16, 2) +fig = Figure() +ax = Axis(fig[1,1]) +for i in 1:3 + lines!(ax, [t[i] for t in tr1], label = "$(i)") +end +axislegend(ax) +fig diff --git a/yard/jixiebi/Group1.jl b/yard/jixiebi/Group1.jl index 0726e7f..3343796 100644 --- a/yard/jixiebi/Group1.jl +++ b/yard/jixiebi/Group1.jl @@ -22,8 +22,8 @@ policy = RB.TimePolicy( @eponymtuple( #驱动量是且仅是时间的函数 # f = (t) -> reduce(vcat, [[0.0, 2t, 2t] for _ in 1:4]) - f = (t) -> reduce(vcat, [[0.0, 2t, 2t, 0.0, 0.5t, 0.5t] for _ in 1:2]) - # f = (t) -> [0.0, 0.0, 0.0] + # f = (t) -> reduce(vcat, [[0.0, 2t, 2t, 0.0, 0.5t, 0.5t] for _ in 1:2]) + f = (t) -> [0.0, 10t, 10t] ) ) @@ -32,7 +32,7 @@ policy = RB.TimePolicy( # ground_plane = RB.StaticContactSurfaces( # [ # # RB.HalfSpace([-tan(θ),0,1],[0.0,0.0,-150.0]), -# RB.Sphere(0.400, [2.2000,0.0,-0.50+1e-3 ]) +# RB.Sphere(0.400, [2.2000,0.0,-0.50+1e-3 ]) # ] # ); @@ -52,7 +52,7 @@ bot_4 = build_4_jixiebis(3) # RB.solve!( # RB.DynamicsProblem( -# bot_4,policy, +# bot,policy, # RB.EulerEytelwein(), # ), # RB.DynamicsSolver( @@ -61,7 +61,7 @@ bot_4 = build_4_jixiebis(3) # RB.SmoothedFischerBurmeister() # ), # ); -# tspan=(0.0,1.0), +# tspan=(0.0,0.2), # dt, # ftol=1e-7,verbose=true # ) @@ -87,7 +87,7 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 2.2), + tspan=(0.0, 3.0), dt, ftol=1e-7,verbose=true, maxiters=50 diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 317a931..0f1c619 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -1,76 +1,189 @@ -using LinearAlgebra -using SparseArrays -using StaticArrays -using BenchmarkTools -using FileIO, MeshIO -using Printf -using Makie -import GLMakie as GM -import CairoMakie as CM -GM.activate!() -using Unitful -using NLsolve -using Revise -using StructArrays -using EponymTuples -using LaTeXStrings -using StaticArrays -using GeometryBasics -using Rotations -using CoordinateTransformations -using Meshing -using TypeSortedCollections -using Match -import TensegrityRobots as TR -cd("docs/examples/jixiebi") -includet("define.jl") -includet("dyfun.jl") -includet("../vis.jl") - - -bot = build_jixiebi2(4) -plot_tg!(bot.tg) -prob1 = TR.SimProblem(bot,dynfuncs1) -dt = 1e-2; T = 9.0 - -TR.solve!(prob1,TR.FBZhong06(), - ( - actuate! = actuate1!, - prescribe! = nothing - ); - dt=dt,tspan=(0.0,T),ftol=1e-7,verbose=true) - -with_theme(theme_pub; -Axis3 = ( - azimuth = 3π/2, - elevation = 0.0, +using TestEnv +TestEnv.activate() + +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/tensegrity.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = joinpath(pathof(RB),"../../tmp") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl + + +dt = 2e-3 + +policy = RB.TimePolicy( + @eponymtuple( + f = (t) -> [0.0, 0.1t, 0.1t] + ) +) + +rigid_contacts = RB.ContactRigidBodies( + [ + # RB.RigidCylinder(14) + # RB.RigidCube(14) + RB.RigidSphere(14) + ] +) + +# parameters +restitution_coefficients = 0.5 +friction_coefficients = 0.1 +bot1 = build_small_jixiebi(3) +fig = plot_traj!(bot1; + # atsteps=[3320], + showground = false, + showlabels = false, + showpoints = false, + # doslide = false, +) + +RB.solve!( + RB.DynamicsProblem( + bot1,policy, + # ground_plane, + rigid_contacts, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ), + RB.EulerEytelwein(), + ), + RB.DynamicsSolver( + RB.Zhong06(), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan=(0.0, 5.0), + dt, + ftol=1e-7,verbose=true, + maxiters=50 +) + +with_theme(theme_pub; size=(2tw, 2tw), fontsize=20, + figure_padding = (5fontsize,5fontsize,1fontsize,1fontsize), + Axis3 = ( + azimuth = π/2, + elevation = pi/6, ), -Mesh = ( - # color = :black, - transparency = false, +)do + fig = plot_traj!(bot1; + # atsteps=[3320], + xlims = (-0.5, 3), + zlims = (-2, 0.5), + AxisType = Axis3, + showground = false, + showlabels = false, + showpoints = false, + showinfo = false, + # doslide = false, + ) +end + +for t in 0.0:5.0:30.0 + step = Int(t/dt)+1 +with_theme(theme_pub; size=(2tw, 2tw), fontsize=20, + figure_padding = (5fontsize,5fontsize,1fontsize,1fontsize), + Axis3 = ( + azimuth = π/2, + elevation = pi/8, ), ) do -plot_traj!(bot; - # AxisType=LScene, - # doslide=false, - doslide=true, - showinfo=false, - axtitle=false, - # hidezdecorations=true, - hideydecorations=true, - fontsize=10, - # gridsize=(2,2), - # attimes=[0.0,2.25,3.75,6.0], - # atsteps=nothing, - showground=false, - showlabels=false, - rigidcolor=:grey, - xlims=(-100,3500), - ylims=(-50,50), - zlims=(-1800,1800), -) + fig = plot_traj!(bot1; + AxisType=Axis3, + xlims = (-0.5, 3), + zlims = (-2, 0.5), + showground = false, + showlabels = false, + showpoints = false, + doslide = false, + atsteps = [step] + ) + savefig(fig, "../tg1_$(t).png") + end end -# traj_bot = bot.traj[1112] -# q_bot = bot.traj.q[1112] -# s_bot = bot.traj.s[1112] \ No newline at end of file + +pos_list = Vector{SVector{3}}() +vel_list = Vector{SVector{3}}() +contact_set = Set{Int}() +(;contacts_traj) = bot1 +for (id, ctraj) in enumerate(contacts_traj) + for cn in ctraj + if cn.state.active == true && cn.id < 144 + @show cn.id, cn.state.gap, norm(cn.state.force) + contact_set = union(contact_set, Set(cn.id)) + end + end +end +contact_set = collect(contact_set) +@show contact_set + +for step in 1:length(bot1.traj) + (;structure, traj, contacts_traj) = bot1 + structure.state.system.q .= traj.q[step] + structure.state.system.c .= traj.c[step] + structure.state.system.q̇ .= traj.q̇[step] + RB.update!(structure) + (;bodies) = structure + foreach(bodies) do body + if body.prop.id == 14 + push!(pos_list, body.state.origin_frame.position) + push!(vel_list, body.state.origin_frame.velocity) + end + end +end + +xt = 0:dt:5 +Poss = [[p[i] for p in pos_list] for i in 1:3] +Vels = [[v[i] for v in vel_list] for i in 1:3] +Fs = [[norm(c_traj[i].state.force) for c_traj in contacts_traj] for i in contact_set] +as = [[c_traj[i].state.active for c_traj in contacts_traj] for i in contact_set] +ps = [[c_traj[i].state.persistent for c_traj in contacts_traj] for i in contact_set] + +fig = Figure(fontsize=20, size=(1200, 800)) +ax1 = Axis(fig[1,1]) +ax2 = Axis(fig[1,2]) +lines!(ax1, xt, Poss[1], label="Direction x") +lines!(ax2, xt, Poss[3], label="Direction z") +ax4 = Axis(fig[2,1]) +ax5 = Axis(fig[2,2]) +lines!(ax4, xt, Vels[1], label="Direction x") +lines!(ax5, xt, Vels[3], label="Direction z") +for ax in [ax1, ax2] + ax.xlabel = "Time [s]" + ax.ylabel = "Position [m]" + axislegend(ax, position=:rt) +end +for ax in [ax4, ax5] + ax.xlabel = "Time [s]" + ax.ylabel = "Velocity [m/s]" + axislegend(ax, position=:rt) +end +fig +savefig(fig, "../position_velocity1.png" ) + +fig = Figure(fontsize=20, size=(1200, 800)) +ax1 = Axis(fig[1,1]) +n = 3 +for (id, f) in enumerate(Fs) + # lines!(ax1,xt[1+n:end-n],[(sum([f[j] for j in i-n:i+n]))/(2n+1) for i in n+1:length(f)-n],label="Node $(contact_set[id])") + # lines!(ax1, xt, as[1], label="activate $(contact_set[id])") + lines!(ax1, xt, ps[1], label="persistent $(contact_set[id])") + # lines!(ax1,xt,f, label="Node $(contact_set[id])") +end +ax1.xlabel = "Time [s]" +ax1.ylabel = "Λₙ" +axislegend(ax1, position=:lt) +fig +# savefig(fig, "../contact_force1.png" ) \ No newline at end of file diff --git a/yard/jixiebi/Group2_2.jl b/yard/jixiebi/Group2_2.jl index ce31d6c..6988656 100644 --- a/yard/jixiebi/Group2_2.jl +++ b/yard/jixiebi/Group2_2.jl @@ -1,51 +1,193 @@ -bot1 = deepcopy(bot) -q_bot = bot.traj.q[901] -s_bot = bot.traj.s[901] -bot1.tg.state.system.q̇ .= 0.0 -bot1.traj.q[1] .= q_bot -bot1.traj.s[1] .= s_bot -TR.update!(bot1.tg) -TR.update_orientations!(bot1.tg) - -plot_tg!(bot1.tg) - -prob2 = TR.SimProblem(bot1, dynfuncs1) -dt = 1e-2; T = 6.0 - -TR.solve!(prob2,TR.FBZhong06(), - ( - actuate! = actuate2!, - prescribe! = nothing - ); - dt=dt,tspan=(0.0,T),ftol=1e-7,verbose=true) - -with_theme(theme_pub; - Axis3 = ( - azimuth = 3π/2, - elevation = 0.0, - ), - Mesh = ( - # color = :black, - transparency = false, +using TestEnv +TestEnv.activate() + +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/tensegrity.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = joinpath(pathof(RB),"../../tmp") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl + + +dt = 1e-2 + +policy = RB.TimePolicy( + @eponymtuple( + # f = (t) -> [0.0, t<5 ? 0.1t : 0.5, t<5 ? 0.1t : 0.5] + # f = (t) -> [0.0, t<20 ? 0.1t : 2, t<20 ? 0.1t : 2] + # f = (t) -> [0.0, 0.1t, 0.1t] + f = (t) -> reduce(vcat, [[0.0, 0.1t, 0.1t] for _ in 1:4]) + # f = (t) -> [0.0, 0.0, 0.0] + ) +) + +rigid_contacts = RB.ContactRigidBodies( + [ + RB.RigidSphere(37) + ] +) + +# parameters +restitution_coefficients = 0.5 +friction_coefficients = 0.1 +bot2 = build_4_jixiebis(2) +RB.solve!( + RB.DynamicsProblem( + bot2,policy, + # ground_plane, + rigid_contacts, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ), + RB.EulerEytelwein(), ), - ) do -plot_traj!(bot1; - # AxisType=LScene, - # doslide=false, - doslide=true, - showinfo=false, - axtitle=false, - # hidezdecorations=true, - hideydecorations=true, - fontsize=10, - # gridsize=(2,2), - # attimes=[0.0,2.25,3.75,6.0], - # atsteps=nothing, - showground=false, - showlabels=false, - rigidcolor=:grey, - xlims=(-100,3500), - ylims=(-50,50), - zlims=(-1800,1800), + RB.DynamicsSolver( + RB.Zhong06(), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan=(0.0, 30.0), + dt, + ftol=1e-7,verbose=true, + maxiters=50 +) +with_theme(theme_pub;size = (2tw, 2tw), +fontsize=20, +figure_padding=(-10,-10,-10,0), +Axis3 = ( + azimuth = 1.0, + elevation = 0.2 ) -end \ No newline at end of file +) do + fig = plot_traj!(bot2; + # atsteps=[3320], + showground = false, + showlabels = false, + showpoints = false, + doslide = false, + ) +end +for t in 0.0:5.0:30.0 + step = Int(t/dt)+1 + with_theme(theme_pub; size=(2tw, 2tw), fontsize=20) do + fig = plot_traj!(bot2; + # atsteps=[3320], + showground = false, + showlabels = false, + showpoints = false, + doslide = false, + atsteps = [step] + ) + savefig(fig, "../tg2_$(t).png") + end +end + + +pos_list = Vector{SVector{3}}() +vel_list = Vector{SVector{3}}() +contact_set = Set{Int}() +(;contacts_traj) = bot2 +for (id, ctraj) in enumerate(contacts_traj) + @show id + for cn in ctraj + if cn.state.active == true && cn.id < 385 + contact_set = union(contact_set, Set(cn.id)) + end + end +end +contact_set = collect(contact_set) +@show contact_set + +for step in 1:length(bot2.traj) + (;structure, traj, contacts_traj) = bot2 + structure.state.system.q .= traj.q[step] + structure.state.system.c .= traj.c[step] + structure.state.system.q̇ .= traj.q̇[step] + RB.update!(structure) + (;bodies) = structure + foreach(bodies) do body + if body.prop.id == 37 + push!(pos_list, body.state.origin_frame.position) + push!(vel_list, body.state.origin_frame.velocity) + end + end +end + +xt = 0:dt:30 +Poss = [[p[i] for p in pos_list] for i in 1:3] +Vels = [[v[i] for v in vel_list] for i in 1:3] +Fs = [[norm(c_traj[i].state.force) for c_traj in contacts_traj] for i in contact_set] + +fig = Figure(fontsize=20, size=(1200, 600)) +ax1 = Axis(fig[1,1]) +ax2 = Axis(fig[1,2]) +# ax3 = Axis(fig[1,3]) +# lines!(ax1, xt, Poss[1], label="Direction x") +# lines!(ax2, xt, Poss[2], label="Direction y") +lines!(ax1, xt, Poss[3], label="Direction z") +# ax4 = Axis(fig[2,1]) +# ax5 = Axis(fig[2,2]) +# ax6 = Axis(fig[2,3]) +# lines!(ax4, xt, Vels[1], label="Direction x") +# lines!(ax5, xt, Vels[2], label="Direction y") +lines!(ax2, xt, Vels[3], label="Direction z") +ax1.xlabel = "Time [s]" +ax1.ylabel = "Position [m]" +axislegend(ax1, position=:rt) +ax2.xlabel = "Time [s]" +ax2.ylabel = "Velocity [m/s]" +axislegend(ax2, position=:lb) +# for (ax,ps) in zip([ax1, ax2, ax3], [:lt, :lt, :rt]) +# ax.xlabel = "Time [s]" +# ax.ylabel = "Position [m]" +# axislegend(ax, position=ps) +# end +# for (ax,ps) in zip([ax4, ax5, ax6], [:lb, :lt, :lb]) +# ax.xlabel = "Time [s]" +# ax.ylabel = "Velocity [m/s]" +# axislegend(ax, position=ps) +# end +fig +savefig(fig, "../position_velocity2-2.png" ) + +fig = Figure(fontsize=20, size=(1200, 800)) +ax1 = Axis(fig[1,1]) +n = 3 +for (id, f) in enumerate(Fs) + if contact_set[id] < 96 + # lines!(ax1,xt[1:end-1],[(f[i]+f[i+1])/2 for i in 1:length(f)-1],label="Node $(contact_set[id])") + lines!(ax1,xt[1+n:end-n],[(sum([f[j] for j in i-n:i+n]))/(2n+1) for i in n+1:length(f)-n],label="Node $(contact_set[id])") + end +end +ax1.xlabel = "Time [s]" +ax1.ylabel = "Λₙ" +axislegend(ax1, position=:lt) +fig +savefig(fig, "../contact_force2-2.png" ) + +bot1 = build_small_jixiebi(3) +(;structure) = bot1 +(;bodies) = structure +foreach(bodies) do body + (;prop, state) = body + (;loci_states) = state + force = [0.0, 0.0, 0.0] + @show prop.id + for loci in loci_states + force += loci.force + end + @show force +end + diff --git a/yard/jixiebi/plot_policy.jl b/yard/jixiebi/plot_policy.jl new file mode 100644 index 0000000..42aeb05 --- /dev/null +++ b/yard/jixiebi/plot_policy.jl @@ -0,0 +1,17 @@ +t = 0:dt:30 +sc1 = zeros(length(t)) +sc2 = 0.01*ones(length(t)) +sc3 = 0.01*ones(length(t)) + +fig = Figure(fontsize=20) +ax1 = Axis(fig[1,1]) +lw=3 +lines!(ax1, t, sc1, label="Sliding cable 1", linewidth=lw) +lines!(ax1, t, sc2, label="Sliding cable 2", linewidth=lw) +lines!(ax1, t, sc3, label="Sliding cable 3", linestyle=:dash, linewidth=lw) +ax1.xlabel = "Time [s]" +ax1.ylabel = "Velocity [m/s]" +axislegend(ax1, position=:rc) + +fig +savefig(fig, "../sliding_cables.png") \ No newline at end of file diff --git a/yard/jixiebi/test.jl b/yard/jixiebi/test.jl index 3566c14..23c8006 100644 --- a/yard/jixiebi/test.jl +++ b/yard/jixiebi/test.jl @@ -40,4 +40,20 @@ GeometryBasics.Mesh.Sphere((0.,0.,0.), 1.) s1 = Meshes.Sphere((0.,0.,0.),1.) mesh = Meshes.discretize(s1, Meshes.RegularDiscretization(30, 30)) -m1 = mesh |> RB.simple2mesh \ No newline at end of file +m1 = mesh |> RB.simple2mesh + + +temp_n = 20 +temp_m = zeros(temp_n, temp_n) +for i in 1:temp_n + n1 = 0.5 + n2 = 0.25 + temp_prev = (i+temp_n-2) % temp_n + 1 + temp_next = (i) % temp_n + 1 + temp_m[i, i] = n1 + temp_m[i, temp_prev] = temp_m[i, temp_next] = n2 + @show temp_prev,i, temp_next +end +temp_inv_m = inv(temp_m) +display(temp_inv_m) +display(temp_inv_m*temp_m) \ No newline at end of file diff --git a/yard/temp/structure.jl b/yard/temp/structure.jl new file mode 100644 index 0000000..51d459e --- /dev/null +++ b/yard/temp/structure.jl @@ -0,0 +1,229 @@ +function test_structure(n) + k1 = 1.0 + k2 = 80.0 + # kc = 4.0 + kc = 1.2 + delta = 20.00 + # delta = 37.52777 + # restlen1 = 120.0 + # restlen1 = 102.47223 + restlen1 = 100.0 + # restlen2 = 35.0555 + restlen2 = 50.0 + # restlenc = 102.47223 + restlenc = 160.0 + # pre = 1400.0 + pre = 383.65 + len1= -112.8 + len2= 47.2 + r1 = 100 + r2 = 120 + r3 = 35 + rl = [[len1, 0.0, -r3], + [len1, r3*sqrt(3)/2, r3/2], + [len1, -r3*sqrt(3)/2, r3/2], + [len2, 0.0, -r1], + [len2, r1*sqrt(3)/2, r1/2], + [len2, -r1*sqrt(3)/2, r1/2], + [len2, 0.0, r2], + [len2, r2*sqrt(3)/2, -r2/2], + [len2, -r2*sqrt(3)/2, -r2/2]] + mesh = load(RB.assetpath("jixiebi/m2.STL")) |> RB.make_patch(; rot=RotZ(-π / 2)) |> RB.make_patch(; rot=RotX(pi / 6)) + function rigidbody(i, rl, r_center, mesh) + if i == 1 + contactable = false + visible = true + ci = Int[] + Φi = collect(1:6) + else + contactable = true + visible = true + ci = Int[] + Φi = collect(1:6) + end + + ri = r_center + aps = rl + theta = 0 + α = [cos(theta) -sin(theta) 0; + sin(theta) cos(theta) 0; + 0 0 1] + r̄g = [0.0, 0.0, 0.0] + m = 1.0 + I = [372.01 0 0; 0 358.79 0; 0 0 372.01] ./ 10 + nrp = length(aps) + ṙo = zeros(3) + ω = zeros(Float64, 3) + prop = RB.RigidBodyProperty( + i, + contactable, + m, + SMatrix{3,3}(I), + SVector{3}(r̄g), + [SVector{3}(aps[i]) for i in 1:nrp]; + visible + ) + ro = SVector{3}(ri) + + state = RB.RigidBodyState(prop, ri, α, ṙo, ω) + nmcs = RB.NCF.NC1P3V(SVector{3}(ri)) + coords = RB.NonminimalCoordinates(nmcs, ci, Φi) + rb = RB.RigidBody(prop, state, coords, mesh) + end + rbs = [rigidbody(i, rl, [i*(len2-len1) - (i-1) * delta, 0, 0], mesh) for i in 1:n] + bodies = TypeSortedCollection(rbs) + nstrings = 6*(n-1) + spring_dampers = [(i <= 3(n-1)) ? RB.DistanceSpringDamper3D(restlen1, k1, 0.02) : RB.DistanceSpringDamper3D(restlen2, k2, 0.02) for i in 1:nstrings] + ncluster = 3 + cluster_segs = [[RB.DistanceSpringDamperSegment(restlenc, kc, prestress=pre) for i in 1:n-1] for _ in 1:ncluster] + cluster_sps = [[RB.SlidingPoint(0.01) for i in 1:n-2] for _ in 1:ncluster] + matrix_cnt_raw = Vector{Matrix{Int}}() + for i in 1:n-1 + s = zeros(3, 4) + s[1, :] = [i, 4, i+1, 4] + s[2, :] = [i, 5, i+1, 5] + s[3, :] = [i, 6, i+1, 6] + push!(matrix_cnt_raw, s) + end + for i in 1:n-1 + s = zeros(3, 4) + s[1, :] = [i, 4, i+1, 1] + s[2, :] = [i, 5, i+1, 2] + s[3, :] = [i, 6, i+1, 3] + push!(matrix_cnt_raw, s) + end + connecting_matrix = reduce(vcat, matrix_cnt_raw) + + matrix_cnt_raw = [Vector{Matrix{Int}}() for _ in 1:ncluster] + for j in 1:ncluster + s = zeros(n-1, 4) + for i in 1:n-1 + s[i, :] = [i, 6+j, i+1, 6+j] + end + push!(matrix_cnt_raw[j], s) + end + connecting_cluster_matrix = [reduce(vcat, matrix_cnt_raw[k]) for k in 1:ncluster] + + cables, clusters = RB.connect_spring_and_clusters(bodies, spring_dampers, cluster_sps, cluster_segs, connecting_matrix, connecting_cluster_matrix, istart=ncluster+1) + cst1 = RB.FixedBodyConstraint(ncluster + 1, rbs[1]) + apparatuses = TypeSortedCollection(vcat([cst1], cables, clusters)) + # apparatuses = TypeSortedCollection(vcat(cables, clusters)) + + indexed = RB.index(bodies, apparatuses;) + numbered = RB.number(bodies, apparatuses) + cnt = RB.Connectivity(numbered, indexed) + structure = RB.Structure(bodies, apparatuses, cnt) + # 测量器/传感器, 可测量误差, 之后用于定义cost函数, 实现优化或反馈控制, 目前暂时用不到。 + gauges = Int[] + # 作动器, 依附于一个或多个bodies或apparatuses, 其类型分派给execute!来施加不同的驱动力 + actuators = [ + # 试下ExternalForceActuator堪不堪用, 不堪用的话再搞个新的Actuator + RB.ExternalForceActuator( + i, + cluster, + #操作员, 1个驱动量 + RB.NaiveOperator(1), + #外力, 可能不需要用到 + 0.0, + #驱动量数值, + [0.0], + ) + for (i, cluster) in enumerate(clusters) + ] + hub = RB.ControlHub( + structure, + gauges, + actuators, + RB.Coalition(structure, gauges, actuators,) + ) + bot = RB.Robot(structure, hub) +end + + +# +policy = RB.TimePolicy( + @eponymtuple( + f = (t) -> [0.0, 5t, 5t] + # f = (t) -> [0.0, 0.0, 0.0] + ) +) + +dt = 1e-4 +RB.solve!( + RB.DynamicsProblem( + bot,policy, + RB.EulerEytelwein(), + ), + RB.DynamicsSolver( + RB.Zhong06(), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan=(0.0,10.0), + dt, + ftol=1e-7,verbose=true +) + +dts = [1e-2, 7e-3,5e-3,2e-3,1e-3, 5e-4, 1e-5] +dts = [2e-3, 1e-3, 5e-4, 1e-4,1e-5] + +pm_dts = [] +for dt in dts + push!(pm_dts, RB.solve!( + RB.DynamicsProblem( + deepcopy(bot),policy, + # ground_plane, + # rigid_contacts, + # RB.RestitutionFrictionCombined( + # RB.NewtonRestitution(), + # RB.CoulombFriction(), + # ), + RB.EulerEytelwein(), + ), + RB.DynamicsSolver( + RB.Zhong06(), + # RB.InnerLayerContactSolver( + # RB.InteriorPointMethod() + # ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan=(0.0, 0.5), + dt, + ftol= dt<1e-4 ? 1e-9 : 1e-8,verbose=true, + maxiters=50 + )[1].prob.bot) +end + +fig = Figure() +ax = Axis(fig[1,1],ylabel = "Abs. Err.") +_,err_nmsi = RB.get_err_avg(pm_dts[:];bid=4,pid=1,di=3) +# plot_convergence_order!(ax,dts[begin:end-1][end-1:end],err_nmsi[1:5][end-1:end];orders=[1, 2],label="NMSI") +plot_convergence_order!(ax,dts[begin:end-1],err_nmsi;orders=[1, 2],label="NMSI") +fig +savefig(fig, "../5t") + +fig = Figure() +ax = Axis(fig[1,1]) +for (id, dt) in enumerate(dts) + tr1 = RB.get_trajectory!(pm_dts[id], 4, 1) + for i in [3] + lines!(ax, LinRange(0.0, 1.0, length(tr1)), [log10(abs(t[i])) for t in tr1], label = "dt = $(dt), axis $(i)") + end +end +axislegend(ax) +fig + +bot = test_structure(4) + +plot_traj!(bot; + # ground=ground_plane, + showground = false, + xlims=(-1000.0, 4000.0), + ylims = (-1000.,1000.), + zlims = (-2000.,1000.), + showlabels = false, + showpoints = false, +) \ No newline at end of file From f447ae2bcd66123b30f6bf24e9b1dc110a137cf5 Mon Sep 17 00:00:00 2001 From: Perseus Date: Wed, 17 Apr 2024 11:55:02 +0800 Subject: [PATCH 02/20] prettify code --- src/mechanics/dynamics.jl | 18 ++ ...hong06_CCP_constant_mass_cluster_cables.jl | 30 ++- src/structures/linearization.jl | 178 ++++++++++++++++++ yard/jixiebi/Group1.jl | 11 ++ yard/jixiebi/Group2_1.jl | 3 +- 5 files changed, 230 insertions(+), 10 deletions(-) diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index 66c3728..553acdb 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -89,6 +89,24 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy:: build_tangent_damping_matrix!(∂F∂q̌̇,structure) end +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,∂F∂s̄,∂ζ∂q,ζ,bot::Robot,policy::AbstractPolicy,q,q̇,t,cluster_cache,s=nothing) + (;structure,hub) = bot + ∂F∂q̌ .= 0 + ∂F∂q̌̇ .= 0 + ∂F∂s̄ .= 0 + ∂ζ∂q .= 0 + ζ .= 0 + clear_forces!(structure) + lazy_update_bodies!(structure,q,q̇) + update_apparatuses!(structure) + generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) + build_tangent_stiffness_matrix!(∂F∂q̌,structure) + build_tangent_damping_matrix!(∂F∂q̌̇,structure) + build_ζ!(ζ, cluster_cache, structure) + build_∂Q̌∂s̄!(∂F∂s̄, cluster_cache, structure) + build_∂ζ∂q!(∂ζ∂q, cluster_cache, structure) +end + struct ContactCache{cacheType} cache::cacheType end diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index 1f0f4a2..862efb8 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -28,7 +28,8 @@ function generate_cache( solver.options, ) F!(F,q,s,q̇,t) = generalized_force!(F,bot,policy,q,q̇,t,s;gravity=options.gravity) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t) + # Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t) + Jac_F!(∂F∂q, ∂F∂q̇, ∂Q̌∂s̄, ∂ζ∂q, ζ, qₘ,q̇ₘ,tₘ, cluster_cache) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, ∂Q̌∂s̄, ∂ζ∂q, ζ,bot,policy, qₘ,q̇ₘ,tₘ, cluster_cache) M = Matrix(assemble_M(structure)) Φ = make_cstr_function(bot) @@ -83,10 +84,12 @@ function make_step_k( function ns_stepk!( 𝐫𝐞𝐬,𝐉, Fₘ,∂F∂q,∂F∂q̇, + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, 𝐁,𝐛,𝐜ᵀ,𝐲, x,Λₖ, structure, contact_cache, + cluster_cache, timestep,iteration,doin=true ) qₖ = @view x[ 1:n1] @@ -98,7 +101,9 @@ function make_step_k( vₘ = q̇ₘ tₘ = tₖ₋₁+h/2 F!(Fₘ,qₘ,sₘ,q̇ₘ,tₘ) - Jac_F!(∂F∂q,∂F∂q̇,qₘ,q̇ₘ,tₘ) + Jac_F!(∂F∂q, ∂F∂q̇, ∂Q̌∂s̄, ∂ζ∂q, ζ, qₘ,q̇ₘ,tₘ, cluster_cache) + + ∂F∂s̄ = transpose(∂Q̌∂s̄) Aₖ₋₁ = A(qₖ₋₁) Aᵀₖ₋₁ = transpose(Aₖ₋₁) @@ -111,18 +116,18 @@ function make_step_k( 𝐫𝐞𝐬[nq+1:nq+nλ] .= mass_norm.*Φ(qₖ) 𝐫𝐞𝐬[nq+nλ+1:nx] .= ψ(sₖ) - ζ = build_ζ(structure) - ∂ζ∂q = build_∂ζ∂q(structure) - ∂ζ∂s̄ = build_∂ζ∂s̄(structure) + # ζ = build_ζ(structure) + # ∂ζ∂q = build_∂ζ∂q(structure) + # ∂ζ∂s̄ = build_∂ζ∂s̄(structure) + # ∂F∂s̄ = build_∂Q̌∂s̄(structure) n = length(ζ) ∂s̄∂s̄ = I(n) - ∂F∂s̄ = build_∂Q̌∂s̄(structure) κ₁ = 10; κ₂ = 100 cosₘ = 1/2 coqₘ = 1/2 - coes = diagm([((ζ[i]/κ₁)^2 + (κ₂*sₖ[i])^2)^(-1/2) for i in 1:n]) - coζ = coes*diagm([ζ[i]/κ₁^2 for i in 1:n]) - diagm([1/κ₁ for i in 1:n]) - cos̄ = coes*diagm([κ₂^2*sₖ[i] for i in 1:n]) - diagm([κ₂ for i in 1:n]) + coes = [((ζ[i]/κ₁)^2 + (κ₂*sₖ[i])^2)^(-1/2) for i in 1:n] + coζ = diagm(coes.*[ζ[i]/κ₁^2 for i in 1:n] .- [1/κ₁ for i in 1:n]) + cos̄ = diagm(coes.*[κ₂^2*sₖ[i] for i in 1:n] .- [κ₂ for i in 1:n]) 𝐉 .= 0.0 𝐉[ 1:nq , 1:nq ] .= M.-(h^2)/2 .*(1/2 .*∂F∂q.+1/h.*∂F∂q̇) @@ -227,6 +232,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C mr = norm(M,Inf) mass_norm = mr α0 = 1.0 + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, cluster_cache = init_cluster_matrix(structure) iteration = 0 prog = Progress(totalstep; dt=1.0, enabled=progress) @@ -289,12 +295,18 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C luJac = ns_stepk!( Res,Jac, F,∂F∂q,∂F∂q̇, + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, 𝐁,𝐛,𝐜ᵀ,𝐲, x,Λʳₖ, structure, contact_cache, + cluster_cache, timestep,iteration ) + if (tₖ₋₁ == 0.096) & (iteration == 1) + @show size(Jac) + write("jac1.bin", Jac) + end if na == 0 normRes = norm(Res) if normRes < ftol diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 132be73..d930f66 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -800,6 +800,131 @@ function build_tangent_damping_matrix!(∂Q̌∂q̌̇,st) end end end +function init_cluster_matrix(st) + (; bodies, apparatuses, connectivity) = st + (; indexed, numbered) = connectivity + (; + num_of_free_coords, + bodyid2sys_free_coords, + bodyid2sys_full_coords, + apparid2sys_free_coords_idx, + apparid2sys_add_var_idx + ) = indexed + ns = 0 + nc = 0 + foreach(apparatuses) do appar + if isa(appar.joint, ClusterJoint) + ns += length(appar.joint.sps) + nc += 1 + end + end + T = get_numbertype(st) + num_of_dim = get_num_of_dims(st) + ∂Q̌∂s̄ = zeros(T, 2ns, num_of_free_coords) + ∂ζ∂q = zeros(T, 2ns, num_of_free_coords) + + αc = zeros(T, ns) + kc = zeros(T, ns + nc) + clusterA = get_clusterA(st) + N_list = Vector{SparseMatrixCSC{Float64,Int64}}() + b_list = [SparseMatrixCSC{Float64,Int64}(undef, 1, 1) for _ in 1:nc] + T_list = [SparseMatrixCSC{Float64,Int64}(undef, 1, 1) for _ in 1:nc] + A_list = [SparseMatrixCSC{Float64,Int64}(undef, 1, 1) for _ in 1:nc] + foreach(apparatuses) do appar + if isa(appar.joint, ClusterJoint) + (; force, joint, id) = appar + (; sps) = joint + nsegs = length(force) + nsp = length(sps) + sp_idx = apparid2sys_add_var_idx[id] + sp_idx_begin = Int((sp_idx[1]-1) / 2) + foreach(force) do seg + kc_idx = seg.id + seg.num_of_add_var + kc[kc_idx] = seg.force.k + end + for i in 1:nsp + αc[sp_idx_begin+i] = sps[i].α + end + b⁺ = zeros(Float64, nsegs-1, nsegs) + b⁻ = zeros(Float64, nsegs-1, nsegs) + for i in 1:nsegs-1 + b⁺[i, i:i+1] = [-kc[i] kc[i+1]/αc[i]] + b⁻[i, i:i+1] = [kc[i] -kc[i+1]*αc[i]] + end + b_list[id] = vcat(b⁺, b⁻) + T_list[id] = get_TransMatrix(nsegs - 1) + + nsegs = length(force) + N = zeros(Float64, nsegs, 2nsegs - 2) + N[1, 1:2] = [1 -1] + N[end, end-1:end] = [-1 1] + for i in 2:nsegs-1 + N[i, 2i-3:2i] = [-1 1 1 -1] + end + push!(N_list, N) + + TT = get_TransMatrix(nsegs - 1) + A = TT*clusterA[id]*TT' + A_list[id] = A + end + end + b = reduce(blockdiag, b_list) + T_matrix = reduce(blockdiag, T_list) + N = reduce(blockdiag, N_list) + ζ = Vector{Float64}(undef, 2ns) + ∂ζ∂s̄ = reduce(blockdiag, A_list) + Tb = T_matrix*b + cluster_cache = @eponymtuple( + N, kc, ns, nc, T, num_of_dim, + Tb, + ) + return ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, cluster_cache +end + +function build_∂Q̌∂s̄!(∂Q̌∂s̄, cluster_cache, st) + (; bodies, apparatuses, connectivity) = st + (; indexed, numbered) = connectivity + (; + num_of_free_coords, + bodyid2sys_free_coords, + bodyid2sys_full_coords, + apparid2sys_free_coords_idx + ) = indexed + (;T, num_of_dim, ns, kc, N) = cluster_cache + D = zeros(T, num_of_dim) + lkn = zeros(T, 2ns, num_of_dim) + J̌ = zeros(T, num_of_dim, num_of_free_coords) + foreach(apparatuses) do appar + if isa(appar.joint, ClusterJoint) + (; force) = appar + foreach(force) do seg + idx = seg.id + seg.num_of_add_var + (; hen, egg) = seg.joint.hen2egg + body_hen = hen.body + body_egg = egg.body + C_hen = body_hen.cache.Cps[hen.pid] + C_egg = body_egg.cache.Cps[egg.pid] + free_idx_hen = body_hen.coords.free_idx + free_idx_egg = body_egg.coords.free_idx + mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] + mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] + (; k, c, state) = seg.force + (; direction, tension) = state + if tension == 0 + ∂Q̌∂s̄ .-= 0 + else + D .= direction + J̌ .= 0 + J̌[:, mfree_egg] .+= C_egg[:, free_idx_egg] + J̌[:, mfree_hen] .-= C_hen[:, free_idx_hen] + kN = kc[idx] .* N[idx, :] + @tullio lkn[k, l] = D[l] * kN[k] + ∂Q̌∂s̄ .-= lkn * J̌ + end + end + end + end +end function build_∂Q̌∂s̄(st) (; bodies, apparatuses, connectivity) = st @@ -878,6 +1003,25 @@ function build_∂Q̌∂s̄(st) return ∂Q̌∂s̄' end +function build_ζ!(ζ, cluster_cache, st) + (; apparatuses, connectivity) = st + (; apparid2sys_add_var_idx) = connectivity.indexed + ζ⁺ = @view ζ[begin:2:end] + ζ⁻ = @view ζ[begin+1:2:end] + foreach(apparatuses) do appar + if isa(appar.joint, ClusterJoint) + (; force, joint, id) = appar + (; sps) = joint + nsp = length(sps) + idx_begin = Int((apparid2sys_add_var_idx[id][1]-1) / 2) + for i in 1:nsp + ζ⁺[idx_begin+i] = force[i+1].force.state.tension / sps[i].α - force[i].force.state.tension + ζ⁻[idx_begin+i] = force[i].force.state.tension - sps[i].α * force[i+1].force.state.tension + end + end + end +end + function build_ζ(st) (; apparatuses, connectivity) = st (; apparid2sys_add_var_idx) = connectivity.indexed @@ -967,6 +1111,38 @@ function build_∂ζ∂s̄(st) return reduce(blockdiag, A_list) end +function build_∂ζ∂q!(∂ζ∂q, cluster_cache, st) + (; apparatuses, connectivity) = st + (; indexed) = connectivity + (; num_of_free_coords, bodyid2sys_free_coords, apparid2sys_add_var_idx) = indexed + (; Tb, T, ns, nc, num_of_dim) = cluster_cache + ∂l∂q = zeros(T, ns+nc, num_of_free_coords) + foreach(apparatuses) do appar + if isa(appar.joint, ClusterJoint) + (; force) = appar + foreach(force) do seg + idx = seg.id + seg.num_of_add_var + J̌ = zeros(T, num_of_dim, num_of_free_coords) + (; hen, egg) = seg.joint.hen2egg + body_hen = hen.body + body_egg = egg.body + C_hen = body_hen.cache.Cps[hen.pid] + C_egg = body_egg.cache.Cps[egg.pid] + free_idx_hen = body_hen.coords.free_idx + free_idx_egg = body_egg.coords.free_idx + mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] + mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] + (; direction) = seg.force.state + J̌[:, mfree_egg] .+= C_egg[:, free_idx_egg] + J̌[:, mfree_hen] .-= C_hen[:, free_idx_hen] + ∂l∂q[idx, :] = direction'*J̌ + end + end + end + ∂ζ∂q .= Tb*∂l∂q + # @show maximum(∂ζ∂q) +end + function build_∂ζ∂q(st) (; apparatuses, connectivity) = st (; indexed) = connectivity @@ -1035,10 +1211,12 @@ function build_∂ζ∂q(st) end b = reduce(blockdiag, b_list) T = reduce(blockdiag, T_list) + # @show maximum(T*b*∂l∂q) return T*b*∂l∂q end + function build_Ǩ(st) _,λ = check_static_equilibrium_output_multipliers(st) build_Ǩ(st,λ) diff --git a/yard/jixiebi/Group1.jl b/yard/jixiebi/Group1.jl index 3343796..5956281 100644 --- a/yard/jixiebi/Group1.jl +++ b/yard/jixiebi/Group1.jl @@ -124,3 +124,14 @@ plot_traj!(bot_4; showpoints = false, ) + +t1 = zeros(336, 336) +t2 = zeros(336, 336) +read!("jac.bin", t1) +read!("jac1.bin", t2) +diff = t1 - t2 +n1 = 168 +n2 = n1 + 90 +n3 = n2 + 78 +findmax(diff[n2:n3, 1:n1]) +findmax(diff) \ No newline at end of file diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 0f1c619..28ef2e8 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -44,6 +44,7 @@ fig = plot_traj!(bot1; # doslide = false, ) + RB.solve!( RB.DynamicsProblem( bot1,policy, @@ -64,7 +65,7 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 5.0), + tspan=(0.0, 0.1), dt, ftol=1e-7,verbose=true, maxiters=50 From 223158bb03d15892dd1b9636ddbabc2a60fff317 Mon Sep 17 00:00:00 2001 From: Perseus Date: Thu, 25 Apr 2024 12:58:30 +0800 Subject: [PATCH 03/20] update structure --- examples/robots/jixiebi.jl | 10 ++--- ...hong06_CCP_constant_mass_cluster_cables.jl | 2 + test/vis.jl | 15 ++++++- yard/jixiebi/Group2_1.jl | 39 ++++++++++++------- yard/jixiebi/Group2_2.jl | 35 +++++++++++------ 5 files changed, 71 insertions(+), 30 deletions(-) diff --git a/examples/robots/jixiebi.jl b/examples/robots/jixiebi.jl index d0bcb7b..2893a50 100644 --- a/examples/robots/jixiebi.jl +++ b/examples/robots/jixiebi.jl @@ -692,7 +692,7 @@ function build_small_jixiebi(n; ks1=8.0, restlens1=0.018007, connecting_cluster_matrix = [reduce(vcat, matrix_cnt_raw[k]) for k in 1:ncluster] cables, clusters = RB.connect_spring_and_clusters(bodies, spring_dampers, cluster_sps, cluster_segs, connecting_matrix, connecting_cluster_matrix, istart=ncluster + 1) cst1 = RB.FixedBodyConstraint(ncluster + 1, rbs[1]) - cst2 = RB.FixedBodyConstraint(77, rbs[14]) + # cst2 = RB.FixedBodyConstraint(77, rbs[14]) apparatuses = TypeSortedCollection(vcat([cst1], cables, clusters)) indexed = RB.index(bodies, apparatuses;) @@ -725,9 +725,9 @@ function build_small_jixiebi(n; ks1=8.0, restlens1=0.018007, bot = RB.Robot(structure, hub) end -function build_4_jixiebis(n; ks1=80.0, restlens1=0.050, - ks2=1.00, restlens2=0.1, - kc=1.20, restlenc=0.160, pre=383.65, +function build_4_jixiebis(n; ks1=8.0, restlens1=0.018007, + ks2=1.00, restlens2=0.08, + kc=2.00, restlenc=0.140, pre=57.6343395, delta=-0.02) @@ -966,7 +966,7 @@ function build_4_jixiebis(n; ks1=80.0, restlens1=0.050, spring_dampers = vcat(deepcopy(spring_dampers), deepcopy(spring_dampers), deepcopy(spring_dampers), deepcopy(spring_dampers)) restlencs = zeros(Float64, 5n - 1) - restlenc1 = 266.77 / scale + restlenc1 = 256.77 / scale for i in 1:5n-1 if (mod(i, 5) == 0) restlencs[i] = restlenc1 diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index 862efb8..7cdd2ed 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -355,10 +355,12 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C ns_stepk!( Res_α0,Jac_α0, F,∂F∂q,∂F∂q̇, + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, 𝐁t,𝐛,𝐜ᵀ,𝐲, x.+Δx,Λʳₖ.+ΔΛₖ, structure, contact_cache, + cluster_cache, timestep,iteration,false ) ϕα0 = (transpose(Res_α0)*sd*Res_α0)/2 diff --git a/test/vis.jl b/test/vis.jl index b8c08d5..0f3b34c 100644 --- a/test/vis.jl +++ b/test/vis.jl @@ -244,6 +244,18 @@ function plot_traj!(bot::RB.Robot; aspect=:data, # tellheight=false, ) + # scale = 1e3 + # m0_yellow = load("yard/jixiebi/m0_yellow.STL") |> RB.make_patch(;rot=RotY(pi/2),trans=[-0.50, 0.0, 0.8],scale=1/scale,color=:yellow) + # m0_blue1 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2), trans=[-0.5,0.23,0.37], scale=1/scale,color=:blue) + # m0_blue2 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2), trans=[0.5,0.23,0.37], scale=1/scale,color=:blue) + # m0_blue3 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2)*RotX(-pi/2), trans=[-0.23,0.5,0.37], scale=1/scale,color=:blue) + # m0_blue4 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2)*RotX(-pi/2), trans=[-0.23,-0.5,0.37], scale=1/scale,color=:blue) + # mesh!(ax, m0_yellow) + # mesh!(ax, m0_blue1) + # mesh!(ax, m0_blue2) + # mesh!(ax, m0_blue3) + # mesh!(ax, m0_blue4) + xlims!(ax,xmin,xmax) ylims!(ax,ymin,ymax) zlims!(ax,zmin,zmax) @@ -367,6 +379,7 @@ function plot_traj!(bot::RB.Robot; recordsteps = 1:skipstep:length(traj.t) record(fig, figname, recordsteps; framerate) do this_step + @show this_step / length(traj.t) if actuate RB.actuate!(bot,[traj.t[this_step]]) end @@ -376,7 +389,7 @@ function plot_traj!(bot::RB.Robot; # @show RB.mechanical_energy(structure) # this_time[] = traj.t[this_step] - RB.analyse_slack(structure,true) + # RB.analyse_slack(structure,true) tgob[] = structure end else diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 28ef2e8..8330af4 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -16,11 +16,15 @@ include(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl -dt = 2e-3 +dt = 5e-3 +A = 0.1 policy = RB.TimePolicy( @eponymtuple( - f = (t) -> [0.0, 0.1t, 0.1t] + # f = (t) -> [0.0, 0.1t, 0.1t] + f = (t) -> [0.0, + t [0.0, t<5 ? 0.1t : 0.5, t<5 ? 0.1t : 0.5] # f = (t) -> [0.0, t<20 ? 0.1t : 2, t<20 ? 0.1t : 2] # f = (t) -> [0.0, 0.1t, 0.1t] - f = (t) -> reduce(vcat, [[0.0, 0.1t, 0.1t] for _ in 1:4]) + f = (t) -> reduce(vcat, [[0.0, + t reduce(vcat, [[0.0, 0.1t, 0.1t] for _ in 1:4]) # f = (t) -> [0.0, 0.0, 0.0] ) ) @@ -63,20 +67,28 @@ RB.solve!( ftol=1e-7,verbose=true, maxiters=50 ) -with_theme(theme_pub;size = (2tw, 2tw), -fontsize=20, -figure_padding=(-10,-10,-10,0), +with_theme(theme_pub; size=(0.8tw, 0.7tw), fontsize=fontsize, + # figure_padding = (5fontsize,5fontsize,fontsize,fontsize), + figure_padding = (2fontsize,2fontsize,0,0), # left, right, down, up Axis3 = ( - azimuth = 1.0, - elevation = 0.2 + azimuth = pi/3.5, + elevation = pi/12 ) ) do fig = plot_traj!(bot2; # atsteps=[3320], showground = false, showlabels = false, + xlims = (-1.5, 1.5), + ylims = (-1.5, 1.5), + zlims = (-2, 2), + AxisType = Axis3, showpoints = false, + showinfo = false, + # doslide = true, doslide = false, + dorecord = true, + figname = "t1.mp4" ) end for t in 0.0:5.0:30.0 @@ -103,6 +115,7 @@ for (id, ctraj) in enumerate(contacts_traj) @show id for cn in ctraj if cn.state.active == true && cn.id < 385 + # if cn.state.active == true contact_set = union(contact_set, Set(cn.id)) end end @@ -110,7 +123,7 @@ end contact_set = collect(contact_set) @show contact_set -for step in 1:length(bot2.traj) +for step in 1:length(bot2.traj[1:2001]) (;structure, traj, contacts_traj) = bot2 structure.state.system.q .= traj.q[step] structure.state.system.c .= traj.c[step] @@ -125,10 +138,10 @@ for step in 1:length(bot2.traj) end end -xt = 0:dt:30 +xt = 0:dt:10 Poss = [[p[i] for p in pos_list] for i in 1:3] Vels = [[v[i] for v in vel_list] for i in 1:3] -Fs = [[norm(c_traj[i].state.force) for c_traj in contacts_traj] for i in contact_set] +Fs = [[norm(c_traj[i].state.force) for c_traj in contacts_traj[1:2001]] for i in contact_set] fig = Figure(fontsize=20, size=(1200, 600)) ax1 = Axis(fig[1,1]) @@ -164,7 +177,7 @@ savefig(fig, "../position_velocity2-2.png" ) fig = Figure(fontsize=20, size=(1200, 800)) ax1 = Axis(fig[1,1]) -n = 3 +n = 1 for (id, f) in enumerate(Fs) if contact_set[id] < 96 # lines!(ax1,xt[1:end-1],[(f[i]+f[i+1])/2 for i in 1:length(f)-1],label="Node $(contact_set[id])") From ab9d6953edec6f5b126841d878e0ebf051c44b5a Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Mon, 29 Apr 2024 13:53:53 +0800 Subject: [PATCH 04/20] fix type instability using `na_ref`; fix abstract type in `connect_clusters`; add dispatch for in-place tangent stiffness matrix for apparatuses and bodies; rm `DifferentiableCollisions`; --- Project.toml | 1 - jixiebi2.jl | 0 src/mechanics/dynamics.jl | 10 +- ...hong06_CCP_constant_mass_cluster_cables.jl | 2 +- src/structures/connectivity.jl | 39 +-- src/structures/linearization.jl | 278 ++++++++++-------- 6 files changed, 188 insertions(+), 142 deletions(-) delete mode 100644 jixiebi2.jl diff --git a/Project.toml b/Project.toml index 7716ec8..18a36de 100644 --- a/Project.toml +++ b/Project.toml @@ -12,7 +12,6 @@ Clarabel = "61c947e1-3e6d-4ee4-985a-eec8c727bd6e" ColorTypes = "3da002f7-5984-5a60-b8a6-cbb66c0b333f" ComponentArrays = "b0b7db55-cfe3-40fc-9ded-d10e2dbeff66" CoordinateTransformations = "150eb455-5306-5404-9cee-2592286d6298" -DifferentiableCollisions = "64b45163-ce2a-43f6-8f64-55d720633796" DocStringExtensions = "ffbed154-4ef7-542d-bbb7-c09d3a79fcae" DynamicPolynomials = "7c1d4256-1411-5781-91ec-d7bc3513ac07" EponymTuples = "97e2ac4a-e175-5f49-beb1-4d6866a6cdc3" diff --git a/jixiebi2.jl b/jixiebi2.jl deleted file mode 100644 index e69de29..0000000 diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index 553acdb..2d7404c 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -157,7 +157,7 @@ function activate_frictional_contacts!(structure,contact_env::ContactRigidBodies (;contact_bodies) = contact_env T = eltype(q) nq = length(q) - na = 0 + na_ref = Ref(0) for contact in contact_bodies contact.pid = contact.init_pid # INFO 3: 第一个loci不动,从第二个开始 @@ -215,7 +215,7 @@ function activate_frictional_contacts!(structure,contact_env::ContactRigidBodies end end end - na += 2 + na_ref[] += 2 # INFO 6: 一个碰撞对应两个na end end @@ -235,6 +235,7 @@ function activate_frictional_contacts!(structure,contact_env::ContactRigidBodies end end + na = na_ref[] inv_friction_coefficients = ones(T,3na) for (i,μ) in enumerate(μs_sys[contacts_bits]) inv_friction_coefficients[3(i-1)+1] = 1/μ @@ -360,7 +361,7 @@ function activate_contacts!(structure,contact_env::ContactRigidBodies,solver_cac (;contact_bodies) = contact_env T = eltype(q) nq = length(q) - na = 0 + na_ref = Ref(0) update_bodies!(structure,q) foreach(structure.bodies) do body (;prop,state) = body @@ -383,12 +384,13 @@ function activate_contacts!(structure,contact_env::ContactRigidBodies,solver_cac if contact_state.persistent persistent_bits[bodyid2sys_loci_idx[bid][pid]] = true end - na += 1 + na_ref[] += 1 end end end end # @show na, length(active_contacts) + na = na_ref[] inv_friction_coefficients = ones(T,na) for (i,μ) in enumerate(μs_sys[contacts_bits]) inv_friction_coefficients[(i-1)+1] = 1 diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index 7cdd2ed..08af31c 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -207,7 +207,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C λ0 = traj.λ[begin] s0 = traj.s[begin] q̇0 = traj.q̇[begin] - activate_contacts!(structure,env,solver_cache,q0) + activate_frictional_contacts!(structure,env,solver_cache,q0) invM = inv(M) pₖ₋₁ = M*q̇0 pₖ = zero(pₖ₋₁) diff --git a/src/structures/connectivity.jl b/src/structures/connectivity.jl index 8099e78..54cc1bb 100644 --- a/src/structures/connectivity.jl +++ b/src/structures/connectivity.jl @@ -38,24 +38,27 @@ function connect_clusters(bodies, cluster_sps, cluster_segs, cms) ret = Vector{Apparatus{<:CableJoint, <:DistanceSpringDamperSegment}}(undef, size(cm, 1)) j = 0 clusterID += 1 - for row in eachrow(cm) - rbid1, pid1, rbid2, pid2 = row - j += 1 - joint = CableJoint( - Hen2Egg(Signifier(rbs_sorted[rbid1], pid1), Signifier(rbs_sorted[rbid2], pid2)), - 0, - ) - segs = Apparatus( - j, - joint, - cluster_seg[j], - num_segs, - Int[], - Int[] - ) - # push!(ret, segs) - ret[j] = segs - end + ret = [ + begin + rbid1, pid1, rbid2, pid2 = row + j += 1 + joint = CableJoint( + Hen2Egg(Signifier(rbs_sorted[rbid1], pid1), Signifier(rbs_sorted[rbid2], pid2)), + 0, + ) + segs = Apparatus( + j, + joint, + cluster_seg[j], + num_segs, + Int[], + Int[] + ) + # push!(ret, segs) + segs + end + for row in eachrow(cm) + ] num_segs += size(cm, 1) push!(rets, Apparatus(clusterID, ClusterJoint(cluster_sps[clusterID], 0), ret, 2j-2, Int[], Int[])) end diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index d930f66..467fb83 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -625,133 +625,173 @@ function build_tangent_damping_matrix(st, @eponymargs(clustered, )) return ∂Q̌∂q̌̇ end + # In-place ∂Q̌∂q̌ for cables and flexible bodies -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,st) - (;bodies,apparatuses,connectivity) = st - (;indexed,numbered) = connectivity +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::AbstractBody,q,st) + #default do nothing +end +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus,q,st) + #default do nothing +end + +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::FlexibleBody,q,st) + (;coords,cache) = body + (;e,) = cache + ancs = coords.nmcs + ∂Q∂e = ANCF.make_∂Q∂e(ancs)(e) + mfree = bodyid2sys_free_coords[body.prop.id] + (;free_idx) = body.coords + ∂Q̌∂q̌[mfree,mfree] .-= ∂Q∂e[free_idx,free_idx] +end + +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJoint},q,st) + + (;indexed,numbered) = st.connectivity (; num_of_free_coords, bodyid2sys_free_coords, bodyid2sys_full_coords, apparid2sys_free_coords_idx ) = indexed + T = get_numbertype(st) num_of_dim = get_num_of_dims(st) - # ∂Q̌∂q̌ = zeros(T,num_of_free_coords,num_of_free_coords) D = @MMatrix zeros(T,num_of_dim,num_of_dim) Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) J̌ = zeros(T,num_of_dim,num_of_free_coords) + + (;hen,egg) = appar.joint.hen2egg + body_hen = hen.body + body_egg = egg.body + C_hen = body_hen.cache.Cps[hen.pid] + C_egg = body_egg.cache.Cps[egg.pid] + free_idx_hen = body_hen.coords.free_idx + free_idx_egg = body_egg.coords.free_idx + mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] + mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] + (;k,c,state,slack) = appar.force + (;direction,tension) = state + l = state.length + l̇ = state.lengthdot + if slack && (tension==0) + ∂Q̌∂q̌ .-= 0 + else + D .= direction*transpose(direction) + density = tension/l + β = c*l̇/l + density + D .*= k-β + D .+= β.*Im + J̌ .= 0 + J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] + J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] + ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ + end +end + +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJoint,<:DistanceSpringDamperSegment},q,st) + + (;indexed,numbered) = st.connectivity + (; + num_of_free_coords, + bodyid2sys_free_coords, + bodyid2sys_full_coords, + apparid2sys_free_coords_idx + ) = indexed + + T = get_numbertype(st) + num_of_dim = get_num_of_dims(st) + D = @MMatrix zeros(T,num_of_dim,num_of_dim) + Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) + J̌ = zeros(T,num_of_dim,num_of_free_coords) + + (;hen,egg) = appar.joint.hen2egg + body_hen = hen.body + body_egg = egg.body + C_hen = body_hen.cache.Cps[hen.pid] + C_egg = body_egg.cache.Cps[egg.pid] + free_idx_hen = body_hen.coords.free_idx + free_idx_egg = body_egg.coords.free_idx + mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] + mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] + (;k,c,state) = appar.force + (;direction,tension) = state + l = state.length + l̇ = state.lengthdot + D .= direction*transpose(direction) + density = tension/l + β = c*l̇/l + density + D .*= k-β + D .+= β.*Im + J̌ .= 0 + J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] + J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] + ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ +end + +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:ClusterJoint},q,st) + foreach(appar.force) do seg + build_tangent_stiffness_matrix!(∂Q̌∂q̌,seg,q,st) + end +end + +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{JointType,<:RotationalSpringDamper},q,st) where {JointType} + (; + num_of_cstr, + hen2egg, + cache, + mask_1st,mask_2nd,mask_3rd,mask_4th + ) = appar.joint + (; + relative_core + ) = cache + full_idx = appar.full_coords_idx + free_idx = appar.free_coords_idx + sys_free_coords_idx = apparid2sys_free_coords_idx[appar.id] + (;mask,k) = appar.force + (;hen,egg) = hen2egg + nmcs_hen = hen.body.coords.nmcs + nmcs_egg = egg.body.coords.nmcs + num_of_coords_hen = get_num_of_coords(nmcs_hen) + num_of_coords_egg = get_num_of_coords(nmcs_egg) + id_hen = hen.body.prop.id + id_egg = egg.body.prop.id + q_hen = @view q[bodyid2sys_full_coords[id_hen]] + q_egg = @view q[bodyid2sys_full_coords[id_egg]] + q_jointed = vcat( + q_hen, + q_egg + ) + jointed2angles = make_jointed2angles(hen2egg,relative_core) + nq = length(q_jointed) + ## angles = jointed2angles(q_jointed) + ## torques = k.*angles + ## angles_jacobian = ForwardDiff.jacobian(jointed2angles,q_jointed) + ## angles_hessians = ForwardDiff.jacobian(x -> ForwardDiff.jacobian(jointed2angles, x), q_jointed) + # angles_hessians = FiniteDiff.finite_difference_jacobian(x -> ForwardDiff.jacobian(jointed2angles, x), q_jointed) + ## reshaped_angles_hessians = reshape(angles_hessians,3,nq,nq) + # @show sys_free_coords_idx, free_idx + for i in mask + ## angle = angles[i] + ## torque = torques[i] + ## generalized_force_jacobian = torque.*reshaped_angles_hessians[i,:,:] .+ k.*angles_jacobian[i,:]*angles_jacobian[[i],:] + # @show generalized_force_jacobian + ## ∂Q̌∂q̌[sys_free_coords_idx,sys_free_coords_idx] .-= generalized_force_jacobian[free_idx,free_idx] + end +end + +# In-place ∂Q̌∂q̌ for cables and flexible bodies +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,st) + (;bodies,apparatuses,connectivity) = st q = get_coords(st) + num_of_dim = get_num_of_dims(st) + # ∂Q̌∂q̌ = zeros(T,num_of_free_coords,num_of_free_coords) foreach(bodies) do body - if body isa FlexibleBody - (;coords,cache) = body - (;e,) = cache - ancs = coords.nmcs - ∂Q∂e = ANCF.make_∂Q∂e(ancs)(e) - mfree = bodyid2sys_free_coords[body.prop.id] - (;free_idx) = body.coords - ∂Q̌∂q̌[mfree,mfree] .-= ∂Q∂e[free_idx,free_idx] - end + build_tangent_stiffness_matrix!(∂Q̌∂q̌,body,q,st) end foreach(apparatuses) do appar - if appar.joint isa CableJoint - (;hen,egg) = appar.joint.hen2egg - body_hen = hen.body - body_egg = egg.body - C_hen = body_hen.cache.Cps[hen.pid] - C_egg = body_egg.cache.Cps[egg.pid] - free_idx_hen = body_hen.coords.free_idx - free_idx_egg = body_egg.coords.free_idx - mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] - mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] - (;k,c,state,slack) = appar.force - (;direction,tension) = state - l = state.length - l̇ = state.lengthdot - if slack && (tension==0) - ∂Q̌∂q̌ .-= 0 - else - D .= direction*transpose(direction) - density = tension/l - β = c*l̇/l + density - D .*= k-β - D .+= β.*Im - J̌ .= 0 - J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] - J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] - ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ - end - elseif appar.joint isa ClusterJoint - foreach(appar.force) do seg - (;hen, egg) = seg.joint.hen2egg - body_hen = hen.body - body_egg = egg.body - C_hen = body_hen.cache.Cps[hen.pid] - C_egg = body_egg.cache.Cps[egg.pid] - free_idx_hen = body_hen.coords.free_idx - free_idx_egg = body_egg.coords.free_idx - mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] - mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] - (;k, c, state) = seg.force - (;direction, tension) = state - l = state.length - l̇ = state.lengthdot - D .= direction*transpose(direction) - density = tension / l - β = c*l̇/l + density - D .*= k - β - D .+= β .* Im - J̌ .= 0 - J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] - J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] - ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ - end - elseif appar.force isa RotationalSpringDamper - (; - num_of_cstr, - hen2egg, - cache, - mask_1st,mask_2nd,mask_3rd,mask_4th - ) = appar.joint - (; - relative_core - ) = cache - full_idx = appar.full_coords_idx - free_idx = appar.free_coords_idx - sys_free_coords_idx = apparid2sys_free_coords_idx[appar.id] - (;mask,k) = appar.force - (;hen,egg) = hen2egg - nmcs_hen = hen.body.coords.nmcs - nmcs_egg = egg.body.coords.nmcs - num_of_coords_hen = get_num_of_coords(nmcs_hen) - num_of_coords_egg = get_num_of_coords(nmcs_egg) - id_hen = hen.body.prop.id - id_egg = egg.body.prop.id - q_hen = @view q[bodyid2sys_full_coords[id_hen]] - q_egg = @view q[bodyid2sys_full_coords[id_egg]] - q_jointed = vcat( - q_hen, - q_egg - ) - jointed2angles = make_jointed2angles(hen2egg,relative_core) - nq = length(q_jointed) - ## angles = jointed2angles(q_jointed) - ## torques = k.*angles - ## angles_jacobian = ForwardDiff.jacobian(jointed2angles,q_jointed) - ## angles_hessians = ForwardDiff.jacobian(x -> ForwardDiff.jacobian(jointed2angles, x), q_jointed) - # angles_hessians = FiniteDiff.finite_difference_jacobian(x -> ForwardDiff.jacobian(jointed2angles, x), q_jointed) - ## reshaped_angles_hessians = reshape(angles_hessians,3,nq,nq) - # @show sys_free_coords_idx, free_idx - for i in mask - ## angle = angles[i] - ## torque = torques[i] - ## generalized_force_jacobian = torque.*reshaped_angles_hessians[i,:,:] .+ k.*angles_jacobian[i,:]*angles_jacobian[[i],:] - # @show generalized_force_jacobian - ## ∂Q̌∂q̌[sys_free_coords_idx,sys_free_coords_idx] .-= generalized_force_jacobian[free_idx,free_idx] - end - end + build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar,q,st) end return ∂Q̌∂q̌ @@ -810,14 +850,16 @@ function init_cluster_matrix(st) apparid2sys_free_coords_idx, apparid2sys_add_var_idx ) = indexed - ns = 0 - nc = 0 + ns_ref = Ref(0) + nc_ref = Ref(0) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - ns += length(appar.joint.sps) - nc += 1 + ns_ref[] += length(appar.joint.sps) + nc_ref[] += 1 end end + ns = ns_ref[] + nc = nc_ref[] T = get_numbertype(st) num_of_dim = get_num_of_dims(st) ∂Q̌∂s̄ = zeros(T, 2ns, num_of_free_coords) @@ -855,13 +897,13 @@ function init_cluster_matrix(st) T_list[id] = get_TransMatrix(nsegs - 1) nsegs = length(force) - N = zeros(Float64, nsegs, 2nsegs - 2) - N[1, 1:2] = [1 -1] - N[end, end-1:end] = [-1 1] + N_segs = zeros(Float64, nsegs, 2nsegs - 2) + N_segs[1, 1:2] = [1 -1] + N_segs[end, end-1:end] = [-1 1] for i in 2:nsegs-1 - N[i, 2i-3:2i] = [-1 1 1 -1] + N_segs[i, 2i-3:2i] = [-1 1 1 -1] end - push!(N_list, N) + push!(N_list, N_segs) TT = get_TransMatrix(nsegs - 1) A = TT*clusterA[id]*TT' From 7ba6aa5950aced52a6eb4387b6da2f3ae37c020d Mon Sep 17 00:00:00 2001 From: Perseus Date: Mon, 29 Apr 2024 14:17:26 +0800 Subject: [PATCH 05/20] update --- examples/robots/jixiebi.jl | 16 +- .../Zhong06_constant_mass_cluster_cables.jl | 10 +- test/vis.jl | 2 + yard/jixiebi/Group2_1 copy.jl | 311 ++++++++++++++++++ yard/jixiebi/Group2_1.jl | 110 +++++-- yard/jixiebi/Group2_2.jl | 12 +- 6 files changed, 421 insertions(+), 40 deletions(-) create mode 100644 yard/jixiebi/Group2_1 copy.jl diff --git a/examples/robots/jixiebi.jl b/examples/robots/jixiebi.jl index 2893a50..b7419ec 100644 --- a/examples/robots/jixiebi.jl +++ b/examples/robots/jixiebi.jl @@ -298,7 +298,7 @@ function build_small_jixiebi(n; ks1=8.0, restlens1=0.018007, # kc=8.00, restlenc=0.160, pre=520.0-0.35, # kc=4.00, restlenc=0.160, pre=480.0-0.35, kc=2.0, restlenc=0.14, pre=57.6343395, - delta=-0.02) + delta=-0.02,object=:none) function RigidData(r̄g, m, i, r̄l, mesh=nothing) @@ -593,9 +593,15 @@ function build_small_jixiebi(n; ks1=8.0, restlens1=0.018007, rb = RB.RigidBody(prop, state, coords, sphere_mesh) end rbs1 = [rigidbody(i, rds[i], r̄s[i]) for i in 1:nb] - # rbs2 = [rigidCube([1.05, 0.0, -0.55], [0.4, 0.4, 0.4], length(rbs1)+1)] - rbs2 = [rigidSphere([0.65, 0.0, -0.55], 0.4, length(rbs1) + 1)] - # rbs2 = [rigidCylinder([1.05, 0.0, -0.5], 0.3, 1.2, 0.0, pi/6, pi/2, length(rbs1) + 1)] + if object == :none + rbs2 = [] + elseif object == :cube + rbs2 = [rigidCube([1.05, 0.0, -0.55], [0.4, 0.4, 0.4], length(rbs1)+1)] + elseif object == :sphere + rbs2 = [rigidSphere([0.65, 0.0, -0.55], 0.4, length(rbs1) + 1)] + elseif object == :cylinder + rbs2 = [rigidCylinder([1.05, 0.0, -0.5], 0.3, 1.2, 0.0, 0.0, pi/2, length(rbs1) + 1)] + end rbs = vcat(rbs1, rbs2) # rbs = vcat(rbs, [rigidbody(nb+1, rds[nb], r̄s[nb])]) @@ -620,7 +626,7 @@ function build_small_jixiebi(n; ks1=8.0, restlens1=0.018007, end ncluster = 3 cluster_segs = [[RB.DistanceSpringDamperSegment(restlencs[i], kc, prestress=pre) for i in 1:5n-1] for _ in 1:ncluster] - cluster_sps = [[RB.SlidingPoint(0.01) for i in 1:5n-2] for _ in 1:ncluster] + cluster_sps = [[RB.SlidingPoint(1e-2) for i in 1:5n-2] for _ in 1:ncluster] matrix_cnt_raw = Vector{Matrix{Int}}() diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl index 285cd11..1137b42 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl @@ -188,11 +188,11 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache end if !isconverged - Res_stepk!(Res,xₖ) - Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) - write("j1.bin", Jac) - FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) - write("j2.bin", Jac) + # Res_stepk!(Res,xₖ) + # Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) + # write("j1.bin", Jac) + # FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) + # write("j2.bin", Jac) if exception error("Not Converged! Step=$timestep, normRes=$normRes") else diff --git a/test/vis.jl b/test/vis.jl index 0f3b34c..a107e66 100644 --- a/test/vis.jl +++ b/test/vis.jl @@ -255,6 +255,8 @@ function plot_traj!(bot::RB.Robot; # mesh!(ax, m0_blue2) # mesh!(ax, m0_blue3) # mesh!(ax, m0_blue4) + # hidezdecorations!(ax) + # hideydecorations!(ax) xlims!(ax,xmin,xmax) ylims!(ax,ymin,ymax) diff --git a/yard/jixiebi/Group2_1 copy.jl b/yard/jixiebi/Group2_1 copy.jl new file mode 100644 index 0000000..725dc1f --- /dev/null +++ b/yard/jixiebi/Group2_1 copy.jl @@ -0,0 +1,311 @@ +using TestEnv +TestEnv.activate() + +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/tensegrity.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +# figdir::String = joinpath(pathof(RB),"../../tmp") +figdir::String = "/home/perseus/Project/LaTeX/contactcable/images" +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl + + +dt = 2e-3 + +A = 0.1 +policy = RB.TimePolicy( + @eponymtuple( + # f = (t) -> [0.0, 0.1t, 0.1t] + f = (t) -> [0.0, + t2acu(t),linestyle=:dot, linewidth=lw, label="Cable 1") + lines!(ax1, 0..tMax, t->acu(t),linestyle=:dash, linewidth=lw, label="Cable 2") + lines!(ax1, 0..tMax, t->0,linestyle=:dashdot, linewidth=lw, label="Cable 3") + axislegend(ax1, nbanks=3) + fig + # figpath = joinpath(figdir, "cylidner_acu.pdf") + # save(figpath, fig; backend=CM) +end + + diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 8330af4..b13a6cf 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -8,7 +8,8 @@ using AbbreviatedStackTraces #jl ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl -figdir::String = joinpath(pathof(RB),"../../tmp") +# figdir::String = joinpath(pathof(RB),"../../tmp") +figdir::String = "/home/perseus/Project/LaTeX/contactcable/images" include(joinpath(pathof(RB),"../../test/vis.jl")) includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl @@ -18,28 +19,28 @@ includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl dt = 5e-3 -A = 0.1 +A = 0.000 policy = RB.TimePolicy( @eponymtuple( # f = (t) -> [0.0, 0.1t, 0.1t] f = (t) -> [0.0, - t2acu(t),linestyle=:dot, linewidth=lw, label="Cable 1") + lines!(ax1, 0..tMax, t->acu(t),linestyle=:dash, linewidth=lw, label="Cable 2") + lines!(ax1, 0..tMax, t->0,linestyle=:dashdot, linewidth=lw, label="Cable 3") + axislegend(ax1, nbanks=3) + fig + figpath = joinpath(figdir, "cylidner_acu.pdf") + save(figpath, fig; backend=CM) +end diff --git a/yard/jixiebi/Group2_2.jl b/yard/jixiebi/Group2_2.jl index bf5cad3..fc0346b 100644 --- a/yard/jixiebi/Group2_2.jl +++ b/yard/jixiebi/Group2_2.jl @@ -192,7 +192,7 @@ savefig(fig, "../contact_force2-2.png" ) bot1 = build_small_jixiebi(3) (;structure) = bot1 -(;bodies) = structure +(;bodies, apparatuses) = structure foreach(bodies) do body (;prop, state) = body (;loci_states) = state @@ -204,3 +204,13 @@ foreach(bodies) do body @show force end +foreach(apparatuses) do appar + if appar.id == 1 + forces = [] + (;force) = appar + foreach(force) do f + push!(forces, f.force.state.tension) + end + @show forces + end +end From a32b230ada44b6ee2656ad4952dc2b58956a0511 Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Tue, 30 Apr 2024 15:21:48 +0800 Subject: [PATCH 06/20] rm out-of-place `build_tangent_stiffness_matrix!`; use `spzero` for `build_tangent_stiffness_matrix!`, reduce allocations by half; use broadcast to update spring-dampers. --- src/members/forces/spring_dampers.jl | 12 +- src/structures/linearization.jl | 215 +-------------------------- yard/jixiebi/Group2_1.jl | 13 +- 3 files changed, 25 insertions(+), 215 deletions(-) diff --git a/src/members/forces/spring_dampers.jl b/src/members/forces/spring_dampers.jl index 6e6212a..c86e34b 100644 --- a/src/members/forces/spring_dampers.jl +++ b/src/members/forces/spring_dampers.jl @@ -70,8 +70,10 @@ function update!(cab::DistanceSpringDamper,p1,p2,ṗ1,ṗ2) # state.force .= ṗ2 - ṗ1 # Δṙ # state.lengthdot = (transpose(state.direction)*state.force)/state.length # state.direction ./= state.length - state.start, state.stop = p1, p2 - state.start_vel, state.stop_vel = ṗ1, ṗ2 + state.start .= p1 + state.stop .= p2 + state.start_vel .= ṗ1 + state.stop_vel .= ṗ2 l = p2 - p1 l̇ = ṗ2 - ṗ1 state.length = norm(l) @@ -243,8 +245,10 @@ $(TYPEDSIGNATURES) """ function update!(cab::DistanceSpringDamperSegment, p1, p2, ṗ1, ṗ2, s1, s2) (;k, c, state, prestress) = cab - state.start, state.stop = p1, p2 - state.start_vel, state.stop_vel = ṗ1, ṗ2 + state.start .= p1 + state.stop .= p2 + state.start_vel .= ṗ1 + state.stop_vel .= ṗ2 l = p2 - p1 l̇ = ṗ2 - ṗ1 state.length = norm(l) diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 467fb83..7a44f6d 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -424,212 +424,11 @@ function make_S(st,q0) inner_S end -# Out-of-place ∂Q̌∂q̌ (dispatch) -function build_tangent_stiffness_matrix(st) - build_tangent_stiffness_matrix(st, st.connectivity.tensioned) - build_tangent_stiffness_matrix(st, st.connectivity.jointed) -end - -# Out-of-place ∂Q̌∂q̌ for cables and clustered cables -function build_tangent_stiffness_matrix(st, @eponymargs(connected, clustered)) - ∂Q̌∂q̌1 = build_tangent_stiffness_matrix(st, @eponymtuple(connected)) - ∂Q̌∂q̌2 = build_tangent_stiffness_matrix(st, @eponymtuple(clustered)) - return ∂Q̌∂q̌1 + ∂Q̌∂q̌2 -end - -# Out-of-place ∂Q̌∂q̌ for cables -function build_tangent_stiffness_matrix(st,@eponymargs(connected,)) - (;cables) = st.apparatuses - (;indexed) = st.connectivity - (;num_of_full_coords,num_of_free_coords,sys_free_coords_idx,bodyid2sys_free_coords,bodyid2sys_full_coords) = indexed - T = get_numbertype(st) - num_of_dim = get_num_of_dims(st) - ∂Q̌∂q̌ = zeros(T,num_of_free_coords,num_of_free_coords) - D = @MMatrix zeros(T,num_of_dim,num_of_dim) - Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = zeros(T,num_of_dim,num_of_free_coords) - foreach(connected) do cc - cable = cables[cc.id] - (;hen,egg) = cc - rb1 = hen.body - rb2 = egg.body - C1 = rb1.state.cache.Cps[hen.pid] - C2 = rb2.state.cache.Cps[egg.pid] - free_idx1 = rb1.state.cache.free_idx - free_idx2 = rb2.state.cache.free_idx - mfree1 = bodyid2sys_free_coords[rb1.prop.id] - mfree2 = bodyid2sys_free_coords[rb2.prop.id] - (;k,c,state,slack) = cable - (;direction,tension,length,lengthdot) = state - if slack && (tension==0) - ∂Q̌∂q̌ .= 0 - else - D .= direction*transpose(direction) - density = tension/length - β = c*lengthdot/length + density - D .*= k-β - D .+= β.*Im - J̌ .= 0 - J̌[:,mfree2] .+= C2[:,free_idx2] - J̌[:,mfree1] .-= C1[:,free_idx1] - ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ - end - # ∂Q̌∂q̌_full[mfree2,mfree2] .+= transpose(C2)*D*C2 - # ∂Q̌∂q̌_full[mfree1,mfree2] .-= transpose(C1)*D*C2 - # ∂Q̌∂q̌_full[mfree2,mfree1] .-= transpose(C2)*D*C1 - # ∂Q̌∂q̌_full[mfree1,mfree1] .+= transpose(C1)*D*C1 - end - return ∂Q̌∂q̌ -end - -# Out-of-place ∂Q̌∂q̌ for cluster cables -function build_tangent_stiffness_matrix(st,@eponymargs(clustered)) - (;clustercables) = st.apparatuses - (;indexed) = st.connectivity - (;num_of_full_coords,num_of_free_coords,sys_free_coords_idx,bodyid2sys_free_coords,bodyid2sys_full_coords) = indexed - T = get_numbertype(st) - num_of_dim = get_num_of_dims(st) - ∂Q̌∂q̌ = zeros(T,num_of_free_coords,num_of_free_coords) - D = @MMatrix zeros(T,num_of_dim,num_of_dim) - Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = zeros(T,num_of_dim,num_of_free_coords) - i = 0 - foreach(clustered) do clustercable - i += 1 - foreach(clustercable) do cc - cable = clustercables[i].segs[cc.id] - (;hen,egg) = cc - rb1 = hen.body - rb2 = egg.body - C1 = rb1.state.cache.Cps[hen.pid] - C2 = rb2.state.cache.Cps[egg.pid] - free_idx1 = rb1.state.cache.free_idx - free_idx2 = rb2.state.cache.free_idx - mfree1 = bodyid2sys_free_coords[rb1.prop.id] - mfree2 = bodyid2sys_free_coords[rb2.prop.id] - (;k,c,state) = cable - (;direction,tension,length,lengthdot) = state - if tension==0 - ∂Q̌∂q̌ .-= 0 - else - D .= direction*transpose(direction) - density = tension/length - β = c*lengthdot/length + density - D .*= k-β - D .+= β.*Im - J̌ .= 0 - J̌[:,mfree2] .+= C2[:,free_idx2] - J̌[:,mfree1] .-= C1[:,free_idx1] - ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ - end - end - end - return ∂Q̌∂q̌ -end - -# Out-of-place ∂Q̌∂q̌̇ (dispatch) -function build_tangent_damping_matrix(st) - build_tangent_damping_matrix(st, st.connectivity.tensioned) -end - -# Out-of-place ∂Q̌∂q̌̇ for cables and clustered cables -function build_tangent_damping_matrix(st, @eponymargs(connected, clustered)) - ∂Q̌∂q̌̇1 = build_tangent_damping_matrix(st, @eponymtuple(connected)) - ∂Q̌∂q̌̇2 = build_tangent_damping_matrix(st, @eponymtuple(clustered)) - return ∂Q̌∂q̌̇1 + ∂Q̌∂q̌̇2 -end - -# Out-of-place ∂Q̌∂q̌̇ for cables -function build_tangent_damping_matrix(st, @eponymargs(connected, )) - (;cables) = st.apparatuses - (;indexed) = st.connectivity - (;num_of_full_coords,num_of_free_coords,sys_free_coords_idx,bodyid2sys_free_coords,bodyid2sys_full_coords) = indexed - T = get_numbertype(st) - num_of_dim = get_num_of_dims(st) - ∂Q̌∂q̌̇ = zeros(T,num_of_free_coords,num_of_free_coords) - D = @MMatrix zeros(T,num_of_dim,num_of_dim) - Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = zeros(T,num_of_dim,num_of_free_coords) - foreach(connected) do cc - cable = cables[cc.id] - (;hen,egg) = cc - rb1 = hen.body - rb2 = egg.body - C1 = rb1.state.cache.Cps[hen.pid] - C2 = rb2.state.cache.Cps[egg.pid] - free_idx1 = rb1.state.cache.free_idx - free_idx2 = rb2.state.cache.free_idx - mfree1 = bodyid2sys_free_coords[rb1.prop.id] - mfree2 = bodyid2sys_free_coords[rb2.prop.id] - (;k,c,state,slack) = cable - (;direction,tension) = state - if slack && (tension == 0) - ∂Q̌∂q̌̇ .-= 0 - else - D .= direction*transpose(direction) - D .*= c - J̌ .= 0 - J̌[:,mfree2] .+= C2[:,free_idx2] - J̌[:,mfree1] .-= C1[:,free_idx1] - - ∂Q̌∂q̌̇ .-= transpose(J̌)*D*J̌ - end - # ∂Q̌∂q̌_full[mfrjiexee2,mfree2] .+= transpose(C2)*D*C2 - # ∂Q̌∂q̌_full[mfree1,mfree2] .-= transpose(C1)*D*C2 - # ∂Q̌∂q̌_full[mfree2,mfree1] .-= transpose(C2)*D*C1 - # ∂Q̌∂q̌_full[mfree1,mfree1] .+= transpose(C1)*D*C1 - end - return ∂Q̌∂q̌̇ -end - -# Out-of-place ∂Q̌∂q̌̇ for clustered cables -function build_tangent_damping_matrix(st, @eponymargs(clustered, )) - (;clustercables) = st.apparatuses - (;indexed) = st.connectivity - (;num_of_full_coords,num_of_free_coords,sys_free_coords_idx,bodyid2sys_free_coords,bodyid2sys_full_coords) = indexed - T = get_numbertype(st) - num_of_dim = get_num_of_dims(st) - ∂Q̌∂q̌̇ = zeros(T,num_of_free_coords,num_of_free_coords) - D = @MMatrix zeros(T,num_of_dim,num_of_dim) - Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = zeros(T,num_of_dim,num_of_free_coords) - i = 0 - foreach(clustered) do clustercable - i += 1 - foreach(clustercable) do cc - cable = clustercables[i].segs[cc.id] - (;hen,egg) = cc - rb1 = hen.body - rb2 = egg.body - C1 = rb1.state.cache.Cps[hen.pid] - C2 = rb2.state.cache.Cps[egg.pid] - free_idx1 = rb1.state.cache.free_idx - free_idx2 = rb2.state.cache.free_idx - mfree1 = bodyid2sys_free_coords[rb1.prop.id] - mfree2 = bodyid2sys_free_coords[rb2.prop.id] - (;k,c,state) = cable - (;direction,tension) = state - if tension == 0 - ∂Q̌∂q̌̇ .-= 0 - else - D .= direction*transpose(direction) - D .*= c - J̌ .= 0 - J̌[:,mfree2] .+= C2[:,free_idx2] - J̌[:,mfree1] .-= C1[:,free_idx1] - - ∂Q̌∂q̌̇ .-= transpose(J̌)*D*J̌ - end - end - end - return ∂Q̌∂q̌̇ -end - - # In-place ∂Q̌∂q̌ for cables and flexible bodies function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::AbstractBody,q,st) #default do nothing end + function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus,q,st) #default do nothing end @@ -656,9 +455,9 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo T = get_numbertype(st) num_of_dim = get_num_of_dims(st) - D = @MMatrix zeros(T,num_of_dim,num_of_dim) + D = spzeros(T,num_of_dim,num_of_dim) Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = zeros(T,num_of_dim,num_of_free_coords) + J̌ = spzeros(T,num_of_dim,num_of_free_coords) (;hen,egg) = appar.joint.hen2egg body_hen = hen.body @@ -684,7 +483,9 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo J̌ .= 0 J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] - ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ + JDJ = transpose(J̌)*sparse(D)*J̌ + @show typeof(JDJ) + ∂Q̌∂q̌ .-= JDJ end end @@ -702,7 +503,7 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo num_of_dim = get_num_of_dims(st) D = @MMatrix zeros(T,num_of_dim,num_of_dim) Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = zeros(T,num_of_dim,num_of_free_coords) + J̌ = spzeros(T,num_of_dim,num_of_free_coords) (;hen,egg) = appar.joint.hen2egg body_hen = hen.body @@ -807,7 +608,7 @@ function build_tangent_damping_matrix!(∂Q̌∂q̌̇,st) # ∂Q̌∂q̌̇ = zeros(T,num_of_free_coords,num_of_free_coords) D = @MMatrix zeros(T,num_of_dim,num_of_dim) Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = zeros(T,num_of_dim,num_of_free_coords) + J̌ = spzeros(T,num_of_dim,num_of_free_coords) foreach(apparatuses) do appar if appar.joint isa CableJoint spring_damper = appar.force diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 8330af4..2b55a58 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -36,6 +36,12 @@ rigid_contacts = RB.ContactRigidBodies( ] ) +nq = RB.get_num_of_free_coords(bot1.structure) + +K = zeros(nq,nq) +RB.build_tangent_stiffness_matrix!(K,bot1.structure) +@time RB.build_tangent_stiffness_matrix!(K,bot1.structure) + # parameters restitution_coefficients = 0.0 friction_coefficients = 0.1 @@ -48,8 +54,7 @@ fig = plot_traj!(bot1; # doslide = false, ) - -RB.solve!( +@time RB.solve!( RB.DynamicsProblem( bot1,policy, # ground_plane, @@ -69,11 +74,11 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 30.0), + tspan=(0.0, 2.0), dt, ftol=1e-7,verbose=true, maxiters=50 - ) +) tw = 468 fontsize = 10 GM.activate!(scalefactor=4.0) From b4aec300864c310ae9095027d1c990cd33c3de06 Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Wed, 1 May 2024 15:49:21 +0800 Subject: [PATCH 07/20] add `ApparatusCache` with `JointCache` and `ForceCache`; use force_cache for `build_tangent_damping_matrix!` and `build_tangent_damping_matrix!`; add `AbstractForce` and `AbstractJoint` types; reuse `ClusterDistanceSpringDampers` for `ClusterJoint` apparatus; rename `jointed_sys_free_idx` to `appar_sys_free_idx`; --- src/Rible.jl | 4 +- src/control/actuators.jl | 2 +- src/get.jl | 4 + src/members/apparatus.jl | 172 +++++++++++++++++++- src/members/forces/spring_dampers.jl | 42 ++--- src/members/joints.jl | 157 ++++-------------- src/postprocess/vis.jl | 6 +- src/structures/connectivity.jl | 15 +- src/structures/constraints.jl | 24 +-- src/structures/linearization.jl | 234 +++++++++++++++------------ src/structures/mutate.jl | 8 +- src/structures/structure.jl | 16 +- yard/jixiebi/Group2_1.jl | 18 ++- 13 files changed, 402 insertions(+), 300 deletions(-) diff --git a/src/Rible.jl b/src/Rible.jl index a75452e..d072d5c 100644 --- a/src/Rible.jl +++ b/src/Rible.jl @@ -113,12 +113,12 @@ import .ANCF include("members/flexibles/flexible_body.jl") -include("members/apparatus.jl") - include("members/forces/spring_dampers.jl") include("members/joints.jl") +include("members/apparatus.jl") + include("structures/connectivity.jl") include("structures/structure.jl") diff --git a/src/control/actuators.jl b/src/control/actuators.jl index 9edc267..47fc5fc 100644 --- a/src/control/actuators.jl +++ b/src/control/actuators.jl @@ -100,7 +100,7 @@ end function execute!(structure::Structure,actuator::ExternalForceActuator{<:Apparatus{<:ClusterJoint},<:NaiveOperator},u) (;id,signifier,operator,force) = actuator (;state) = structure - segs = signifier.force + (;segs) = signifier.force segs[1].force.state.restlen = segs[1].force.original_restlen - u[1] end diff --git a/src/get.jl b/src/get.jl index 2a9596f..60b8932 100644 --- a/src/get.jl +++ b/src/get.jl @@ -135,6 +135,10 @@ get_numbertype(bodies::AbstractVector) = get_numbertype(bodies[begin]) get_numbertype(bodies::TypeSortedCollection) = get_numbertype(bodies.data[1]) get_numbertype(body::BodyType) where {BodyType<:AbstractBody{N,T}} where {N,T} = T +get_numbertype(appar::Apparatus) = get_numbertype((appar.joint,appar.force)) +get_numbertype(appar::Tuple{<:AbstractJoint,<:AbstractForce}) = get_numbertype(appar.joint) +get_numbertype(appar::Tuple{NoJoint,<:AbstractForce}) = get_numbertype(appar.force) + """ Return the system's number of constraints. $(TYPEDSIGNATURES) diff --git a/src/members/apparatus.jl b/src/members/apparatus.jl index 8a54088..5056fa8 100644 --- a/src/members/apparatus.jl +++ b/src/members/apparatus.jl @@ -1,10 +1,69 @@ -struct Apparatus{jointType,forceType} +struct JointCache{φType,AType,FJType} + # cstr + φ::φType + # cstr Jacobian + A::AType + # cstr force Jacobian, symmetric + ∂Aᵀλ∂q::FJType + # cstr velocity Jacobian + ∂Aq̇∂q::AType +end + +struct ForceCache{FType,KType,CType} + Q::FType + #∂Q∂q + K::KType + #∂Q∂q̇ + C::CType +end + +struct ApparatusCache{JCache,FCache} + joint_cache::JCache + force_cache::FCache +end + +struct Apparatus{jointType,forceType,cacheType} id::Int joint::jointType force::forceType num_of_add_var::Int full_coords_idx::Vector{Int} free_coords_idx::Vector{Int} + cache::cacheType +end + +function Apparatus(id::Int,joint::AbstractJoint,force::AbstractForce, + num_of_add_var::Int,full_coords_idx,free_coords_idx + ) + T = get_numbertype(joint) + ## T = get_numbertype(force) + (;num_of_cstr,) = joint + num_appar_free_idx = length(free_coords_idx) + + φ = zeros(T,num_of_cstr) + A = zeros(T,num_of_cstr,num_appar_free_idx) + ∂Aᵀλ∂q = zeros(T,num_appar_free_idx) + ∂Aq̇∂q = zeros(T,num_of_cstr,num_appar_free_idx) + joint_cache = JointCache( + φ, + A, + ∂Aᵀλ∂q, + ∂Aq̇∂q + ) + + Q = zeros(T,num_appar_free_idx) + K = zeros(T,num_appar_free_idx,num_appar_free_idx) + C = zeros(T,num_appar_free_idx,num_appar_free_idx) + force_cache = ForceCache( + Q, + K, + C + ) + cache = ApparatusCache( + joint_cache, + force_cache, + ) + Apparatus(id,joint,force,num_of_add_var,full_coords_idx,free_coords_idx,cache) end function Base.isless(a::Apparatus,b::Apparatus) @@ -12,3 +71,114 @@ function Base.isless(a::Apparatus,b::Apparatus) end get_id(appar::Apparatus) = appar.id + + +function get_appar_idx(appar::Apparatus{<:LinearJoint},bodyid2sys_free_coords) + (;body) = appar.joint + bid = body.prop.id + bodyid2sys_free_coords[bid] +end + +function get_appar_idx(appar::Apparatus{<:jointType},bodyid2sys_free_coords) where {jointType<:Union{PrototypeJoint,CableJoint}} + (;joint) = appar + (;hen,egg) = joint.hen2egg + id_hen = hen.body.prop.id + id_egg = egg.body.prop.id + free_hen = bodyid2sys_free_coords[id_hen] + free_egg = bodyid2sys_free_coords[id_egg] + appar_free_coords_idx = vcat( + free_hen, + free_egg + ) + appar_free_coords_idx +end + +function get_appar_idx(appar::Apparatus,bodyid2sys_free_coords) + Int[] +end + + +function FixedIndicesConstraint(id::Int,body,idx,violations) + num_of_cstr = length(idx) + num_of_coords = get_num_of_coords(body) + T = get_numbertype(body) + A = zeros(T,num_of_cstr,num_of_coords) + for (i,j) in enumerate(idx) + A[i,j] = 1 + end + joint = LinearJoint(body,num_of_cstr,A,violations) + full_idx, free_idx = get_joint_idx(joint) + force = NoForce() + Apparatus( + id, + joint, + force, + 0, + full_idx, free_idx + ) +end + +""" +A prototype joint is defined for a `Hen2Egg`. + +Translation uses either the axis on Hen or on Egg. + +Rotation uses the axis on Egg, because the local angular velocity is defined relative to Egg. + +The order of translation and rotation matters! + +$(TYPEDSIGNATURES) +""" +function PrototypeJoint(id,hen2egg,force,joint_type::Symbol) + (;hen,egg) = hen2egg + joint_info = get_joint_info(joint_type) + (; ntrl, nrot, + num_of_dof, num_of_cstr, + mask_1st, + mask_2nd, + mask_3rd_hen, + mask_3rd_egg, + mask_4th, + ) = joint_info + mask_3rd = vcat(mask_3rd_hen,mask_3rd_egg.+3) + nmcs_hen = hen.body.coords.nmcs + nmcs_egg = egg.body.coords.nmcs + + state_hen = hen.body.state + state_egg = egg.body.state + q_hen,_ = cartesian_frame2coords(nmcs_hen,state_hen.origin_frame) + q_egg,_ = cartesian_frame2coords(nmcs_egg,state_egg.origin_frame) + + cache, values = build_joint_cache( + nmcs_hen,nmcs_egg, + hen.body.prop.loci[hen.pid].position, + egg.body.prop.loci[egg.pid].position, + hen.body.prop.loci[hen.trlid].axes, + egg.body.prop.loci[egg.trlid].axes, + hen.body.prop.loci[hen.rotid].axes, + egg.body.prop.loci[egg.rotid].axes, + mask_1st,mask_2nd,mask_3rd,mask_4th, + q_hen,q_egg + ) + # @show mask_1st,mask_2nd,mask_3rd,mask_4th + # @show values + joint = PrototypeJoint( + hen2egg, + num_of_cstr, + num_of_dof, + mask_1st, + mask_2nd, + mask_3rd, + mask_4th, + values, + cache + ) + full_idx, free_idx = get_joint_idx(joint) + Apparatus( + id, + joint, + force, + 0, + full_idx, free_idx + ) +end diff --git a/src/members/forces/spring_dampers.jl b/src/members/forces/spring_dampers.jl index c86e34b..b7d5fe7 100644 --- a/src/members/forces/spring_dampers.jl +++ b/src/members/forces/spring_dampers.jl @@ -1,3 +1,6 @@ +abstract type AbstractForce end +struct NoForce <: AbstractForce end + """ $(TYPEDEF) """ @@ -35,7 +38,7 @@ end """ $(TYPEDEF) """ -struct DistanceSpringDamper{N,T} +struct DistanceSpringDamper{N,T} <: AbstractForce k::T c::T slack::Bool @@ -131,7 +134,7 @@ end """ $(TYPEDEF) """ -struct RotationalSpringDamper{N,T} +struct RotationalSpringDamper{N,T} <: AbstractForce k::T c::T slack::Bool @@ -204,7 +207,7 @@ function SMADistanceSpringDamperState(temp,restlen,direction) end -struct SMADistanceSpringDamper{N,T,F} +struct SMADistanceSpringDamper{N,T,F} <: AbstractForce id::Int law::F c::T @@ -217,16 +220,7 @@ function SMADistanceSpringDamper3D(restlen::T,law::LawT,c::T,original_temp::T=0. SMADistanceSpringDamper(law,c,state) end -mutable struct SlidingPoint{T} - μ::T - θ::T - α::T - s::T - s⁺::T - s⁻::T -end - -struct DistanceSpringDamperSegment{N,T} +struct DistanceSpringDamperSegment{N,T} <: AbstractForce k::T c::T prestress::T @@ -264,27 +258,25 @@ function update!(cab::DistanceSpringDamperSegment, p1, p2, ṗ1, ṗ2, s1, s2) state.force .= state.tension.*state.direction end -function calculate_α(μ,θ) - exp(-μ*θ) +mutable struct SlidingPoint{T} + μ::T + θ::T + α::T + s::T + s⁺::T + s⁻::T end function SlidingPoint(μ) θ = one(μ) * 2pi - α = calculate_α(μ, θ) + α = exp(-μ*θ) s = zero(μ) s⁺, s⁻ = s2s̄(s) SlidingPoint(μ, θ, α, s, s⁺, s⁻) end -struct ClusterDistanceSpringDampers{spsType,segsType} - sps::spsType - segs::segsType -end - -function ClusterDistanceSpringDampers(segs; μ=0.0) - nsp = length(segs) - 1 - sps = StructArray([SlidingPoint(μ) for i = 1:nsp]) - ClusterDistanceSpringDampers(sps, segs) +struct ClusterDistanceSpringDampers{seg} <: AbstractForce + segs::Vector{seg} end function s2s̄(s::Number) diff --git a/src/members/joints.jl b/src/members/joints.jl index fddc1cc..9f67abd 100644 --- a/src/members/joints.jl +++ b/src/members/joints.jl @@ -1,5 +1,6 @@ #todo parameterization of joints abstract type AbstractJoint end +struct NoJoint <: AbstractJoint end """ $(TYPEDEF) @@ -29,12 +30,6 @@ function get_joint_idx(joint::LinearJoint) full_idx, free_idx end -function get_appar_idx(appar::Apparatus{<:LinearJoint},bodyid2sys_free_coords) - (;body) = appar.joint - bid = body.prop.id - bodyid2sys_free_coords[bid] -end - function FixedBodyConstraint(id::Int,body::AbstractBody) nmcs = body.coords.nmcs state = body.state @@ -47,26 +42,6 @@ function FixedBodyConstraint(id::Int,body::AbstractBody) FixedIndicesConstraint(id,body,independent_free_idx,violations) end -function FixedIndicesConstraint(id::Int,body,idx,violations) - num_of_cstr = length(idx) - num_of_coords = get_num_of_coords(body) - T = get_numbertype(body) - A = zeros(T,num_of_cstr,num_of_coords) - for (i,j) in enumerate(idx) - A[i,j] = 1 - end - joint = LinearJoint(body,num_of_cstr,A,violations) - full_idx, free_idx = get_joint_idx(joint) - force = nothing - Apparatus( - id, - joint, - force, - 0, - full_idx, free_idx - ) -end - function get_joint_info(joint_type::Symbol) (joint_type == :FloatingSpherical) && (return (ntrl = 3, nrot = 3, num_of_dof = 6, num_of_cstr = 0, mask_1st = Int[] , mask_2nd = Int[], mask_3rd_hen = Int[], mask_3rd_egg = Int[], mask_4th = Int[] )) (joint_type == :OrbitalSpherical) && (return (ntrl = 2, nrot = 3, num_of_dof = 5, num_of_cstr = 1, mask_1st = Int[] , mask_2nd = [1] , mask_3rd_hen = Int[], mask_3rd_egg = Int[], mask_4th = Int[] )) @@ -91,27 +66,27 @@ function get_joint_info(joint_type::Symbol) (joint_type == :Fixed) && (return (ntrl = 0, nrot = 0, num_of_dof = 0, num_of_cstr = 6, mask_1st = [1,2,3], mask_2nd = Int[], mask_3rd_hen = Int[], mask_3rd_egg = Int[], mask_4th = [1,2,3])) #t'*b, t'*n, b'*n end -FloatingSphericalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:FloatingSpherical) -OrbitalSphericalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:OrbitalSpherical) -PlanarSphericalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:PlanarSpherical) -PrismaticSphericalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:PrismaticSpherical) -SphericalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Spherical) -FloatingUniversalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:FloatingUniversal) -OrbitalUniversalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:OrbitalUniversal) -PlanarUniversalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:PlanarUniversal) -PrismaticUniversalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:PrismaticUniversal) -UniversalPrismaticJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:UniversalPrismatic) -UniversalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Universal) -FloatingRevoluteJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:FloatingRevolute) -OrbitalRevoluteJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:OrbitalRevolute) -PlanarRevoluteJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:PlanarRevolute) -CylindricalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Cylindrical) -RevoluteJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Revolute) -FloatingJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Floating) -OrbitalJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Orbital) -PlanarJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Planar) -PrismaticJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Prismatic) -FixedJoint(id,hen2egg,force=nothing) = PrototypeJoint(id,hen2egg,force,:Fixed) +FloatingSphericalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:FloatingSpherical) +OrbitalSphericalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:OrbitalSpherical) +PlanarSphericalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:PlanarSpherical) +PrismaticSphericalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:PrismaticSpherical) +SphericalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Spherical) +FloatingUniversalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:FloatingUniversal) +OrbitalUniversalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:OrbitalUniversal) +PlanarUniversalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:PlanarUniversal) +PrismaticUniversalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:PrismaticUniversal) +UniversalPrismaticJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:UniversalPrismatic) +UniversalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Universal) +FloatingRevoluteJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:FloatingRevolute) +OrbitalRevoluteJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:OrbitalRevolute) +PlanarRevoluteJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:PlanarRevolute) +CylindricalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Cylindrical) +RevoluteJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Revolute) +FloatingJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Floating) +OrbitalJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Orbital) +PlanarJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Planar) +PrismaticJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Prismatic) +FixedJoint(id,hen2egg,force=NoForce()) = PrototypeJoint(id,hen2egg,force,:Fixed) const PinJoint = SphericalJoint @@ -130,70 +105,6 @@ struct PrototypeJoint{hen2eggType,maskType,valueType,cacheType} <: AbstractJoint cache::cacheType end -""" -A prototype joint is defined for a `Hen2Egg`. - -Translation uses either the axis on Hen or on Egg. - -Rotation uses the axis on Egg, because the local angular velocity is defined relative to Egg. - -The order of translation and rotation matters! - -$(TYPEDSIGNATURES) -""" -function PrototypeJoint(id,hen2egg,force,joint_type::Symbol) - (;hen,egg) = hen2egg - joint_info = get_joint_info(joint_type) - (; ntrl, nrot, - num_of_dof, num_of_cstr, - mask_1st, - mask_2nd, - mask_3rd_hen, - mask_3rd_egg, - mask_4th, - ) = joint_info - mask_3rd = vcat(mask_3rd_hen,mask_3rd_egg.+3) - nmcs_hen = hen.body.coords.nmcs - nmcs_egg = egg.body.coords.nmcs - - state_hen = hen.body.state - state_egg = egg.body.state - q_hen,_ = cartesian_frame2coords(nmcs_hen,state_hen.origin_frame) - q_egg,_ = cartesian_frame2coords(nmcs_egg,state_egg.origin_frame) - - cache, values = build_joint_cache( - nmcs_hen,nmcs_egg, - hen.body.prop.loci[hen.pid].position, - egg.body.prop.loci[egg.pid].position, - hen.body.prop.loci[hen.trlid].axes, - egg.body.prop.loci[egg.trlid].axes, - hen.body.prop.loci[hen.rotid].axes, - egg.body.prop.loci[egg.rotid].axes, - mask_1st,mask_2nd,mask_3rd,mask_4th, - q_hen,q_egg - ) - # @show mask_1st,mask_2nd,mask_3rd,mask_4th - # @show values - joint = PrototypeJoint( - hen2egg, - num_of_cstr, - num_of_dof, - mask_1st, - mask_2nd, - mask_3rd, - mask_4th, - values, - cache - ) - full_idx, free_idx = get_joint_idx(joint) - Apparatus( - id, - joint, - force, - 0, - full_idx, free_idx - ) -end """ $(TYPEDEF) @@ -203,11 +114,12 @@ struct CableJoint{hen2eggType} <: AbstractJoint num_of_cstr::Int end -struct ClusterJoint{SlidingPointsType} <: AbstractJoint - sps::SlidingPointsType +struct ClusterJoint{spType} <: AbstractJoint + sps::Vector{spType} num_of_cstr::Int end +get_numbertype(::ClusterJoint{SlidingPoint{T}}) where{T} = T function get_joint_idx(joint::Union{PrototypeJoint,CableJoint}) (;hen,egg) = joint.hen2egg @@ -228,20 +140,9 @@ function get_joint_idx(joint::Union{PrototypeJoint,CableJoint}) full_idx, free_idx end -function get_appar_idx(appar::Apparatus{<:jointType},bodyid2sys_free_coords) where {jointType<:Union{PrototypeJoint,CableJoint}} - (;joint) = appar - (;hen,egg) = joint.hen2egg - id_hen = hen.body.prop.id - id_egg = egg.body.prop.id - free_hen = bodyid2sys_free_coords[id_hen] - free_egg = bodyid2sys_free_coords[id_egg] - sys_free_coords_idx = vcat( - free_hen, - free_egg - ) - sys_free_coords_idx +function get_numbertype(joint::Union{PrototypeJoint,CableJoint}) + get_numbertype(joint.hen2egg.hen.body) end -function get_appar_idx(appar::Apparatus,bodyid2sys_free_coords) - Int[] -end + +get_numbertype(::LinearJoint{T}) where{T} = T \ No newline at end of file diff --git a/src/postprocess/vis.jl b/src/postprocess/vis.jl index ad01b5c..eb53c8f 100644 --- a/src/postprocess/vis.jl +++ b/src/postprocess/vis.jl @@ -94,10 +94,10 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; ) where {S<:Apparatus{<:ClusterJoint}} cluster_cable_ob = viz[:structure] # foreach(cluster_cable_ob[].force) do cluster_seg - n_segs = length(cluster_cable_ob[].force) + n_segs = length(cluster_cable_ob[].force.segs) for i in 1:n_segs - seg_ob = lift(cluster_cable_ob) do seg - iseg = seg.force[i].force + seg_ob = lift(cluster_cable_ob) do cluster_cable + iseg = cluster_cable.force.segs[i].force point_start = iseg.state.start |> GB.Point point_stop = iseg.state.stop |> GB.Point [(point_start, point_stop)] diff --git a/src/structures/connectivity.jl b/src/structures/connectivity.jl index 54cc1bb..767a569 100644 --- a/src/structures/connectivity.jl +++ b/src/structures/connectivity.jl @@ -34,8 +34,6 @@ function connect_clusters(bodies, cluster_sps, cluster_segs, cms) for (cluster_seg, cm) in zip(cluster_segs, cms) @assert size(cm, 2) == 4 rbs_sorted = sort(bodies) - #DONE 这里ret的类型是Vector{Any}, 导致下面的Apparatus不是concrete, 会影响运算性能, 建议修改 - ret = Vector{Apparatus{<:CableJoint, <:DistanceSpringDamperSegment}}(undef, size(cm, 1)) j = 0 clusterID += 1 ret = [ @@ -46,19 +44,20 @@ function connect_clusters(bodies, cluster_sps, cluster_segs, cms) Hen2Egg(Signifier(rbs_sorted[rbid1], pid1), Signifier(rbs_sorted[rbid2], pid2)), 0, ) + full_coords_idx, free_coords_idx = get_joint_idx(joint) segs = Apparatus( j, joint, cluster_seg[j], num_segs, - Int[], - Int[] + full_coords_idx, + free_coords_idx ) # push!(ret, segs) segs end for row in eachrow(cm) - ] + ] |> ClusterDistanceSpringDampers num_segs += size(cm, 1) push!(rets, Apparatus(clusterID, ClusterJoint(cluster_sps[clusterID], 0), ret, 2j-2, Int[], Int[])) end @@ -111,8 +110,6 @@ function connect(bodies, spring_dampers; connecting_matrix=Int[;;], istart=0) ret end - - struct Indexed{id2idxType,idxType} num_of_bodies::Int num_of_apparatuses::Int @@ -253,10 +250,10 @@ function index(bodies,apparatuses=Int[];sharing_matrix::AbstractMatrix=Int[;;]) num_of_excst_by_joint[id] = apparatus.joint.num_of_cstr apparid2sys_extrinsic_cstr_idx[id] = collect(num_excst_last+1:num_excst_last+num_of_excst_by_joint[id]) num_excst_last += num_of_excst_by_joint[id] - if !(apparatus.joint isa Nothing) + if !(apparatus.joint isa NoJoint) num_of_joint_apparatuses += 1 end - if !(apparatus.force isa Nothing) + if !(apparatus.force isa NoForce) num_of_force_apparatuses += 1 end end diff --git a/src/structures/constraints.jl b/src/structures/constraints.jl index 1d79b32..4573400 100644 --- a/src/structures/constraints.jl +++ b/src/structures/constraints.jl @@ -6,31 +6,31 @@ end function cstr_jacobian(appar::Apparatus,structure,q) (;apparid2sys_free_coords_idx) = structure.connectivity.indexed - jointed_sys_free_idx = apparid2sys_free_coords_idx[appar.id] + appar_sys_free_idx = apparid2sys_free_coords_idx[appar.id] T = get_numbertype(structure) - zeros(T,0,length(jointed_sys_free_idx)) + zeros(T,0,length(appar_sys_free_idx)) end function cstr_forces_jacobian(appar::Apparatus,structure,q,λ) (;apparid2sys_free_coords_idx) = structure.connectivity.indexed - jointed_sys_free_idx = apparid2sys_free_coords_idx[appar.id] + appar_sys_free_idx = apparid2sys_free_coords_idx[appar.id] T = get_numbertype(structure) - zeros(T,length(jointed_sys_free_idx),length(jointed_sys_free_idx)) + zeros(T,length(appar_sys_free_idx),length(appar_sys_free_idx)) end function cstr_velocity_jacobian(appar::Apparatus,structure,q,q̇) (;apparid2sys_free_coords_idx) = structure.connectivity.indexed - jointed_sys_free_idx = apparid2sys_free_coords_idx[appar.id] + appar_sys_free_idx = apparid2sys_free_coords_idx[appar.id] T = get_numbertype(structure) - zeros(T,0,length(jointed_sys_free_idx)) + zeros(T,0,length(appar_sys_free_idx)) end function cstr_function(appar::Apparatus{<:LinearJoint},structure,q,c) (;indexed) = structure.connectivity - sys_free_coords_idx = indexed.apparid2sys_free_coords_idx[appar.id] + appar_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] (;A,violations) = appar.joint - A*q[sys_free_coords_idx] .- violations + A*q[appar_sys_free_idx] .- violations end function cstr_jacobian(appar::Apparatus{<:LinearJoint},structure,q) @@ -40,16 +40,16 @@ end function cstr_forces_jacobian(appar::Apparatus{<:LinearJoint},structure,q,λ) (;indexed) = structure.connectivity - sys_free_coords_idx = indexed.apparid2sys_free_coords_idx[appar.id] - n = length(sys_free_coords_idx) + appar_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] + n = length(appar_sys_free_idx) zeros(eltype(λ),n,n) end function cstr_velocity_jacobian(appar::Apparatus{<:LinearJoint},structure,q,q̇) (;indexed) = structure.connectivity - sys_free_coords_idx = indexed.apparid2sys_free_coords_idx[appar.id] + appar_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] (;num_of_cstr,) = appar.joint - n = length(sys_free_coords_idx) + n = length(appar_sys_free_idx) zeros(eltype(q̇),num_of_cstr,n) end diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 7a44f6d..4cfdfb6 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -28,8 +28,8 @@ function cstr_forces_jacobian(st::AbstractStructure,q,λ) if get_num_of_dims(st) == 3 foreach(apparatuses) do appar joint_cstr_idx = num_of_intrinsic_cstr .+ apparid2sys_extrinsic_cstr_idx[appar.id] - jointed_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] - ret[jointed_sys_free_idx,jointed_sys_free_idx] .+= cstr_forces_jacobian(appar,st,q,λ[joint_cstr_idx]) + appar_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] + ret[appar_sys_free_idx,appar_sys_free_idx] .+= cstr_forces_jacobian(appar,st,q,λ[joint_cstr_idx]) end end ret @@ -57,8 +57,8 @@ function cstr_velocity_jacobian(st::AbstractStructure,q,q̇) if get_num_of_dims(st) == 3 foreach(apparatuses) do appar joint_cstr_idx = num_of_intrinsic_cstr .+ apparid2sys_extrinsic_cstr_idx[appar.id] - jointed_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] - ret[joint_cstr_idx,jointed_sys_free_idx] .= cstr_velocity_jacobian(appar,st,q,q̇) + appar_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] + ret[joint_cstr_idx,appar_sys_free_idx] .= cstr_velocity_jacobian(appar,st,q,q̇) end end ret @@ -447,33 +447,33 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo (;indexed,numbered) = st.connectivity (; - num_of_free_coords, - bodyid2sys_free_coords, - bodyid2sys_full_coords, apparid2sys_free_coords_idx ) = indexed - + (;joint, force, cache) = appar + (;joint_cache, force_cache) = cache T = get_numbertype(st) num_of_dim = get_num_of_dims(st) - D = spzeros(T,num_of_dim,num_of_dim) + appar_free_coords_idx = apparid2sys_free_coords_idx[appar.id] + num_of_appar_free_idx = length(appar_free_coords_idx) + D = @MMatrix zeros(T,num_of_dim,num_of_dim) Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = spzeros(T,num_of_dim,num_of_free_coords) + J̌ = zeros(T,num_of_dim,num_of_appar_free_idx) - (;hen,egg) = appar.joint.hen2egg + (;hen,egg) = joint.hen2egg body_hen = hen.body body_egg = egg.body C_hen = body_hen.cache.Cps[hen.pid] C_egg = body_egg.cache.Cps[egg.pid] - free_idx_hen = body_hen.coords.free_idx - free_idx_egg = body_egg.coords.free_idx - mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] - mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] - (;k,c,state,slack) = appar.force + free_idx_hen = hen.body.coords.free_idx + free_idx_egg = egg.body.coords.free_idx + ncoords_hen = length(free_idx_hen) + ncoords_egg = length(free_idx_egg) + (;k,c,state,slack) = force (;direction,tension) = state l = state.length l̇ = state.lengthdot if slack && (tension==0) - ∂Q̌∂q̌ .-= 0 + ## ∂Q̌∂q̌ .-= 0 else D .= direction*transpose(direction) density = tension/l @@ -481,11 +481,11 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo D .*= k-β D .+= β.*Im J̌ .= 0 - J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] - J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] - JDJ = transpose(J̌)*sparse(D)*J̌ - @show typeof(JDJ) - ∂Q̌∂q̌ .-= JDJ + J̌[:,free_idx_hen] .-= C_hen[:,free_idx_hen] + J̌[:,ncoords_hen.+free_idx_egg] .+= C_egg[:,free_idx_egg] + force_cache.K .= -transpose(J̌)*D*J̌ + ## @show typeof(JDJ) + ∂Q̌∂q̌[appar_free_coords_idx,appar_free_coords_idx] .+= force_cache.K end end @@ -493,28 +493,29 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo (;indexed,numbered) = st.connectivity (; - num_of_free_coords, bodyid2sys_free_coords, - bodyid2sys_full_coords, apparid2sys_free_coords_idx ) = indexed - + (;joint, force, cache) = appar + (;joint_cache, force_cache) = cache T = get_numbertype(st) num_of_dim = get_num_of_dims(st) + appar_free_coords_idx = get_appar_idx(appar,bodyid2sys_free_coords) + num_of_appar_free_idx = length(appar_free_coords_idx) D = @MMatrix zeros(T,num_of_dim,num_of_dim) Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = spzeros(T,num_of_dim,num_of_free_coords) + J̌ = zeros(T,num_of_dim,num_of_appar_free_idx) - (;hen,egg) = appar.joint.hen2egg + (;hen,egg) = joint.hen2egg body_hen = hen.body body_egg = egg.body C_hen = body_hen.cache.Cps[hen.pid] C_egg = body_egg.cache.Cps[egg.pid] free_idx_hen = body_hen.coords.free_idx free_idx_egg = body_egg.coords.free_idx - mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] - mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] - (;k,c,state) = appar.force + ncoords_hen = length(free_idx_hen) + ncoords_egg = length(free_idx_egg) + (;k,c,state) = force (;direction,tension) = state l = state.length l̇ = state.lengthdot @@ -524,13 +525,17 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo D .*= k-β D .+= β.*Im J̌ .= 0 - J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] - J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] - ∂Q̌∂q̌ .-= transpose(J̌)*D*J̌ + J̌[:,free_idx_hen] .-= C_hen[:,free_idx_hen] + J̌[:,ncoords_hen.+free_idx_egg] .+= C_egg[:,free_idx_egg] + ## @show size(J̌),size(force_cache.K) + force_cache.K .= -transpose(J̌)*D*J̌ + ## @tullio force_cache.K[i,j] = -J̌[k,i]*D[k,l]*J̌[l,j] + ## @show typeof(JDJ) + ∂Q̌∂q̌[appar_free_coords_idx,appar_free_coords_idx] .+= force_cache.K end function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:ClusterJoint},q,st) - foreach(appar.force) do seg + foreach(appar.force.segs) do seg build_tangent_stiffness_matrix!(∂Q̌∂q̌,seg,q,st) end end @@ -547,7 +552,6 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{JointType ) = cache full_idx = appar.full_coords_idx free_idx = appar.free_coords_idx - sys_free_coords_idx = apparid2sys_free_coords_idx[appar.id] (;mask,k) = appar.force (;hen,egg) = hen2egg nmcs_hen = hen.body.coords.nmcs @@ -583,10 +587,8 @@ end # In-place ∂Q̌∂q̌ for cables and flexible bodies function build_tangent_stiffness_matrix!(∂Q̌∂q̌,st) (;bodies,apparatuses,connectivity) = st - q = get_coords(st) - num_of_dim = get_num_of_dims(st) - # ∂Q̌∂q̌ = zeros(T,num_of_free_coords,num_of_free_coords) + q = get_coords(st) foreach(bodies) do body build_tangent_stiffness_matrix!(∂Q̌∂q̌,body,q,st) end @@ -594,53 +596,73 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,st) foreach(apparatuses) do appar build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar,q,st) end +end + +# In-place ∂Q̌∂q̌̇ for cables and flexible bodies +function build_tangent_damping_matrix!(∂Q̌∂q̌̇,body::AbstractBody,q,st) + #default do nothing +end - return ∂Q̌∂q̌ +function build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar::Apparatus,q,st) + #default do nothing end -# In-place ∂Q̌∂q̌̇ for cables -function build_tangent_damping_matrix!(∂Q̌∂q̌̇,st) - (;apparatuses,connectivity) = st - (;numbered,indexed) = connectivity - (;num_of_full_coords,num_of_free_coords,sys_free_coords_idx,bodyid2sys_free_coords,bodyid2sys_full_coords) = indexed +function build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar::Apparatus{<:CableJoint},q,st) + + (;indexed,numbered) = st.connectivity + (; + apparid2sys_free_coords_idx + ) = indexed + (;joint, force, cache) = appar + (;joint_cache, force_cache) = cache T = get_numbertype(st) num_of_dim = get_num_of_dims(st) - # ∂Q̌∂q̌̇ = zeros(T,num_of_free_coords,num_of_free_coords) + appar_free_coords_idx = apparid2sys_free_coords_idx[appar.id] + num_of_appar_free_idx = length(appar_free_coords_idx) D = @MMatrix zeros(T,num_of_dim,num_of_dim) Im = Symmetric(SMatrix{num_of_dim,num_of_dim}(one(T)*I)) - J̌ = spzeros(T,num_of_dim,num_of_free_coords) + J̌ = zeros(T,num_of_dim,num_of_appar_free_idx) + + (;hen,egg) = joint.hen2egg + body_hen = hen.body + body_egg = egg.body + C_hen = body_hen.cache.Cps[hen.pid] + C_egg = body_egg.cache.Cps[egg.pid] + free_idx_hen = body_hen.coords.free_idx + free_idx_egg = body_egg.coords.free_idx + ncoords_hen = length(free_idx_hen) + ncoords_egg = length(free_idx_egg) + (;k,c,state,slack) = force + (;direction,tension) = state + if slack && (tension == 0) + ∂Q̌∂q̌̇ .-= 0 + else + D .= direction*transpose(direction) + D .*= c + J̌ .= 0 + J̌[:,free_idx_hen] .-= C_hen[:,free_idx_hen] + J̌[:,ncoords_hen.+free_idx_egg] .+= C_egg[:,free_idx_egg] + force_cache.C .= -transpose(J̌)*D*J̌ + + ∂Q̌∂q̌̇[appar_free_coords_idx,appar_free_coords_idx] .+= force_cache.C + end + # ∂Q̌∂q̌_full[mfree_egg,mfree_egg] .+= transpose(C_egg)*D*C_egg + # ∂Q̌∂q̌_full[mfree_hen,mfree_egg] .-= transpose(C_hen)*D*C_egg + # ∂Q̌∂q̌_full[mfree_egg,mfree_hen] .-= transpose(C_egg)*D*C_hen + # ∂Q̌∂q̌_full[mfree_hen,mfree_hen] .+= transpose(C_hen)*D*C_hen +end + +# In-place ∂Q̌∂q̌̇ for cables +function build_tangent_damping_matrix!(∂Q̌∂q̌̇,st) + (;apparatuses,) = st + + q = get_coords(st) + foreach(apparatuses) do appar - if appar.joint isa CableJoint - spring_damper = appar.force - (;hen,egg) = appar.joint.hen2egg - body_hen = hen.body - body_egg = egg.body - C_hen = body_hen.cache.Cps[hen.pid] - C_egg = body_egg.cache.Cps[egg.pid] - free_idx_hen = body_hen.coords.free_idx - free_idx_egg = body_egg.coords.free_idx - mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] - mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] - (;k,c,state,slack) = spring_damper - (;direction,tension) = state - if slack && (tension == 0) - ∂Q̌∂q̌̇ .-= 0 - else - D .= direction*transpose(direction) - D .*= c - J̌ .= 0 - J̌[:,mfree_egg] .+= C_egg[:,free_idx_egg] - J̌[:,mfree_hen] .-= C_hen[:,free_idx_hen] - - ∂Q̌∂q̌̇ .-= transpose(J̌)*D*J̌ - end - # ∂Q̌∂q̌_full[mfree_egg,mfree_egg] .+= transpose(C_egg)*D*C_egg - # ∂Q̌∂q̌_full[mfree_hen,mfree_egg] .-= transpose(C_hen)*D*C_egg - # ∂Q̌∂q̌_full[mfree_egg,mfree_hen] .-= transpose(C_egg)*D*C_hen - # ∂Q̌∂q̌_full[mfree_hen,mfree_hen] .+= transpose(C_hen)*D*C_hen - end + build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar,q,st) end end + function init_cluster_matrix(st) (; bodies, apparatuses, connectivity) = st (; indexed, numbered) = connectivity @@ -677,11 +699,12 @@ function init_cluster_matrix(st) if isa(appar.joint, ClusterJoint) (; force, joint, id) = appar (; sps) = joint - nsegs = length(force) + (; segs) = force + nsegs = length(segs) nsp = length(sps) sp_idx = apparid2sys_add_var_idx[id] sp_idx_begin = Int((sp_idx[1]-1) / 2) - foreach(force) do seg + foreach(segs) do seg kc_idx = seg.id + seg.num_of_add_var kc[kc_idx] = seg.force.k end @@ -697,7 +720,6 @@ function init_cluster_matrix(st) b_list[id] = vcat(b⁺, b⁻) T_list[id] = get_TransMatrix(nsegs - 1) - nsegs = length(force) N_segs = zeros(Float64, nsegs, 2nsegs - 2) N_segs[1, 1:2] = [1 -1] N_segs[end, end-1:end] = [-1 1] @@ -739,8 +761,8 @@ function build_∂Q̌∂s̄!(∂Q̌∂s̄, cluster_cache, st) J̌ = zeros(T, num_of_dim, num_of_free_coords) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - (; force) = appar - foreach(force) do seg + (; segs) = appar.force + foreach(segs) do seg idx = seg.id + seg.num_of_add_var (; hen, egg) = seg.joint.hen2egg body_hen = hen.body @@ -855,11 +877,12 @@ function build_ζ!(ζ, cluster_cache, st) if isa(appar.joint, ClusterJoint) (; force, joint, id) = appar (; sps) = joint + (; segs) = force nsp = length(sps) idx_begin = Int((apparid2sys_add_var_idx[id][1]-1) / 2) for i in 1:nsp - ζ⁺[idx_begin+i] = force[i+1].force.state.tension / sps[i].α - force[i].force.state.tension - ζ⁻[idx_begin+i] = force[i].force.state.tension - sps[i].α * force[i+1].force.state.tension + ζ⁺[idx_begin+i] = segs[i+1].force.state.tension / sps[i].α - segs[i].force.state.tension + ζ⁻[idx_begin+i] = segs[i].force.state.tension - sps[i].α * segs[i+1].force.state.tension end end end @@ -884,8 +907,8 @@ function build_ζ(st) nsp = length(sps) idx_begin = Int((apparid2sys_add_var_idx[id][1]-1) / 2) for i in 1:nsp - ζ⁺[idx_begin+i] = force[i+1].force.state.tension / sps[i].α - force[i].force.state.tension - ζ⁻[idx_begin+i] = force[i].force.state.tension - sps[i].α * force[i+1].force.state.tension + ζ⁺[idx_begin+i] = segs[i+1].force.state.tension / sps[i].α - segs[i].force.state.tension + ζ⁻[idx_begin+i] = segs[i].force.state.tension - sps[i].α * segs[i+1].force.state.tension end end end @@ -894,23 +917,25 @@ end function get_clusterA(st) (; apparatuses) = st - nc = 0 + nc_ref = Ref(0) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - nc += 1 + nc_ref[] += 1 end end + nc = nc_ref[] A_list = [Matrix{Float64}(undef, 1, 1) for _ in 1:nc] foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) (; force, joint, id) = appar (; sps) = joint + (; segs) = force n = length(sps) - ap = [-force[i+1].force.k for i in 1:n-1] - ap0 = [force[i].force.k + force[i+1].force.k/sps[i].α for i in 1:n] - ap1 = [-force[i+1].force.k/sps[i].α for i in 1:n-1] - an0 = [force[i].force.k + force[i+1].force.k*sps[i].α for i in 1:n] - an1 = [-force[i+1].force.k*sps[i].α for i in 1:n-1] + ap = [-segs[i+1].force.k for i in 1:n-1] + ap0 = [segs[i].force.k + segs[i+1].force.k/sps[i].α for i in 1:n] + ap1 = [-segs[i+1].force.k/sps[i].α for i in 1:n-1] + an0 = [segs[i].force.k + segs[i+1].force.k*sps[i].α for i in 1:n] + an1 = [-segs[i+1].force.k*sps[i].α for i in 1:n-1] A⁺ = diagm(-1=>ap, 0=>ap0, 1=>ap1) A⁻ = diagm(-1=>ap, 0=>an0, 1=>an1) A = [A⁺ -A⁺; -A⁻ A⁻] @@ -934,18 +959,20 @@ end function build_∂ζ∂s̄(st) (; apparatuses) = st - nc = 0 + nc_ref = Ref(0) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - nc += 1 + nc_ref[] += 1 end end + nc = nc_ref[] A_list = [SparseMatrixCSC{Float64,Int64}(undef, 1, 1) for _ in 1:nc] clusterA = get_clusterA(st) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) (; force, id) = appar - nsegs = length(force) + (; segs) = force + nsegs = length(segs) T = get_TransMatrix(nsegs - 1) A = T*clusterA[id]*T' A_list[id] = A @@ -962,8 +989,8 @@ function build_∂ζ∂q!(∂ζ∂q, cluster_cache, st) ∂l∂q = zeros(T, ns+nc, num_of_free_coords) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - (; force) = appar - foreach(force) do seg + (; segs) = appar.force + foreach(segs) do seg idx = seg.id + seg.num_of_add_var J̌ = zeros(T, num_of_dim, num_of_free_coords) (; hen, egg) = seg.joint.hen2egg @@ -992,14 +1019,16 @@ function build_∂ζ∂q(st) (; num_of_free_coords, bodyid2sys_free_coords, apparid2sys_add_var_idx) = indexed T = get_numbertype(st) num_of_dim = get_num_of_dims(st) - ns = 0 - nc = 0 + ns_ref = Ref(0) + nc_ref = Ref(0) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - ns += length(appar.joint.sps) - nc += 1 + ns_ref[] += length(appar.joint.sps) + nc_ref[] += 1 end end + ns = ns_ref[] + nc = nc_ref[] ∂l∂q = zeros(T, ns+nc, num_of_free_coords) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) @@ -1031,11 +1060,12 @@ function build_∂ζ∂q(st) if isa(appar.joint, ClusterJoint) (; force, joint, id) = appar (; sps) = joint - nsegs = length(force) + (; segs) = force + nsegs = length(segs) nsp = length(sps) sp_idx = apparid2sys_add_var_idx[id] sp_idx_begin = Int((sp_idx[1]-1) / 2) - foreach(force) do seg + foreach(segs) do seg kc_idx = seg.id + seg.num_of_add_var kc[kc_idx] = seg.force.k end diff --git a/src/structures/mutate.jl b/src/structures/mutate.jl index 10fb2be..e72f268 100644 --- a/src/structures/mutate.jl +++ b/src/structures/mutate.jl @@ -91,8 +91,9 @@ end function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:ClusterJoint}) (;id, joint, force) = appar (;sps) = joint - nAppar = length(appar.force) - for (idx, iappar) in enumerate(force) + (;segs) = force + nAppar = length(segs) + for (idx, iappar) in enumerate(segs) ijoint = iappar.joint iforce = iappar.force hen = ijoint.hen2egg.hen @@ -141,7 +142,8 @@ function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:PrototypeJo ) = cache full_idx = appar.full_coords_idx free_idx = appar.free_coords_idx - sys_free_coords_idx = apparid2sys_free_coords_idx[appar.id] + appar_sys_free_idx = apparid2sys_free_coords_idx[appar.id] + @show appar_sys_free_idx spring_damper = appar.force (;mask,k) = spring_damper (;hen,egg) = hen2egg diff --git a/src/structures/structure.jl b/src/structures/structure.jl index 6e5c01d..7e17aa8 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -368,8 +368,8 @@ function cstr_jacobian(structure::AbstractStructure,q,c=get_local_coords(structu ext = apparid2sys_extrinsic_cstr_idx[id] if !isempty(ext) jointexcst = num_of_intrinsic_cstr.+apparid2sys_extrinsic_cstr_idx[id] - jointed_sys_free_idx = apparid2sys_free_coords_idx[id] - ret[jointexcst,jointed_sys_free_idx] .= cstr_jacobian(appar,structure,q) + appar_sys_free_idx = apparid2sys_free_coords_idx[id] + ret[jointexcst,appar_sys_free_idx] .= cstr_jacobian(appar,structure,q) end end ret @@ -442,11 +442,11 @@ function build_ψ(structure::AbstractStructure) foreach(apparatuses) do appar if isa(appar, Apparatus{<:ClusterJoint}) (;sps) = appar.joint - (;force) = appar + (;segs) = appar.force nsi = length(sps) for (i, sp) in enumerate(sps) - ζ⁺ = force[i+1].force.state.tension/sp.α - force[i].force.state.tension - ζ⁻ = force[i].force.state.tension - sp.α*force[i+1].force.state.tension + ζ⁺ = segs[i+1].force.state.tension/sp.α - segs[i].force.state.tension + ζ⁻ = segs[i].force.state.tension - sp.α*segs[i+1].force.state.tension ψ⁺[is+i] = FB(ζ⁺, s⁺[is+i]) ψ⁻[is+i] = FB(ζ⁻, s⁻[is+i]) end @@ -571,8 +571,8 @@ function check_constraints_consistency(st;tol=1e-14) end end foreach(apparatuses) do appar - sys_free_coords_idx = indexed.apparid2sys_free_coords_idx[appar.id] - q̇_jointed = state.system.q̌̇[sys_free_coords_idx] + appar_sys_free_idx = indexed.apparid2sys_free_coords_idx[appar.id] + q̇_jointed = state.system.q̌̇[appar_sys_free_idx] Aq̇_joint = cstr_jacobian(appar,st,q)*q̇_jointed norm_velocity_joint = norm(Aq̇_joint) if norm_velocity_joint > tol @@ -628,7 +628,7 @@ function potential_energy(st::Structure;gravity=false) V[] += potential_energy_gravity(st) end foreach(st.apparatuses) do appar - if !(appar.force isa Nothing) + if !(appar.force isa NoForce) V[] += potential_energy(appar.force) end end diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 2b55a58..854a214 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -15,7 +15,6 @@ includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl include(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl - dt = 5e-3 A = 0.1 @@ -36,16 +35,23 @@ rigid_contacts = RB.ContactRigidBodies( ] ) +# parameters +restitution_coefficients = 0.0 +friction_coefficients = 0.1 +bot1 = build_small_jixiebi(3) + nq = RB.get_num_of_free_coords(bot1.structure) K = zeros(nq,nq) RB.build_tangent_stiffness_matrix!(K,bot1.structure) @time RB.build_tangent_stiffness_matrix!(K,bot1.structure) -# parameters -restitution_coefficients = 0.0 -friction_coefficients = 0.1 -bot1 = build_small_jixiebi(3) + +C = zeros(nq,nq) + +RB.build_tangent_damping_matrix!(K,bot1.structure) +@time RB.build_tangent_damping_matrix!(K,bot1.structure) + fig = plot_traj!(bot1; # atsteps=[3320], showground = false, @@ -54,7 +60,7 @@ fig = plot_traj!(bot1; # doslide = false, ) -@time RB.solve!( +@time RB.solve!( RB.DynamicsProblem( bot1,policy, # ground_plane, From 8aaa31d76f0a0fc14e26d674b750e5b64839300f Mon Sep 17 00:00:00 2001 From: Perseus Date: Wed, 1 May 2024 17:15:36 +0800 Subject: [PATCH 08/20] fix bugs --- src/structures/linearization.jl | 15 ++++++++------- yard/jixiebi/Group2_1 copy.jl | 2 +- yard/jixiebi/Group2_1.jl | 22 +++++++++++----------- 3 files changed, 20 insertions(+), 19 deletions(-) diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 4cfdfb6..8893fd4 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -819,9 +819,9 @@ function build_∂Q̌∂s̄(st) kc = zeros(T, ns + nc) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - (; force) = appar - nsegs = length(force) - for seg in force + (; segs) = appar.force + nsegs = length(segs) + for seg in segs (; id, num_of_add_var) = seg kc[id+num_of_add_var] = seg.force.k end @@ -837,8 +837,8 @@ function build_∂Q̌∂s̄(st) N = reduce(blockdiag, N_list) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - (; force) = appar - foreach(force) do seg + (; segs) = appar.force + foreach(segs) do seg idx = seg.id + seg.num_of_add_var (; hen, egg) = seg.joint.hen2egg body_hen = hen.body @@ -904,6 +904,7 @@ function build_ζ(st) if isa(appar.joint, ClusterJoint) (; force, joint, id) = appar (; sps) = joint + (; segs) = force nsp = length(sps) idx_begin = Int((apparid2sys_add_var_idx[id][1]-1) / 2) for i in 1:nsp @@ -1032,8 +1033,8 @@ function build_∂ζ∂q(st) ∂l∂q = zeros(T, ns+nc, num_of_free_coords) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) - (; force) = appar - foreach(force) do seg + (; segs) = appar.force + foreach(segs) do seg idx = seg.id + seg.num_of_add_var J̌ = zeros(T, num_of_dim, num_of_free_coords) (; hen, egg) = seg.joint.hen2egg diff --git a/yard/jixiebi/Group2_1 copy.jl b/yard/jixiebi/Group2_1 copy.jl index 725dc1f..9e169ee 100644 --- a/yard/jixiebi/Group2_1 copy.jl +++ b/yard/jixiebi/Group2_1 copy.jl @@ -69,7 +69,7 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 30.0), + tspan=(0.0, 3.0), dt, ftol=1e-7,verbose=true, maxiters=50 diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 06193b8..e31d8e6 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -18,7 +18,7 @@ includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl dt = 5e-3 -A = 0.000 +A = 0.1 policy = RB.TimePolicy( @eponymtuple( # f = (t) -> [0.0, 0.1t, 0.1t] @@ -39,7 +39,7 @@ rigid_contacts = RB.ContactRigidBodies( # parameters restitution_coefficients = 0.0 friction_coefficients = 0.1 -bot1 = build_small_jixiebi(3) +bot1 = build_small_jixiebi(3, object=:cylinder) nq = RB.get_num_of_free_coords(bot1.structure) @@ -61,22 +61,22 @@ fig = plot_traj!(bot1; # doslide = false, ) -@time RB.solve!( +RB.solve!( RB.DynamicsProblem( bot1,policy, # ground_plane, - # rigid_contacts, - # RB.RestitutionFrictionCombined( - # RB.NewtonRestitution(), - # RB.CoulombFriction(), - # ), + rigid_contacts, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ), RB.EulerEytelwein(), ), RB.DynamicsSolver( RB.Zhong06(), - # RB.InnerLayerContactSolver( - # RB.InteriorPointMethod() - # ), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ), RB.MonolithicApparatusSolver( RB.SmoothedFischerBurmeister() ), From c0a71f5e61d50fb3887d136f8faaa43b05641520 Mon Sep 17 00:00:00 2001 From: Perseus Date: Wed, 1 May 2024 22:49:41 +0800 Subject: [PATCH 09/20] reduce allocation --- src/members/apparatus.jl | 21 +++++++++++++ src/members/joints.jl | 20 +++++++++++++ src/structures/connectivity.jl | 4 +-- src/structures/linearization.jl | 52 ++++++++++++++++++++++++++------- yard/jixiebi/Group2_1 copy.jl | 6 ++-- 5 files changed, 87 insertions(+), 16 deletions(-) diff --git a/src/members/apparatus.jl b/src/members/apparatus.jl index 5056fa8..40387e7 100644 --- a/src/members/apparatus.jl +++ b/src/members/apparatus.jl @@ -93,6 +93,27 @@ function get_appar_idx(appar::Apparatus{<:jointType},bodyid2sys_free_coords) whe appar_free_coords_idx end +function get_appar_idx(appar::Apparatus{<:ClusterJoint},bodyid2sys_free_coords) + (; segs) = appar.force + first_hen_id = segs[1].joint.hen2egg.hen.body.prop.id + first_egg_id = segs[1].joint.hen2egg.egg.body.prop.id + first_hen_free = bodyid2sys_free_coords[first_hen_id] + first_egg_free = bodyid2sys_free_coords[first_egg_id] + appar_free_coords_idx = vcat( + first_hen_free, + first_egg_free + ) + for seg in segs[2:end] + (;id) = seg.joint.hen2egg.egg.body.prop + free_idx = bodyid2sys_free_coords[id] + appar_free_coords_idx = vcat( + appar_free_coords_idx, + free_idx + ) + end + appar_free_coords_idx +end + function get_appar_idx(appar::Apparatus,bodyid2sys_free_coords) Int[] end diff --git a/src/members/joints.jl b/src/members/joints.jl index 9f67abd..91c97d6 100644 --- a/src/members/joints.jl +++ b/src/members/joints.jl @@ -140,6 +140,26 @@ function get_joint_idx(joint::Union{PrototypeJoint,CableJoint}) full_idx, free_idx end +# for clustercables seg +function get_joint_idx(beginIdx, joint::Union{PrototypeJoint,CableJoint}) + (;hen,egg) = joint.hen2egg + nmcs_hen = hen.body.coords.nmcs + nmcs_egg = egg.body.coords.nmcs + free_idx_hen = hen.body.coords.free_idx + free_idx_egg = egg.body.coords.free_idx + ncoords_hen = get_num_of_coords(nmcs_hen) + ncoords_egg = get_num_of_coords(nmcs_egg) + full_idx = vcat( + collect(1:ncoords_hen), + collect(1:ncoords_egg) .+ ncoords_hen + ) .+ beginIdx + free_idx = vcat( + free_idx_hen, + free_idx_egg .+ ncoords_hen + ) .+ beginIdx + beginIdx+ncoords_hen, full_idx, free_idx +end + function get_numbertype(joint::Union{PrototypeJoint,CableJoint}) get_numbertype(joint.hen2egg.hen.body) end diff --git a/src/structures/connectivity.jl b/src/structures/connectivity.jl index 767a569..cd8ad70 100644 --- a/src/structures/connectivity.jl +++ b/src/structures/connectivity.jl @@ -36,6 +36,7 @@ function connect_clusters(bodies, cluster_sps, cluster_segs, cms) rbs_sorted = sort(bodies) j = 0 clusterID += 1 + beginIdx = 0 ret = [ begin rbid1, pid1, rbid2, pid2 = row @@ -44,7 +45,7 @@ function connect_clusters(bodies, cluster_sps, cluster_segs, cms) Hen2Egg(Signifier(rbs_sorted[rbid1], pid1), Signifier(rbs_sorted[rbid2], pid2)), 0, ) - full_coords_idx, free_coords_idx = get_joint_idx(joint) + beginIdx, full_coords_idx, free_coords_idx = get_joint_idx(beginIdx, joint) segs = Apparatus( j, joint, @@ -53,7 +54,6 @@ function connect_clusters(bodies, cluster_sps, cluster_segs, cms) full_coords_idx, free_coords_idx ) - # push!(ret, segs) segs end for row in eachrow(cm) diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 8893fd4..dc459c5 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -753,38 +753,68 @@ function build_∂Q̌∂s̄!(∂Q̌∂s̄, cluster_cache, st) num_of_free_coords, bodyid2sys_free_coords, bodyid2sys_full_coords, - apparid2sys_free_coords_idx + apparid2sys_free_coords_idx, + apparid2sys_add_var_idx ) = indexed (;T, num_of_dim, ns, kc, N) = cluster_cache D = zeros(T, num_of_dim) - lkn = zeros(T, 2ns, num_of_dim) - J̌ = zeros(T, num_of_dim, num_of_free_coords) + # lkn = zeros(T, 2ns, num_of_dim) + # J̌ = zeros(T, num_of_dim, num_of_free_coords) foreach(apparatuses) do appar if isa(appar.joint, ClusterJoint) + appar_free_coords_idx = apparid2sys_free_coords_idx[appar.id] (; segs) = appar.force + clustercable_id = appar.id + nsegs = length(segs) foreach(segs) do seg - idx = seg.id + seg.num_of_add_var + (; free_coords_idx, id, num_of_add_var) = seg (; hen, egg) = seg.joint.hen2egg + if id == 1 + cluster_idx = collect(1:2) + elseif id == nsegs + cluster_idx = collect(2nsegs-3:2nsegs-2) + else + cluster_idx = collect(2id-3:2id) + end + num_of_cluster_idx = length(cluster_idx) + num_free_coords_idx = length(free_coords_idx) + seg_free_coords_idx = appar_free_coords_idx[free_coords_idx] + J̌ = zeros(T,num_of_dim,num_free_coords_idx) + lkn = zeros(T, num_of_cluster_idx, num_of_dim) + idx = id + num_of_add_var + cluster_idx .+= apparid2sys_add_var_idx[clustercable_id][1]-1 body_hen = hen.body body_egg = egg.body C_hen = body_hen.cache.Cps[hen.pid] C_egg = body_egg.cache.Cps[egg.pid] free_idx_hen = body_hen.coords.free_idx free_idx_egg = body_egg.coords.free_idx - mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] - mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] + ncoords_hen = length(free_idx_hen) + ncoords_egg = length(free_idx_egg) + # mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] + # mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] (; k, c, state) = seg.force (; direction, tension) = state if tension == 0 - ∂Q̌∂s̄ .-= 0 + # ∂Q̌∂s̄ .-= 0 else D .= direction J̌ .= 0 - J̌[:, mfree_egg] .+= C_egg[:, free_idx_egg] - J̌[:, mfree_hen] .-= C_hen[:, free_idx_hen] - kN = kc[idx] .* N[idx, :] + # J̌[:, mfree_egg] .+= C_egg[:, free_idx_egg] + # J̌[:, mfree_hen] .-= C_hen[:, free_idx_hen] + J̌[:,free_idx_hen] .-= C_hen[:,free_idx_hen] + J̌[:,ncoords_hen.+free_idx_egg] .+= C_egg[:,free_idx_egg] + # @show cluster_idx + kN = kc[idx] .* N[idx, cluster_idx] @tullio lkn[k, l] = D[l] * kN[k] - ∂Q̌∂s̄ .-= lkn * J̌ + # if idx <= 3 + # @show idx + # @show size(lkn), size(J̌) + # display(lkn) + # display(J̌) + # end + ∂Q̌∂s̄[cluster_idx, seg_free_coords_idx] .-= lkn * J̌ + # ∂Q̌∂s̄[appar_free_coords_idx, appar_free_coords_idx] .-= lkn * J̌ end end end diff --git a/yard/jixiebi/Group2_1 copy.jl b/yard/jixiebi/Group2_1 copy.jl index 9e169ee..6869a49 100644 --- a/yard/jixiebi/Group2_1 copy.jl +++ b/yard/jixiebi/Group2_1 copy.jl @@ -17,7 +17,7 @@ include(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) includet(joinpath(pathof(RB),"../../examples/robots/jixiebi.jl")) #jl -dt = 2e-3 +dt = 5e-3 A = 0.1 policy = RB.TimePolicy( @@ -50,7 +50,7 @@ fig = plot_traj!(bot1; ) -RB.solve!( +@profview_allocs RB.solve!( RB.DynamicsProblem( bot1,policy, rigid_contacts, @@ -69,7 +69,7 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 3.0), + tspan=(0.0, 1.0), dt, ftol=1e-7,verbose=true, maxiters=50 From 8b654b37374ce82d0243855bbab7d829444d27ec Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Sun, 12 May 2024 20:15:27 +0800 Subject: [PATCH 10/20] implement torsional spring-dampers with an angle as the additional variable; the additional variables a new independent variables in the dynamics introduce auxiliary equality equations; tested on slider-crank example; add types: `TorsionalSpringDamperState`; `TorsionalSpringDamper`; modify update_apparatus; `update_apparatus!` and `update_apparatuses!` with `s`; `build_tangent_damping_matrix!` signature for apparatuses and bodies; add new functions: `auxi_function!`; `auxi_jacobian!`; `get_num_of_add_var` `has_gravity`; `get_apparatuses`; move codes: `rotation2angles` to `utils`; remove codes: `function update_apparatuses!(st, @eponymargs(clustered,))` --- examples/robots/slider_crank.jl | 29 +++- src/control/control.jl | 5 +- src/get.jl | 2 + src/mechanics/contact.jl | 3 + src/mechanics/dynamics.jl | 38 ++++- .../Zhong06_CCP_constant_mass.jl | 2 +- .../Zhong06_family/Zhong06_constant_mass.jl | 114 +++++++------ src/mechanics/solvers.jl | 4 + src/members/apparatus.jl | 4 +- src/members/forces/spring_dampers.jl | 69 ++++++++ src/members/rigids/rigid_body.jl | 4 +- src/robots/robot.jl | 7 +- src/structures/clustertensegrity.jl | 44 ----- src/structures/constraints.jl | 154 +++++++++++++++++- src/structures/linearization.jl | 123 ++++++++++++-- src/structures/mutate.jl | 104 ++++++++---- src/structures/structure.jl | 76 +++++++-- src/utils.jl | 12 ++ yard/nonsmooth/slider_crank.jl | 31 +++- 19 files changed, 642 insertions(+), 183 deletions(-) diff --git a/examples/robots/slider_crank.jl b/examples/robots/slider_crank.jl index 2d75274..280da46 100644 --- a/examples/robots/slider_crank.jl +++ b/examples/robots/slider_crank.jl @@ -14,7 +14,7 @@ function slider_crank(;θ = 0, coordsType = RB.NCF.NC) ω0 = [ 150.0, -75.0, - ]./100 + ]./100*0.0 b = 0.05 a = 0.025 d = 0.05 @@ -221,9 +221,18 @@ function slider_crank(;θ = 0, coordsType = RB.NCF.NC) rigdibodies = TypeSortedCollection(rbs) j1 = RB.FixedBodyConstraint(1,base) - j2 = RB.RevoluteJoint(2,RB.Hen2Egg(RB.Signifier(base ,1,1),RB.Signifier(link1,1,1))) - j3 = RB.RevoluteJoint(3,RB.Hen2Egg(RB.Signifier(link1,2,2),RB.Signifier(link2,1,1))) - j4 = RB.RevoluteJoint(4,RB.Hen2Egg(RB.Signifier(link2,2,2),RB.Signifier(slider1,5,5))) + j2 = RB.RevoluteJoint(2, + RB.Hen2Egg(RB.Signifier(base ,1,1),RB.Signifier(link1,1,1)), + RB.TorsionalSpringDamper(0.0,100.0;) + ) + j3 = RB.RevoluteJoint(3, + RB.Hen2Egg(RB.Signifier(link1,2,2),RB.Signifier(link2,1,1)), + ## RB.TorsionalSpringDamper(0.0,100.0;), + ) + j4 = RB.RevoluteJoint(4, + RB.Hen2Egg(RB.Signifier(link2,2,2),RB.Signifier(slider1,5,5)), + ## RB.TorsionalSpringDamper(0.0,100.0;) + ) apparatuses = TypeSortedCollection([j1,j2,j3,j4]) @@ -231,5 +240,15 @@ function slider_crank(;θ = 0, coordsType = RB.NCF.NC) indexed = RB.index(rigdibodies,apparatuses) cnt = RB.Connectivity(numbered,indexed) st = RB.Structure(rigdibodies,apparatuses,cnt) - RB.Robot(st,) + # 测量器/传感器, 可测量误差, 之后用于定义cost函数, 实现优化或反馈控制, 目前暂时用不到。 + gauges = Int[] + # 作动器, 依附于一个或多个bodies或apparatuses, 其类型分派给execute!来施加不同的驱动力 + actuators = Int[] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st, gauges, actuators,) + ) + RB.Robot(st,hub) end \ No newline at end of file diff --git a/src/control/control.jl b/src/control/control.jl index e26d2ff..1f0bf18 100644 --- a/src/control/control.jl +++ b/src/control/control.jl @@ -282,7 +282,10 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure::Structur ∂F∂q̌̇ .= ∂F∂u*∂u∂q̌̇ end -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure::Structure,hub,policy::TimePolicy,q::AbstractVector,q̇::AbstractVector,t::Real;gravity=false) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure::Structure,hub,policy::TimePolicy,q,q̇,t::Real,∂F∂s=nothing,s=nothing;gravity=false) +end + +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure::Structure,hub,policy::NoPolicy,q,q̇,t::Real,∂F∂s=nothing,s=nothing;gravity=false) end function set_restlen!(structure,u) diff --git a/src/get.jl b/src/get.jl index 60b8932..cbaf256 100644 --- a/src/get.jl +++ b/src/get.jl @@ -208,6 +208,8 @@ get_cables_force_density(bot::Robot) = get_cables_force_density(bot.structure) get_bodies(bot::Robot) = get_bodies(bot.structure) get_bodies(st::AbstractStructure) = sort(st.bodies) +get_apparatuses(bot::Robot) = get_apparatuses(bot.structure) +get_apparatuses(st::AbstractStructure) = sort(st.apparatuses) get_rigidbars(bot::Robot) = get_rigidbars(bot.structure) diff --git a/src/mechanics/contact.jl b/src/mechanics/contact.jl index bbbafb0..e026db1 100644 --- a/src/mechanics/contact.jl +++ b/src/mechanics/contact.jl @@ -95,6 +95,9 @@ struct GravitySpace{T} <: StaticContactEnvironment gravity::T end +has_gravity(env::AbstractContactEnvironment) = false +has_gravity(env::GravitySpace) = env.gravity + abstract type ContactGeometry end abstract type ContactPrimitive <: ContactGeometry end abstract type ConvexContactPrimitive <: ContactPrimitive end diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index 2d7404c..f7a0232 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -51,7 +51,7 @@ function generalized_force!(F,bot::Robot,::NoPolicy,q,q̇,t,s=nothing;gravity=tr (;structure) = bot clear_forces!(structure) lazy_update_bodies!(structure,q,q̇) - update_apparatuses!(structure) + update_apparatuses!(structure, s) if gravity apply_gravity!(structure;factor=1) end @@ -73,17 +73,19 @@ function generalized_force!(F,bot::Robot,policy::AbstractPolicy,q,q̇,t,s=nothin user_defined_force!(F,t) end -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t,s=nothing) - generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,NoPolicy(),q,q̇,t,s=nothing) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t,∂F∂s=nothing,s=nothing) + generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,NoPolicy(),q,q̇,t,∂F∂s,s) end -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,s=nothing) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,∂F∂s=nothing,s=nothing) (;structure,hub) = bot ∂F∂q̌ .= 0 ∂F∂q̌̇ .= 0 + ∂F∂s .= 0 clear_forces!(structure) lazy_update_bodies!(structure,q,q̇) - update_apparatuses!(structure) + update_apparatuses!(structure, s) + generalized_force_jacobian!(∂F∂s,structure,q,q̇,t,s,) generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) build_tangent_stiffness_matrix!(∂F∂q̌,structure) build_tangent_damping_matrix!(∂F∂q̌̇,structure) @@ -98,7 +100,7 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,∂F∂s̄,∂ζ∂ ζ .= 0 clear_forces!(structure) lazy_update_bodies!(structure,q,q̇) - update_apparatuses!(structure) + update_apparatuses!(structure, s) generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) build_tangent_stiffness_matrix!(∂F∂q̌,structure) build_tangent_damping_matrix!(∂F∂q̌̇,structure) @@ -107,6 +109,26 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,∂F∂s̄,∂ζ∂ build_∂ζ∂q!(∂ζ∂q, cluster_cache, structure) end + +function generalized_force_jacobian!(∂F∂s,structure,q,q̇,t,s,) + (;apparatuses,connectivity) = structure + (; + apparid2sys_add_var_idx, + apparid2sys_free_coords_idx + ) = connectivity.indexed + foreach(apparatuses) do appar + appar_add_var_idx = apparid2sys_add_var_idx[appar.id] + appar_free_coords_idx = apparid2sys_free_coords_idx[appar.id] + generalized_force_jacobian!( + (@view ∂F∂s[appar_free_coords_idx,appar_add_var_idx]), + appar, + structure, + q,q̇,t, + (@view s[appar_add_var_idx]), + ) + end +end + struct ContactCache{cacheType} cache::cacheType end @@ -205,8 +227,8 @@ function activate_frictional_contacts!(structure,contact_env::ContactRigidBodies (;nmcs) = ibody.coords ncoords = get_num_of_coords(nmcs) iq = @MVector zeros(ncoords) - c(x) = NCF.to_local_coords(nmcs,x) - C(c) = NCF.to_position_jacobian(nmcs,iq,c) + c(x) = to_local_coords(nmcs,x) + C(c) = to_position_jacobian(nmcs,iq,c) ibody.cache.Cps[ipid] = C(c(local_pos)) diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl index d95052f..ec19b34 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl @@ -21,7 +21,7 @@ function generate_cache( (;bot,policy,env) = prob (;structure) = bot options = merge( - (gravity=true,factor=1,checkpersist=true), #default + (gravity=has_gravity(env),factor=1,checkpersist=true), #default prob.options, solver.options, ) diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl index 4484b3b..96be820 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl @@ -10,19 +10,20 @@ function generate_cache( dt,kargs... ) (;prob) = simulator - (;bot,policy) = prob + (;bot,policy,env) = prob (;traj,structure) = bot options = merge( - (gravity=true,factor=1,checkpersist=true), #default + (gravity=has_gravity(env),factor=1,checkpersist=true), #default prob.options, solver.options, ) (;M,M⁻¹,M̌,M̌⁻¹,Ḿ,M̄)= build_mass_matrices(structure) A = make_cstr_jacobian(structure) Φ = make_cstr_function(structure) - F!(F,q,q̇,t) = generalized_force!(F,bot,policy,q,q̇,t;gravity=options.gravity) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t) + F!(F,q,q̇,t,s) = generalized_force!(F,bot,policy,q,q̇,t,s;gravity=options.gravity) + Jac_F!(∂F∂q̌,∂F∂q̌̇, ∂F∂s, q,q̇,t, s) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t,∂F∂s,s) q̌0 = traj.q̌[begin] + s0 = traj.s[begin] λ0 = traj.λ[begin] q̇0 = traj.q̇[begin] q̇0 = traj.q̇[begin] @@ -30,21 +31,24 @@ function generate_cache( T = eltype(q̌0) nq̌ = length(q̌0) nλ = length(λ0) + ns = length(s0) ∂F∂q̌ = zeros(T,nq̌,nq̌) ∂F∂q̌̇ = zeros(T,nq̌,nq̌) - nx = nq̌ + nλ - xₖ = vcat(q̌0,λ0) + ∂F∂s = zeros(T,nq̌,ns) + ∂S∂q̌ = zeros(T,ns,nq̌) + ∂S∂s = zeros(T,ns,ns) + nx = nq̌ + nλ + ns + xₖ = vcat(q̌0,λ0,s0) Res = zero(xₖ) Jac = Res*transpose(Res) Zhong06_Constant_Mass_Cache(solver, @eponymtuple( F!,Jac_F!, Ḿ,M̌,M̄,M̌⁻¹,A,Φ, - ∂F∂q̌,∂F∂q̌̇, - nq̌,nλ,nx, + ∂F∂q̌,∂F∂q̌̇,∂F∂s,∂S∂q̌,∂S∂s, + nq̌,nλ,ns,nx, xₖ, - Res, - Jac, + Res,Jac, options ) ) @@ -59,12 +63,12 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; progress=true,exception=true) (;prob,controller,tspan,restart,totalstep) = sim (;bot,) = prob - (;traj) = bot + (;structure,traj) = bot (; F!,Jac_F!, Ḿ,M̌,M̄,M̌⁻¹,A,Φ, - ∂F∂q̌,∂F∂q̌̇, - nq̌,nλ,nx, + ∂F∂q̌,∂F∂q̌̇,∂F∂s,∂S∂q̌,∂S∂s, + nq̌,nλ,ns,nx, xₖ, Res, Jac @@ -73,32 +77,44 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; mass_norm = mr h = dt T = get_numbertype(bot) - function make_Res_stepk(qₖ,q̌ₖ,λₖ,qₖ₋₁,p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) - @inline @inbounds function inner_Res_stepk!(Res,x) + function make_stepk(qₖ,q̌ₖ,λₖ,sₖ,sₖ₋₁,qₖ₋₁,p̌ₖ₋₁,F̌,∂F∂q̌,∂F∂q̌̇,∂F∂s,∂S∂q̌,∂S∂s,Aᵀₖ₋₁,tₖ₋₁) + S = make_auxi_function(structure,deepcopy(sₖ₋₁)) + Jac_S! = make_auxi_jacobian(structure,deepcopy(sₖ₋₁)) + function inner_Res_stepk!(Res,x) q̌ₖ .= x[ 1:nq̌ ] λₖ .= x[nq̌+1:nq̌+nλ] + sₖ .= x[nq̌+nλ+1:nx] qₘ = (qₖ.+qₖ₋₁)./2 q̇ₘ = (qₖ.-qₖ₋₁)./h tₘ = tₖ₋₁+h/2 - F!(F̌,qₘ, q̇ₘ, tₘ) + sₘ = (sₖ .+ sₖ₋₁)./2 + F!(F̌,qₘ, q̇ₘ, tₘ, sₘ) Res[ 1:nq̌ ] .= Ḿ*(qₖ.-qₖ₋₁) .- h.*p̌ₖ₋₁ .- (h^2)/2 .*F̌ .+ mass_norm.*Aᵀₖ₋₁*λₖ Res[nq̌+1:nq̌+nλ] .= mass_norm.*Φ(qₖ) + Res[nq̌+nλ+1:nx] .= S(qₖ,sₖ) end - end - function Jac_stepk!(Jac,x,qₖ,q̌ₖ,qₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) - q̌ₖ .= x[1:nq̌] - qₘ = (qₖ.+qₖ₋₁)./2 - q̇ₘ = (qₖ.-qₖ₋₁)./h - tₘ = tₖ₋₁+h/2 - Jac_F!(∂F∂q̌,∂F∂q̌̇,qₘ,q̇ₘ,tₘ) - Jac[ 1:nq̌ , 1:nq̌ ] .= M̌.-(h^2)/2 .*(1/2 .*∂F∂q̌.+1/h.*∂F∂q̌̇) - Jac[ 1:nq̌ ,nq̌+1:end] .= mass_norm.*Aᵀₖ₋₁ - Jac[nq̌+1:end, 1:nq̌ ] .= mass_norm.*A(qₖ) - Jac[nq̌+1:end,nq̌+1:end] .= 0.0 + function inner_Jac_stepk!(Jac,x,) + q̌ₖ .= x[1:nq̌] + qₘ = (qₖ.+qₖ₋₁)./2 + q̇ₘ = (qₖ.-qₖ₋₁)./h + tₘ = tₖ₋₁+h/2 + sₘ = (sₖ .+ sₖ₋₁)./2 + + Jac_F!(∂F∂q̌,∂F∂q̌̇,∂F∂s,qₘ,q̇ₘ,tₘ,sₘ) + Jac_S!(∂S∂q̌,∂S∂s,qₖ,sₖ) + Jac[ 1:nq̌ , 1:nq̌ ] .= M̌.-(h^2)/2 .*(1/2 .*∂F∂q̌.+1/h.*∂F∂q̌̇) + Jac[ 1:nq̌ ,nq̌+1:nq̌+nλ] .= mass_norm.*Aᵀₖ₋₁ + Jac[nq̌+1:nq̌+nλ, 1:nq̌ ] .= mass_norm.*A(qₖ) + Jac[nq̌+1:nq̌+nλ,nq̌+1:nq̌+nλ] .= 0.0 + Jac[ 1:nq̌, nq̌+nλ+1:nx] .= -(h^2)/2 .*(1/2 .*∂F∂s) + Jac[nq̌+nλ+1:nx,1:nq̌] .= ∂S∂q̌ + Jac[nq̌+nλ+1:nx,nq̌+nλ+1:nx] .= ∂S∂s + end + inner_Res_stepk!, inner_Jac_stepk! end iteration_break = 0 @@ -117,18 +133,20 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; qₖ₋₁ = traj.q[timestep] q̌ₖ₋₁ = traj.q̌[timestep] q̌̇ₖ₋₁ = traj.q̌̇[timestep] - p̌ₖ₋₁ = traj.p̌[timestep] + p̌ₖ₋₁ = traj.p̌[timestep] + sₖ₋₁ = traj.s[timestep] qₖ = traj.q[timestep+1] q̌ₖ = traj.q̌[timestep+1] q̌̇ₖ = traj.q̌̇[timestep+1] q̃̇ₖ = traj.q̃̇[timestep+1] λₖ = traj.λ[timestep+1] + sₖ = traj.s[timestep+1] p̌ₖ = traj.p̌[timestep+1] F̌ = traj.F̌[timestep+1] xₖ[ 1:nq̌] .= q̌ₖ₋₁ .+ h.*q̌̇ₖ₋₁ xₖ[nq̌+1:nq̌+nλ] .= 0 Aᵀₖ₋₁ = transpose(A(qₖ₋₁)) - Res_stepk! = make_Res_stepk(qₖ,q̌ₖ,λₖ,qₖ₋₁,p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) + Res_stepk!,Jac_stepk! = make_stepk(qₖ,q̌ₖ,λₖ,sₖ,sₖ₋₁,qₖ₋₁,p̌ₖ₋₁,F̌,∂F∂q̌,∂F∂q̌̇,∂F∂s,∂S∂q̌,∂S∂s,Aᵀₖ₋₁,tₖ₋₁) isconverged = false normRes = typemax(T) if false #Jac_F! isa Missing @@ -139,23 +157,23 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; Res_stepk_result.iterations xₖ .= Res_stepk_result.zero else - # if timestep == 10 - # Jac_ref = zeros(nq̌+nλ,nq̌+nλ) - # FiniteDiff.finite_difference_jacobian!(Jac_ref,Res_stepk!,xₖ) - # Jac_my = zeros(nq̌+nλ,nq̌+nλ) - # Jac_stepk!(Jac_my,xₖ) - # diff_Jac = Jac_my .- Jac_ref - # diff_Jac[abs.(diff_Jac).<1e-5] .= 0.0 - # diff_rowidx = findall((x)-> x>1e-5,norm.(eachrow(diff_Jac))) - # @show diff_rowidx .- length(q̌ₖ) - # @show diff_Jac[end-4:end-3,:] - # @show findall((x)->abs(x)>0,diff_Jac[114+length(q̌ₖ),:]) - # @show findall((x)->abs(x)>0,diff_Jac[115+length(q̌ₖ),:]) - # @show Jac_my[end-4:end-3,:] - # @show Jac_ref[end-4:end-3,:] - # end - # @show maximum(abs.(diff_Jac))for iteration = 1:maxiters - # @show iteration,D,ηs,restitution_coefficients,gaps + ## if timestep == 100 + ## Jac_ref = zeros(nx,nx) + ## FiniteDiff.finite_difference_jacobian!(Jac_ref,Res_stepk!,xₖ) + ## Jac_my = zeros(nx,nx) + ## Jac_stepk!(Jac_my,xₖ) + ## diff_Jac = Jac_my .- Jac_ref + ## diff_Jac[abs.(diff_Jac).<1e-5] .= 0.0 + ## diff_rowidx = findall((x)-> x>1e-5,norm.(eachrow(diff_Jac))) + ## @show diff_rowidx .- length(q̌ₖ) + ## @show diff_Jac[end-4:end-3,:] + ## @show findall((x)->abs(x)>0,diff_Jac[114+length(q̌ₖ),:]) + ## @show findall((x)->abs(x)>0,diff_Jac[115+length(q̌ₖ),:]) + ## @show Jac_my[ 1:nq̌, nq̌+nλ+1:nx] + ## @show Jac_ref[ 1:nq̌, nq̌+nλ+1:nx] + ## end + ## @show maximum(abs.(diff_Jac))for iteration = 1:maxiters + ## @show iteration,D,ηs,restitution_coefficients,gaps for iteration = 1:maxiters Res_stepk!(Res,xₖ) # @show Res @@ -166,7 +184,7 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; break end # FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) - Jac_stepk!(Jac,xₖ,qₖ,q̌ₖ,qₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) + Jac_stepk!(Jac,xₖ) xₖ .+= Jac\(-Res) end # dfk = OnceDifferentiable(Res_stepk!,Jac_stepk!,xₖ,Res) @@ -182,6 +200,8 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; end q̌ₖ .= xₖ[ 1:nq̌ ] λₖ .= xₖ[nq̌+1:nq̌+nλ] + sₖ .= xₖ[nq̌+nλ+1:nx] + @show timestep, sₖ, sₖ₋₁ Momentum_k!(p̌ₖ,p̌ₖ₋₁,qₖ,qₖ₋₁,λₖ,Ḿ,A,Aᵀₖ₋₁,mass_norm,h) q̌̇ₖ .= M̌⁻¹*(p̌ₖ.-M̄*q̃̇ₖ ) #---------Step k finisher----------- diff --git a/src/mechanics/solvers.jl b/src/mechanics/solvers.jl index 91d6ac0..67eae81 100644 --- a/src/mechanics/solvers.jl +++ b/src/mechanics/solvers.jl @@ -130,6 +130,10 @@ function DynamicsProblem(bot::Robot;options...) DynamicsProblem(bot::Robot,NoPolicy(),GravitySpace(true),Contactless(),Naive(),values(options)) end +function DynamicsProblem(bot::Robot,env::AbstractContactEnvironment;options...) + DynamicsProblem(bot::Robot,NoPolicy(),env,Contactless(),Naive(),values(options)) +end + function DynamicsProblem(bot::Robot,policy::AbstractPolicy;options...) DynamicsProblem(bot::Robot,policy,GravitySpace(true),Contactless(),Naive(),values(options)) end diff --git a/src/members/apparatus.jl b/src/members/apparatus.jl index 5056fa8..2018585 100644 --- a/src/members/apparatus.jl +++ b/src/members/apparatus.jl @@ -97,7 +97,6 @@ function get_appar_idx(appar::Apparatus,bodyid2sys_free_coords) Int[] end - function FixedIndicesConstraint(id::Int,body,idx,violations) num_of_cstr = length(idx) num_of_coords = get_num_of_coords(body) @@ -174,11 +173,12 @@ function PrototypeJoint(id,hen2egg,force,joint_type::Symbol) cache ) full_idx, free_idx = get_joint_idx(joint) + num_add_var = get_num_of_add_var(force) Apparatus( id, joint, force, - 0, + num_add_var, full_idx, free_idx ) end diff --git a/src/members/forces/spring_dampers.jl b/src/members/forces/spring_dampers.jl index b7d5fe7..9b16d69 100644 --- a/src/members/forces/spring_dampers.jl +++ b/src/members/forces/spring_dampers.jl @@ -1,6 +1,8 @@ abstract type AbstractForce end struct NoForce <: AbstractForce end +get_num_of_add_var(::AbstractForce) = 0 + """ $(TYPEDEF) """ @@ -109,6 +111,73 @@ function potential_energy(cab::DistanceSpringDamper) pe = 1/2*k*Δ^2 end + +""" +$(TYPEDEF) +""" +mutable struct TorsionalSpringDamperState{T} + rest_angle::T + angle::T + angular_velocity::T + torque::T +end + +""" +$(TYPEDSIGNATURES) +""" +function TorsionalSpringDamperState(rest_angle) + TorsionalSpringDamperState( + rest_angle, + zero(rest_angle), + zero(rest_angle), + zero(rest_angle), + ) +end + +""" +$(TYPEDEF) +""" +struct TorsionalSpringDamper{T} <: AbstractForce + k::T + c::T + slack::Bool + state::TorsionalSpringDamperState{T} +end + +""" +$(TYPEDSIGNATURES) +""" +function TorsionalSpringDamper(rest_angle::T,k::T,c=zero(k);slack=false) where T + state = TorsionalSpringDamperState(rest_angle) + TorsionalSpringDamper(k,c,slack,state) +end + +get_num_of_add_var(::TorsionalSpringDamper) = 1 + +""" +$(TYPEDSIGNATURES) +""" +function update!(sd::TorsionalSpringDamper,angle,angular_velocity=zero(angle)) + (;k,c,state) = sd + deformation = angle - rest_angle + state.angle = angle + state.angular_velocity = angular_velocity + state.torque = k*deformation + c*state.angular_velocity +end + +""" +$(TYPEDSIGNATURES) +""" +function potential_energy(sd::TorsionalSpringDamper) + (;k,c,state,slack) = sd + Δ⁺ = (state.angle - state.rest_angle) + Δ = ifelse(slack,max(0,Δ⁺),Δ⁺) + ## Δ = Δ⁺ + pe = 1/2*k*(Δ^2) +end + + + """ $(TYPEDEF) """ diff --git a/src/members/rigids/rigid_body.jl b/src/members/rigids/rigid_body.jl index 9a7b9c8..9cfc8c0 100644 --- a/src/members/rigids/rigid_body.jl +++ b/src/members/rigids/rigid_body.jl @@ -160,8 +160,8 @@ function BodyCache(prop::RigidBodyProperty{N,T}, q = @MVector zeros(T,size(M,2)) Ṁq̇ = @MVector zeros(T,size(M,2)) ∂T∂qᵀ = @MVector zeros(T,size(M,2)) - c(x) = NCF.to_local_coords(nmcs,x) - C(c) = NCF.to_position_jacobian(nmcs,q,c) + c(x) = to_local_coords(nmcs,x) + C(c) = to_position_jacobian(nmcs,q,c) Co = C(c(zero(mass_center))) Cg = C(c(mass_center)) Cps = [typeof(Cg)(C(c(loci[i].position))) for i in 1:num_of_loci] diff --git a/src/robots/robot.jl b/src/robots/robot.jl index 8336203..b2d3c81 100644 --- a/src/robots/robot.jl +++ b/src/robots/robot.jl @@ -41,6 +41,8 @@ end make_cstr_jacobian(bot::Robot) = (q) -> cstr_jacobian(bot.structure,q) make_cstr_function(bot::Robot) = (q) -> cstr_function(bot.structure,q) +make_auxi_function(bot::Robot) = (q,s) -> auxi_function(bot.structure,q,s) +make_auxi_jacobian(bot::Robot) = (q,s) -> auxi_jacobian(bot.structure,q,s) build_mass_matrices(bot::Robot) = build_mass_matrices(bot.structure) @@ -73,10 +75,10 @@ $(TYPEDSIGNATURES) """ function reset!(bot::Robot) (;structure, traj) = bot - (;q, q̇) = traj + (;q, q̇, s) = traj clear_forces!(structure) update_bodies!(structure,q[begin],q̇[begin]) - update_apparatuses!(structure) + update_apparatuses!(structure, s) resize!(traj,1) end @@ -107,7 +109,6 @@ function goto_step!(bot::Robot,that_step;actuate=false) bot end - function mechanical_energy!(bot::Robot;actuate=false,gravity=true) (;structure,traj) = bot StructArray([ diff --git a/src/structures/clustertensegrity.jl b/src/structures/clustertensegrity.jl index 94a343f..be98e82 100644 --- a/src/structures/clustertensegrity.jl +++ b/src/structures/clustertensegrity.jl @@ -1,47 +1,3 @@ - - -function update_apparatuses!(st, @eponymargs(clustered,)) - (;clustercables) = st.apparatuses - id = 0 - foreach(clustered) do scnt - id += 1 - clustercable = clustercables[id] - (;s) = clustercable.sps - for (segid, seg) in enumerate(clustercable.segs) - (;state, k, c, original_restlen, prestress) = seg - (;restlen) = state - state1 = scnt[segid].hen.body.state - state2 = scnt[segid].egg.body.state - pid1 = scnt[segid].hen.pid - pid2 = scnt[segid].egg.pid - p1 = state1.loci_states[pid1] - ṗ1 = state1.ṙps[pid1] - f1 = state1.fps[pid1] - p2 = state2.loci_states[pid2] - ṗ2 = state2.ṙps[pid2] - f2 = state2.fps[pid2] - Δr = p2 - p1 - Δṙ = ṗ2 - ṗ1 - state.length,state.direction = lengthdir(p2-p1) - l = state.length - τ = state.direction - state.lengthdot = (transpose(Δr)*Δṙ)/l - if segid == 1 - u = restlen + s[segid] - elseif segid == length(clustercable.segs) - u = restlen - s[segid-1] - else - u = restlen + s[segid] - s[segid-1] - end - state.tension = k*(l-u) + prestress - state.tension = max(state.tension, 0) - f1 .+= τ*state.tension - f2 .-= τ*state.tension - # state.force = τ*state.tension - end - end -end - function distribute_s̄!(st::AbstractStructure, s̄) s⁺ = @view s̄[begin:2:end] s⁻ = @view s̄[begin+1:2:end] diff --git a/src/structures/constraints.jl b/src/structures/constraints.jl index 4573400..325df2f 100644 --- a/src/structures/constraints.jl +++ b/src/structures/constraints.jl @@ -204,4 +204,156 @@ function cstr_velocity_jacobian(appar::Apparatus{<:PrototypeJoint},structure,q,q q̇_hen,q̇_egg, ) @view ret[:,free_idx] -end \ No newline at end of file +end + +function auxi_function!(ret, appar::Apparatus,structure::Structure,q, s, s0) + #default do nothing +end + +function auxi_function!(ret, + appar::Apparatus{<:PrototypeJoint,<:TorsionalSpringDamper}, + structure::Structure, + q, s, s0 + ) + (;indexed,numbered) = structure.connectivity + (;bodyid2sys_full_coords) = indexed + (;joint,force) = appar + (; + hen2egg, + violations, + cache, + mask_1st,mask_2nd,mask_3rd,mask_4th + ) = joint + (; + relative_core + ) = cache + ## (; + + ## ) = force + num_of_add_var = get_num_of_add_var(force) + (;hen,egg) = hen2egg + id_hen = hen.body.prop.id + id_egg = egg.body.prop.id + nmcs_hen = hen.body.coords.nmcs + nmcs_egg = egg.body.coords.nmcs + q_hen = @view q[bodyid2sys_full_coords[id_hen]] + q_egg = @view q[bodyid2sys_full_coords[id_egg]] + # cstr violations + # @show joint.id + + X_hen = NCF.get_X(nmcs_hen,q_hen) + X_egg = NCF.get_X(nmcs_egg,q_egg) + invX̄_hen = nmcs_hen.data.invX̄ + invX̄_egg = nmcs_egg.data.invX̄ + axes_rot_hen = invX̄_hen*hen.body.prop.loci[hen.rotid].axes + axes_rot_egg = invX̄_egg*egg.body.prop.loci[egg.rotid].axes + R = (transpose((X_hen*axes_rot_hen).X)*X_egg*axes_rot_egg).X + ## @show R + θ0 = s0[1] + θ = s[1] + modθ0 = mod2pi(θ0+π/4) + if modθ0 < π/2 + ## @show θ0, "sin" + ret[1] = sin(θ)-R[2,1] + elseif modθ0 < π + ## @show θ0, "cos" + ret[1] = cos(θ)-R[1,1] + elseif modθ0 < 3π/2 + ## @show θ0, "-sin" + ret[1] = sin(θ)-R[2,1] + else + ## @show θ0, "-cos" + ret[1] = cos(θ)-R[1,1] + end + + ## c1 = [1.0,0,0]×(R[:,1]/norm(R[:,1])) + ## c2 = [0,1.0,0]×(R[:,2]/norm(R[:,2])) + ## c3 = [0,0,1.0]×(R[:,3]/norm(R[:,3])) + ## asin.( [0,0,c3[1]]) + ## @show R[2,2:3], rad2deg(θ) +end + +function auxi_jacobian!(∂S∂q̌,∂S∂s, appar::Apparatus, structure::AbstractStructure, q, s, s0) + #default do nothing +end + +function auxi_jacobian!(∂S∂q̌,∂S∂s, + appar::Apparatus{<:PrototypeJoint,<:TorsionalSpringDamper}, + structure::AbstractStructure, + q, s, s0 + ) + (;indexed,numbered) = structure.connectivity + (;bodyid2sys_full_coords) = indexed + (;joint,force) = appar + (; + hen2egg, + violations, + cache, + mask_1st,mask_2nd,mask_3rd,mask_4th + ) = joint + (; + relative_core + ) = cache + full_idx = appar.full_coords_idx + free_idx = appar.free_coords_idx + num_of_add_var = get_num_of_add_var(force) + (;hen,egg) = hen2egg + id_hen = hen.body.prop.id + id_egg = egg.body.prop.id + nmcs_hen = hen.body.coords.nmcs + nmcs_egg = egg.body.coords.nmcs + q_hen = @view q[bodyid2sys_full_coords[id_hen]] + q_egg = @view q[bodyid2sys_full_coords[id_egg]] + q_appar = vcat(q_hen,q_egg) + # cstr violations + # @show joint.id + + X_hen = NCF.get_X(nmcs_hen,q_hen) + X_egg = NCF.get_X(nmcs_egg,q_egg) + invX̄_hen = nmcs_hen.data.invX̄ + invX̄_egg = nmcs_egg.data.invX̄ + axes_rot_hen = invX̄_hen*hen.body.prop.loci[hen.rotid].axes + axes_rot_egg = invX̄_egg*egg.body.prop.loci[egg.rotid].axes + select_uvw_hen = BlockDiagonal([nmcs_hen.conversion_to_X,zero(nmcs_egg.conversion_to_X)]) + select_uvw_egg = BlockDiagonal([zero(nmcs_hen.conversion_to_X),nmcs_egg.conversion_to_X]) + + ## R = (transpose((X_hen*axes_rot_hen).X)*X_egg*axes_rot_egg).X + + axis_zero = zero(axes_rot_hen.X[:,1]) + + half_11 = select_uvw_hen'* + kron(vcat(0,axes_rot_hen.X[:,1],0,axis_zero),I(3))* + kron(vcat(0,axis_zero,0,axes_rot_egg.X[:,1]),I(3))'* + select_uvw_egg + half_21 = select_uvw_hen'* + kron(vcat(0,axes_rot_hen.X[:,2],0,axis_zero),I(3))* + kron(vcat(0,axis_zero,0,axes_rot_egg.X[:,1]),I(3))'* + select_uvw_egg + hess_11 = Symmetric(half_11 + half_11') + hess_21 = Symmetric(half_21 + half_21') + θ0 = s0[1] + θ = s[1] + modθ0 = mod2pi(θ0+π/4) + if modθ0 < π/2 + ## @show θ0, "sin" + ∂S∂q̌[1,:] .= -(q_appar'*hess_21)[free_idx] #R[2,1] + ∂S∂s[1,1] = cos(θ) + elseif modθ0 < π + ## @show θ0, "cos" + ∂S∂q̌[1,:] .= -(q_appar'*hess_11)[free_idx] #R[1,1] + ∂S∂s[1,1] = sin(θ) + elseif modθ0 < 3π/2 + ## @show θ0, "-sin" + ∂S∂q̌[1,:] .= -(q_appar'*hess_21)[free_idx] #R[2,1] + ∂S∂s[1,1] = cos(θ) + else + ## @show θ0, "-cos" + ∂S∂q̌[1,:] .= -(q_appar'*hess_11)[free_idx] #R[1,1] + ∂S∂s[1,1] = sin(θ) + end + + ## c1 = [1.0,0,0]×(R[:,1]/norm(R[:,1])) + ## c2 = [0,1.0,0]×(R[:,2]/norm(R[:,2])) + ## c3 = [0,0,1.0]×(R[:,3]/norm(R[:,3])) + ## asin.( [0,0,c3[1]]) +end diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 4cfdfb6..7937db2 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -425,15 +425,15 @@ function make_S(st,q0) end # In-place ∂Q̌∂q̌ for cables and flexible bodies -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::AbstractBody,q,st) +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::AbstractBody,st::AbstractStructure,q,s=nothing) #default do nothing end -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus,q,st) +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus,st::AbstractStructure,q,s=nothing) #default do nothing end -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::FlexibleBody,q,st) +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::FlexibleBody,st::AbstractStructure,q,s=nothing) (;coords,cache) = body (;e,) = cache ancs = coords.nmcs @@ -443,7 +443,7 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::FlexibleBody,q,st) ∂Q̌∂q̌[mfree,mfree] .-= ∂Q∂e[free_idx,free_idx] end -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJoint},q,st) +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJoint},st::AbstractStructure,q,s=nothing) (;indexed,numbered) = st.connectivity (; @@ -489,7 +489,7 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo end end -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJoint,<:DistanceSpringDamperSegment},q,st) +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJoint,<:DistanceSpringDamperSegment},st::AbstractStructure,q,s=nothing) (;indexed,numbered) = st.connectivity (; @@ -534,13 +534,13 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:CableJo ∂Q̌∂q̌[appar_free_coords_idx,appar_free_coords_idx] .+= force_cache.K end -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:ClusterJoint},q,st) +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{<:ClusterJoint},st::AbstractStructure,q,s=nothing) foreach(appar.force.segs) do seg - build_tangent_stiffness_matrix!(∂Q̌∂q̌,seg,q,st) + build_tangent_stiffness_matrix!(∂Q̌∂q̌,seg,st,q) end end -function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{JointType,<:RotationalSpringDamper},q,st) where {JointType} +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{JointType,<:RotationalSpringDamper},st::AbstractStructure,q,s=nothing) where {JointType} (; num_of_cstr, hen2egg, @@ -584,30 +584,123 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{JointType end end +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus{JointType,<:TorsionalSpringDamper},st::AbstractStructure,q,s=nothing) where {JointType} + (; + bodyid2sys_full_coords, + bodyid2sys_free_coords, + ) = st.connectivity.indexed + (; + num_of_cstr, + hen2egg, + cache, + mask_1st,mask_2nd,mask_3rd,mask_4th + ) = appar.joint + (;k,state) = appar.force + (; + relative_core + ) = cache + (;hen,egg) = hen2egg + nmcs_egg = egg.body.coords.nmcs + free_idx_egg = egg.body.coords.free_idx + num_of_coords_egg = get_num_of_coords(nmcs_egg) + id_egg = egg.body.prop.id + egg_sys_full_idx = bodyid2sys_full_coords[id_egg] + egg_sys_free_idx = bodyid2sys_free_coords[id_egg] + invX̄_egg = nmcs_egg.data.invX̄ + q_egg = @view q[egg_sys_full_idx] + state.angle = s[1] + deformation = state.angle - state.rest_angle + state.torque = -k*deformation/100 + loci_axes_rot_egg = egg.body.prop.loci[egg.rotid].axes + axes_rot_egg = invX̄_egg*loci_axes_rot_egg + + r̄_home = egg.body.prop.loci[egg.pid].position + r̄_away = r̄_home + loci_axes_rot_egg.X[:,1] + C_home = to_position_jacobian(nmcs_egg,q_egg,to_local_coords(nmcs_egg,r̄_home)) + C_away = to_position_jacobian(nmcs_egg,q_egg,to_local_coords(nmcs_egg,r̄_away)) + + ∂F∂q = state.torque*(-transpose(C_home) + transpose(C_away))*kron(hcat(0,transpose(axes_rot_egg.X[:,2])),I(3)) + ∂Q̌∂q̌[egg_sys_free_idx,egg_sys_free_idx] .+= ∂F∂q[free_idx_egg,free_idx_egg] +end + +function generalized_force_jacobian!(∂Q̌∂s,appar::Apparatus,st,q,q̇,t, s=nothing) + #default do nothing +end + +function generalized_force_jacobian!(∂Q̌∂s,appar::Apparatus{JointType,<:TorsionalSpringDamper},st::AbstractStructure,q,q̇,t,s) where {JointType} + (; + bodyid2sys_full_coords, + bodyid2sys_free_coords, + ) = st.connectivity.indexed + (; + num_of_cstr, + hen2egg, + cache, + mask_1st,mask_2nd,mask_3rd,mask_4th + ) = appar.joint + (;k,state) = appar.force + (; + relative_core + ) = cache + (;hen,egg) = hen2egg + nmcs_egg = egg.body.coords.nmcs + free_idx_egg = egg.body.coords.free_idx + num_of_coords_egg = get_num_of_coords(nmcs_egg) + id_egg = egg.body.prop.id + egg_sys_full_idx = bodyid2sys_full_coords[id_egg] + egg_sys_free_idx = bodyid2sys_free_coords[id_egg] + invX̄_egg = nmcs_egg.data.invX̄ + q_egg = @view q[egg_sys_full_idx] + state.angle = s[1] + deformation = state.angle - state.rest_angle + state.torque = -k*deformation/100 + loci_axes_rot_egg = egg.body.prop.loci[egg.rotid].axes + axes_rot_egg = invX̄_egg*loci_axes_rot_egg + + r̄_home = egg.body.prop.loci[egg.pid].position + r̄_away = r̄_home + loci_axes_rot_egg.X[:,1] + C_home = to_position_jacobian(nmcs_egg,q_egg,to_local_coords(nmcs_egg,r̄_home)) + C_away = to_position_jacobian(nmcs_egg,q_egg,to_local_coords(nmcs_egg,r̄_away)) + + ∂F∂s = -k/100*(-transpose(C_home) + transpose(C_away))*axes_rot_egg.X[:,2] + ## @show ∂F∂s + ∂Q̌∂s[egg_sys_free_idx,:] .+= ∂F∂s[free_idx_egg,:] +end + # In-place ∂Q̌∂q̌ for cables and flexible bodies function build_tangent_stiffness_matrix!(∂Q̌∂q̌,st) (;bodies,apparatuses,connectivity) = st - + (; + apparid2sys_add_var_idx + ) = connectivity.indexed q = get_coords(st) + ## s = get_add_vars(st) + s = st.state.system.s foreach(bodies) do body - build_tangent_stiffness_matrix!(∂Q̌∂q̌,body,q,st) + build_tangent_stiffness_matrix!(∂Q̌∂q̌,body,st,q) end foreach(apparatuses) do appar - build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar,q,st) + build_tangent_stiffness_matrix!( + ∂Q̌∂q̌, + appar, + st, + q, + (@view s[apparid2sys_add_var_idx[appar.id]]) + ) end end # In-place ∂Q̌∂q̌̇ for cables and flexible bodies -function build_tangent_damping_matrix!(∂Q̌∂q̌̇,body::AbstractBody,q,st) +function build_tangent_damping_matrix!(∂Q̌∂q̌̇,body::AbstractBody,st::AbstractStructure,q) #default do nothing end -function build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar::Apparatus,q,st) +function build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar::Apparatus,st::AbstractStructure,q) #default do nothing end -function build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar::Apparatus{<:CableJoint},q,st) +function build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar::Apparatus{<:CableJoint},st::AbstractStructure,q) (;indexed,numbered) = st.connectivity (; @@ -659,7 +752,7 @@ function build_tangent_damping_matrix!(∂Q̌∂q̌̇,st) q = get_coords(st) foreach(apparatuses) do appar - build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar,q,st) + build_tangent_damping_matrix!(∂Q̌∂q̌̇,appar,st::AbstractStructure,q) end end diff --git a/src/structures/mutate.jl b/src/structures/mutate.jl index e72f268..28d089c 100644 --- a/src/structures/mutate.jl +++ b/src/structures/mutate.jl @@ -9,18 +9,6 @@ function clear_forces!(bodies::TypeSortedCollection) foreach(clear_forces!,bodies) end - -function rotation2angles(R::AbstractVector{T}) where {T} - rotation2angles(reshape(R,3,:)) -end - -function rotation2angles(R::AbstractMatrix{T}) where {T} - c1 = [1.0,0,0]×(R[:,1]/norm(R[:,1])) - c2 = [0,1.0,0]×(R[:,2]/norm(R[:,2])) - c3 = [0,0,1.0]×(R[:,3]/norm(R[:,3])) - asin.( [0,0,c3[1]]) -end - function make_jointed2angles(hen2egg,relative_core) (;hen,egg) = hen2egg nmcs_hen = hen.body.coords.nmcs @@ -40,39 +28,29 @@ function make_jointed2angles(hen2egg,relative_core) end """ -Update DistanceSpringDamper Tension +Update apparatuses of a structure $(TYPEDSIGNATURES) """ -function update_apparatuses!(st::AbstractStructure, s=nothing) - (;apparatuses) = st - foreach(apparatuses) do appar - update_apparatus!(st, appar) - end +function update_apparatuses!(st::AbstractStructure, s::AbstractVector{T}) where {T} + st.state.system.s .= s + update_apparatuses!(st) end -function update_apparatuses!(st::AbstractStructure, s̄::AbstractVector{T}) where {T} +function update_apparatuses!(st::AbstractStructure, s=nothing) (;apparatuses) = st - st.state.system.s .= s̄ - foreach(apparatuses) do appar - if isa(appar, Apparatus{<:ClusterJoint}) - (;id) = appar - (;sps) = appar.joint - idx = st.connectivity.indexed.apparid2sys_add_var_idx[id] - for (i, sp) in enumerate(sps) - sp.s⁺ = s̄[idx[2i-1]] - sp.s⁻ = s̄[idx[2i]] - sp.s = sp.s⁺ - sp.s⁻ - end - end + foreach(apparatuses) do appar + appar_add_var_idx = st.connectivity.indexed.apparid2sys_add_var_idx[appar.id] + update_apparatus!(st, appar, + (@view st.state.system.s[appar_add_var_idx]) + ) end - update_apparatuses!(st) end -function update_apparatus!(st::AbstractStructure, appar::Apparatus) +function update_apparatus!(st::AbstractStructure, appar::Apparatus, s) #default no update end -function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:CableJoint}) +function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:CableJoint}, s) (;id,joint,force) = appar (;hen,egg) = joint.hen2egg locus_state_hen = hen.body.state.loci_states[hen.pid] @@ -88,11 +66,16 @@ function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:CableJoint} f_egg .-= force.state.force end -function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:ClusterJoint}) +function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:ClusterJoint},s) (;id, joint, force) = appar (;sps) = joint (;segs) = force nAppar = length(segs) + for (i, sp) in enumerate(sps) + sp.s⁺ = s[2i-1] + sp.s⁻ = s[2i] + sp.s = sp.s⁺ - sp.s⁻ + end for (idx, iappar) in enumerate(segs) ijoint = iappar.joint iforce = iappar.force @@ -122,7 +105,7 @@ function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:ClusterJoin end end -function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:PrototypeJoint,<:RotationalSpringDamper}) +function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:PrototypeJoint,<:RotationalSpringDamper}, s) (;indexed,numbered) = st.connectivity (;system) = st.state (;bodyid2sys_free_coords, @@ -170,6 +153,55 @@ function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:PrototypeJo end end +function update_apparatus!(st::AbstractStructure, appar::Apparatus{<:PrototypeJoint,<:TorsionalSpringDamper}, s) + (;indexed,numbered) = st.connectivity + (;system,members) = st.state + (;bodyid2sys_free_coords, + bodyid2sys_full_coords, + num_of_free_coords, + num_of_full_coords, + apparid2sys_free_coords_idx + ) = indexed + (; + num_of_cstr, + hen2egg, + cache, + mask_1st,mask_2nd,mask_3rd,mask_4th + ) = appar.joint + (; + relative_core + ) = cache + (;hen,egg) = hen2egg + full_idx = appar.full_coords_idx + free_idx = appar.free_coords_idx + appar_sys_free_idx = apparid2sys_free_coords_idx[appar.id] + spring_damper = appar.force + (;state,k) = spring_damper + id_egg = egg.body.prop.id + q_egg = @view system.q[bodyid2sys_full_coords[id_egg]] + nmcs_egg = egg.body.coords.nmcs + X_egg = NCF.get_X(nmcs_egg,q_egg) + invX̄_egg = nmcs_egg.data.invX̄ + state.angle = s[1] + deformation = state.angle - state.rest_angle + ## @show asin.(angles) .|> rad2deg + state.torque = -k/100*deformation + ## angles_jacobian = ForwardDiff.jacobian(jointed2angles,q_jointed) + ## @show q_jointed + ## @show angles_jacobian + # couple of forces + loci_axes_rot_egg = egg.body.prop.loci[egg.rotid].axes + axes_rot_egg = X_egg*invX̄_egg*loci_axes_rot_egg + # X_hen*invX̄_hen*loci_axes_rot_hen == X_egg*invX̄_egg*loci_axes_rot_egg + # R_hen*loci_axes_rot_hen == R_egg*loci_axes_rot_egg + r̄_home = egg.body.prop.loci[egg.pid].position + r̄_away = r̄_home + loci_axes_rot_egg.X[:,1] + C_home = to_position_jacobian(nmcs_egg,q_egg,to_local_coords(nmcs_egg,r̄_home)) + C_away = to_position_jacobian(nmcs_egg,q_egg,to_local_coords(nmcs_egg,r̄_away)) + (;F) = members[egg.body.prop.id] + F .+= state.torque*(-transpose(C_home)+transpose(C_away))*axes_rot_egg.X[:,2] +end + function stretch_rigids!(st::AbstractStructure,c) st.state.system.c .= c stretch_rigids!(st) diff --git a/src/structures/structure.jl b/src/structures/structure.jl index 7e17aa8..60c5f2b 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -44,16 +44,7 @@ function StructureState(bodies,apparatuses,cnt::Connectivity) q̈ = zero(q) F = zero(q) λ = Vector{T}(undef,num_of_cstr) - s = Vector{Float64}() - foreach(apparatuses) do appar - (;joint) = appar - if isa(joint, ClusterJoint) - for sp in joint.sps - append!(s, sp.s⁺) - append!(s, sp.s⁻) - end - end - end + s = Vector{T}(undef,num_of_add_var) c = get_local_coords(bodies,numbered) p = zero(q) p̌ = Vector{T}(undef,num_of_free_coords) @@ -84,6 +75,16 @@ function StructureState(bodies,apparatuses,cnt::Connectivity) members[body.prop.id].q .= q members[body.prop.id].q̇ .= q̇ end + #fixme assign to the right places + ## foreach(apparatuses) do appar + ## (;joint) = appar + ## if isa(joint, ClusterJoint) + ## for sp in joint.sps + ## append!(s, sp.s⁺) + ## append!(s, sp.s⁻) + ## end + ## end + ## end StructureState(system,members) end @@ -334,6 +335,61 @@ function cstr_function(structure::AbstractStructure,q,c=get_local_coords(structu ret end +function make_auxi_function(structure::AbstractStructure,s0) + (q,s) -> auxi_function(structure,q,s,deepcopy(s0)) +end + +function auxi_function(structure::AbstractStructure,q,s,s0) + (;apparatuses,connectivity) = structure + (;numbered,indexed,) = connectivity + (; + num_of_free_coords, + num_of_full_coords, + sys_pres_coords_idx, + sys_free_coords_idx, + num_of_add_var, + apparid2sys_add_var_idx + ) = indexed + + ret = Vector{eltype(q)}(undef,num_of_add_var) + foreach(apparatuses) do appar + appar_add_var_idx = apparid2sys_add_var_idx[appar.id] + auxi_function!( + (@view ret[appar_add_var_idx]), + appar,structure, + q, + (@view s[appar_add_var_idx]), + (@view s0[appar_add_var_idx]) + ) + end + ret +end + +function make_auxi_jacobian(structure::AbstractStructure,s0) + function inner_auxi_jacobian!(∂S∂q̌,∂S∂s,q,s) + (;apparatuses,connectivity) = structure + (;indexed,) = connectivity + (; + apparid2sys_free_coords_idx, + apparid2sys_add_var_idx + ) = indexed + + foreach(apparatuses) do appar + appar_add_var_idx = apparid2sys_add_var_idx[appar.id] + appar_sys_free_idx = apparid2sys_free_coords_idx[appar.id] + auxi_jacobian!( + (@view ∂S∂q̌[appar_add_var_idx,appar_sys_free_idx]), + (@view ∂S∂s[appar_add_var_idx,appar_add_var_idx]), + appar,structure, + q, + (@view s[appar_add_var_idx]), + (@view s0[appar_add_var_idx]) + ) + end + end +end + + function cstr_jacobian(structure::AbstractStructure,q,c=get_local_coords(structure)) (;bodies,apparatuses,connectivity) = structure (;indexed,numbered) = connectivity diff --git a/src/utils.jl b/src/utils.jl index 02f10a2..06d1a28 100644 --- a/src/utils.jl +++ b/src/utils.jl @@ -199,4 +199,16 @@ function check_id_sanity(things) @assert allunique(ids) end ids,num_of_things +end + + +function rotation2angles(R::AbstractVector{T}) where {T} + rotation2angles(reshape(R,3,:)) +end + +function rotation2angles(R::AbstractMatrix{T}) where {T} + c1 = [1.0,0,0]×(R[:,1]/norm(R[:,1])) + c2 = [0,1.0,0]×(R[:,2]/norm(R[:,2])) + c3 = [0,0,1.0]×(R[:,3]/norm(R[:,3])) + asin.( [0,0,c3[1]]) end \ No newline at end of file diff --git a/yard/nonsmooth/slider_crank.jl b/yard/nonsmooth/slider_crank.jl index 9f38a57..2173fe8 100644 --- a/yard/nonsmooth/slider_crank.jl +++ b/yard/nonsmooth/slider_crank.jl @@ -30,8 +30,8 @@ sc = slider_crank(;coordsType=RB.QCF.QC) # Contact Surfaces planes = RB.StaticContactSurfaces( [ - RB.Plane([0,0, 1.0],[0,0,-0.026]), - RB.Plane([0,0,-1.0],[0,0, 0.026]) + RB.HalfSpace([0,0, 1.0],[0,0,-0.026]), + RB.HalfSpace([0,0,-1.0],[0,0, 0.026]) ] ) @@ -45,24 +45,42 @@ tspan = (0.0,1.0) # No Contact Dynamics sc = slider_crank(;coordsType=RB.NCF.NC) +(;q,s) = sc.structure.state.system +RB.auxi_function(sc.structure,q,s) + +get_add_var(sc) + +appars = RB.get_apparatuses(sc) +appars[2].num_of_add_var + +prob = RB.DynamicsProblem(sc,RB.GravitySpace(true)) -prob = RB.DynamicsProblem(sc,) RB.solve!( prob, RB.DynamicsSolver( RB.Zhong06() - # RB.Moreau(0.5) + # RB.Moreau(0.5); ); dt,tspan,ftol=1e-12,maxiters=50,verbose=true,exception=true,progress=false, ) + GM.activate!(;scalefactor=1); plot_traj!(sc;showground=false) RB.solve!( prob, RB.DynamicsSolver(RB.Moreau(0.5)); - dt,tspan,ftol=1e-12,maxiters=3,verbose=true,exception=true,progress=false, + dt,tspan, + ftol=1e-12,maxiters=3,verbose=true,exception=true,progress=false, ) +me = RB.mechanical_energy!(sc) +fig = Figure() +ax = Axis(fig[1,1]) +lines!(ax,me.E) +lines!(ax,me.V) +lines!(ax,me.T) +fig + dts = [ 1e-3,5e-4,2e-4,1e-4,1e-5 @@ -452,6 +470,3 @@ RB.solve!( ) GM.activate!(;px_per_unit=2,scalefactor = 2);plot_traj!(sc;showground=false) - -me = RB.mechanical_energy!(sc) -Makie.lines(me.E) \ No newline at end of file From b54fd1d6ad6a00f68aa3edcdd0bbe8b62632d5c2 Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Wed, 15 May 2024 10:20:13 +0800 Subject: [PATCH 11/20] implement additional variables into `Zhong06_CCP_constant_mass.jl`; add `AbstractEnvironment` and `StaticEnvironment`, which includes `Gravity` as `AbstractGravity` as `AbstractField`; --- src/mechanics/contact.jl | 51 ++++++++---- src/mechanics/dynamics.jl | 14 +++- .../Zhong06_CCP_constant_mass.jl | 82 +++++++++++-------- .../Zhong06_family/Zhong06_constant_mass.jl | 2 +- src/mechanics/solvers.jl | 19 +++-- yard/nonsmooth/slider_crank.jl | 13 +-- 6 files changed, 109 insertions(+), 72 deletions(-) diff --git a/src/mechanics/contact.jl b/src/mechanics/contact.jl index e026db1..4e99109 100644 --- a/src/mechanics/contact.jl +++ b/src/mechanics/contact.jl @@ -1,3 +1,36 @@ +abstract type AbstractField end +abstract type AbstractGravity <: AbstractField end +struct NoGravity <: AbstractGravity end +struct EarthSurfaceGravity{T} <: AbstractGravity + acceleration::T +end + +Gravity(g=9.81) = EarthSurfaceGravity(g) + + +has_gravity(::NoGravity) = false +has_gravity(::EarthSurfaceGravity) = true + +abstract type AbstractGeometry end + +abstract type AbstractEnvironment end +struct StaticEnvironment{geometryType,fieldType} <: AbstractEnvironment + geometry::geometryType + field::fieldType +end +abstract type AbstractContactEnvironment <: AbstractEnvironment end +abstract type RigidBodyContactEnvironment <: AbstractContactEnvironment end + +function StaticContactSurfaces(surfaces,gravity=Gravity()) + StaticEnvironment( + surfaces, + gravity + ) +end + +has_gravity(env::AbstractEnvironment) = has_gravity(env.field) + + struct Contact{T} id::Int μ::T @@ -52,8 +85,6 @@ function ApproxFrictionalContact(ϵ::T,μ::T,m::Int) where T ) end -abstract type AbstractContactEnvironment end -abstract type RigidBodyContactEnvironment<: AbstractContactEnvironment end struct ContactRigidBodies{bodiesType} <: RigidBodyContactEnvironment contact_bodies::bodiesType end @@ -84,21 +115,7 @@ function RigidCube(id) return RigidCube(id, one(id), one(id)) end - -abstract type StaticContactEnvironment <: AbstractContactEnvironment end -struct StaticContactSurfaces{surfacesType} <: StaticContactEnvironment - surfaces::surfacesType -end - -struct EmptySpace <: StaticContactEnvironment end -struct GravitySpace{T} <: StaticContactEnvironment - gravity::T -end - -has_gravity(env::AbstractContactEnvironment) = false -has_gravity(env::GravitySpace) = env.gravity - -abstract type ContactGeometry end +abstract type ContactGeometry <: AbstractGeometry end abstract type ContactPrimitive <: ContactGeometry end abstract type ConvexContactPrimitive <: ContactPrimitive end diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index f7a0232..cfb24d5 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -77,7 +77,19 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t, generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,NoPolicy(),q,q̇,t,∂F∂s,s) end -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,∂F∂s=nothing,s=nothing) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,) + (;structure,hub) = bot + ∂F∂q̌ .= 0 + ∂F∂q̌̇ .= 0 + clear_forces!(structure) + lazy_update_bodies!(structure,q,q̇) + update_apparatuses!(structure,) + generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) + build_tangent_stiffness_matrix!(∂F∂q̌,structure) + build_tangent_damping_matrix!(∂F∂q̌̇,structure) +end + +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,∂F∂s,s) (;structure,hub) = bot ∂F∂q̌ .= 0 ∂F∂q̌̇ .= 0 diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl index ec19b34..b71db18 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl @@ -25,8 +25,8 @@ function generate_cache( prob.options, solver.options, ) - F!(F,q,q̇,t) = generalized_force!(F,bot,policy,q,q̇,t;gravity=options.gravity) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t) + F!(F,q,q̇,t,s) = generalized_force!(F,bot,policy,q,q̇,t,s;gravity=options.gravity) + Jac_F!(∂F∂q̌,∂F∂q̌̇, ∂F∂s,q,q̇,t, s) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t,∂F∂s,s) M = Matrix(assemble_M(structure)) Φ = make_cstr_function(bot) @@ -64,50 +64,57 @@ function generate_cache( end function make_step_k( + structure, solver_cache::Zhong06_CCP_Constant_Mass_Cache, - nq,nλ,na, - qₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁, + nq,nλ,ns,na, + qₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁,sₖ₋₁, pₖ,vₖ, invM, h,mass_norm) (;F!,Jac_F!,M,Φ,A,∂Aᵀλ∂q) = solver_cache.cache - n1 = nq - n2 = nq+nλ nΛ = 3na - nx = n2 + nx = nq+nλ+ns + S = make_auxi_function(structure,deepcopy(sₖ₋₁)) + Jac_S! = make_auxi_jacobian(structure,deepcopy(sₖ₋₁)) function ns_stepk!( 𝐫𝐞𝐬,𝐉, - Fₘ,∂F∂q,∂F∂q̇, + Fₘ,∂F∂q,∂F∂q̇,∂F∂s,∂S∂q,∂S∂s, 𝐁,𝐛,𝐜ᵀ,𝐲, x,Λₖ, - structure, contact_cache, timestep,iteration,doin=true ) # @show timestep, iteration, na - qₖ = @view x[ 1:n1] - λₘ = @view x[n1+1:n2] + qₖ = @view x[ 1:nq] + λₘ = @view x[nq+1:nq+nλ] + sₖ = @view x[nq+nλ+1:nx] qₘ = (qₖ.+qₖ₋₁)./2 q̇ₘ = (qₖ.-qₖ₋₁)./h + sₘ = (sₖ .+ sₖ₋₁)./2 vₘ = q̇ₘ tₘ = tₖ₋₁+h/2 - F!(Fₘ,qₘ,q̇ₘ,tₘ) - Jac_F!(∂F∂q,∂F∂q̇,qₘ,q̇ₘ,tₘ) - + F!(Fₘ,qₘ,q̇ₘ,tₘ,sₘ) + Jac_F!(∂F∂q,∂F∂q̇,∂F∂s,qₘ,q̇ₘ,tₘ,sₘ) + Jac_S!(∂S∂q,∂S∂s,qₖ,sₖ) Aₖ₋₁ = A(qₖ₋₁) Aₖ = A(qₖ) - 𝐫𝐞𝐬[ 1:n1] .= -h.*pₖ₋₁ .+ M*(qₖ.-qₖ₋₁) .- + 𝐫𝐞𝐬[ 1:nq] .= -h.*pₖ₋₁ .+ M*(qₖ.-qₖ₋₁) .- mass_norm.*transpose(Aₖ₋₁)*λₘ .- (h^2)/2 .*Fₘ - 𝐫𝐞𝐬[n1+1:n2] .= -mass_norm.*Φ(qₖ) + 𝐫𝐞𝐬[nq+1:nq+nλ] .= -mass_norm.*Φ(qₖ) + 𝐫𝐞𝐬[nq+nλ+1:nx] .= S(qₖ,sₖ) 𝐉 .= 0.0 - 𝐉[ 1:n1, 1:n1] .= M .-h^2/2 .*(1/2 .*∂F∂q .+ 1/h.*∂F∂q̇) - 𝐉[ 1:n1,n1+1:n2] .= -mass_norm.*transpose(Aₖ₋₁) + 𝐉[ 1:nq, 1:nq] .= M .-h^2/2 .*(1/2 .*∂F∂q .+ 1/h.*∂F∂q̇) + 𝐉[ 1:nq,nq+1:nq+nλ] .= -mass_norm.*transpose(Aₖ₋₁) + + 𝐉[nq+1:nq+nλ, 1:nq] .= -mass_norm.*Aₖ - 𝐉[n1+1:n2, 1:n1] .= -mass_norm.*Aₖ + 𝐉[ 1:nq, nq+nλ+1:nx] .= -(h^2)/2 .*(1/2 .*∂F∂s) + 𝐉[nq+nλ+1:nx,1:nq] .= ∂S∂q + 𝐉[nq+nλ+1:nx,nq+nλ+1:nx] .= ∂S∂s lu𝐉 = lu(𝐉) @@ -120,7 +127,7 @@ function make_step_k( Dₘ = contact_cache.cache.Dper Dₖ = contact_cache.cache.Dimp 𝐁 .= 0 - 𝐁[ 1:n1,1:nΛ] .= h.*mass_norm.*transpose(D)*H + 𝐁[ 1:nq,1:nΛ] .= h.*mass_norm.*transpose(D)*H 𝐫𝐞𝐬 .-= 𝐁*Λₖ if doin @@ -146,9 +153,9 @@ function make_step_k( 𝐛[is+1:is+3] .= [v́ₜⁱ,0,0] Dⁱₘ = @view Dₘ[is+1:is+3,:] Dⁱₖ = @view Dₖ[is+1:is+3,:] - 𝐜ᵀ[is+1 , 1:n1] .= 1/(norm(v́⁺[is+2:is+3])+1e-14)*(v́⁺[is+2]*∂v́⁺∂qₖ[is+2,:] .+ v́⁺[is+3]*∂v́⁺∂qₖ[is+3,:]) - 𝐜ᵀ[is+1:is+3, 1:n1] .+= ∂v́⁺∂qₖ[is+1:is+3,:] - 𝐜ᵀ[is+1:is+3,n1+1:n2] .= Dⁱₖ*∂vₖ∂λₘ + 𝐜ᵀ[is+1 , 1:nq ] .= 1/(norm(v́⁺[is+2:is+3])+1e-14)*(v́⁺[is+2]*∂v́⁺∂qₖ[is+2,:] .+ v́⁺[is+3]*∂v́⁺∂qₖ[is+3,:]) + 𝐜ᵀ[is+1:is+3, 1:nq ] .+= ∂v́⁺∂qₖ[is+1:is+3,:] + 𝐜ᵀ[is+1:is+3,nq+1:nq+nλ] .= Dⁱₖ*∂vₖ∂λₘ end if timestep == 3092 ## @show v́⁺, (v́⁺+𝐛), α @@ -183,6 +190,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; (;M,A,contacts_bits,options) = solver_cache.cache q0 = traj.q[begin] λ0 = traj.λ[begin] + s0 = traj.s[begin] q̇0 = traj.q̇[begin] activate_contacts!(structure,env,solver_cache,q0) invM = inv(M) @@ -191,10 +199,14 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; T = eltype(q0) nq = length(q0) nλ = length(λ0) + ns = length(s0) F = zeros(T,nq) ∂F∂q = zeros(T,nq,nq) ∂F∂q̇ = zeros(T,nq,nq) - nx = nq + nλ + ∂F∂s = zeros(T,nq,ns) + ∂S∂q = zeros(T,ns,nq) + ∂S∂s = zeros(T,ns,ns) + nx = nq + nλ + ns Δx = zeros(T,nx) x = zero(Δx) Res = zero(Δx) @@ -219,12 +231,12 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; cₖ = contacts_traj[timestep+1] qₖ₋₁ = traj.q[timestep] q̇ₖ₋₁ = traj.q̇[timestep] - # pₖ₋₁ = traj.p[timestep] + sₖ₋₁ = traj.s[timestep] # λₖ₋₁ = traj.λ[timestep] tₖ₋₁ = traj.t[timestep] qₖ = traj.q[timestep+1] q̇ₖ = traj.q̇[timestep+1] - # pₖ = traj.p[timestep+1] + sₖ = traj.s[timestep+1] λₘ = traj.λ[timestep+1] pₖ₋₁ = M*q̇ₖ₋₁ qˣ = qₖ₋₁ .+ dt./2 .*q̇ₖ₋₁ @@ -248,9 +260,10 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; 𝐲 = zeros(T,nΛ) get_frictional_directions_and_positions!(structure, contact_cache, qₖ₋₁, q̇ₖ₋₁, Λₖ) ns_stepk! = make_step_k( + structure, solver_cache, - nq,nλ,na, - qₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁, + nq,nλ,ns,na, + qₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁,sₖ₋₁, pₖ,q̇ₖ, invM, dt,mass_norm @@ -264,20 +277,19 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; Λʳₖ .= Λₖ Nmax = 50 for iteration = 1:maxiters - if timestep == 3092 + ## if timestep == 3092 ## @show L # @show timestep, iteration ## @show 𝐍 - @show iteration + ## @show iteration # @show qr(L).R |> diag ## @show :befor, size(𝐍), rank(𝐍), cond(𝐍) - end + ## end luJac = ns_stepk!( Res,Jac, - F,∂F∂q,∂F∂q̇, + F,∂F∂q,∂F∂q̇,∂F∂s,∂S∂q,∂S∂s, 𝐁,𝐛,𝐜ᵀ,𝐲, x,Λʳₖ, - structure, contact_cache, timestep,iteration ) @@ -328,10 +340,9 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; Δx .= luJac\minusResΛ ns_stepk!( Res_α0,Jac_α0, - F,∂F∂q,∂F∂q̇, + F,∂F∂q,∂F∂q̇,∂F∂s,∂S∂q,∂S∂s, 𝐁t,𝐛,𝐜ᵀ,𝐲, x.+Δx,Λʳₖ.+ΔΛₖ, - structure, contact_cache, timestep,iteration,false ) @@ -355,6 +366,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; end qₖ .= x[ 1:nq] λₘ .= x[ nq+1:nq+nλ] + sₖ .= x[nq+nλ+1:nx] pₖ .= Momentum_k(qₖ₋₁,pₖ₋₁,qₖ,λₘ,M,A,mass_norm,dt) q̇ₖ .= invM*pₖ Dₘ = contact_cache.cache.Dper diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl index 96be820..51bf1e8 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl @@ -111,7 +111,7 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; Jac[nq̌+1:nq̌+nλ, 1:nq̌ ] .= mass_norm.*A(qₖ) Jac[nq̌+1:nq̌+nλ,nq̌+1:nq̌+nλ] .= 0.0 Jac[ 1:nq̌, nq̌+nλ+1:nx] .= -(h^2)/2 .*(1/2 .*∂F∂s) - Jac[nq̌+nλ+1:nx,1:nq̌] .= ∂S∂q̌ + Jac[nq̌+nλ+1:nx,1:nq̌] .= ∂S∂q̌ Jac[nq̌+nλ+1:nx,nq̌+nλ+1:nx] .= ∂S∂s end inner_Res_stepk!, inner_Jac_stepk! diff --git a/src/mechanics/solvers.jl b/src/mechanics/solvers.jl index 67eae81..a60727c 100644 --- a/src/mechanics/solvers.jl +++ b/src/mechanics/solvers.jl @@ -127,7 +127,11 @@ struct DynamicsProblem{RobotType,policyType,envType,contact_modelType,apparatus_ end function DynamicsProblem(bot::Robot;options...) - DynamicsProblem(bot::Robot,NoPolicy(),GravitySpace(true),Contactless(),Naive(),values(options)) + DynamicsProblem(bot::Robot,NoPolicy(),Gravity(true),Contactless(),Naive(),values(options)) +end + +function DynamicsProblem(bot::Robot,env::AbstractEnvironment;options...) + DynamicsProblem(bot::Robot,NoPolicy(),env,Contactless(),Naive(),values(options)) end function DynamicsProblem(bot::Robot,env::AbstractContactEnvironment;options...) @@ -135,28 +139,27 @@ function DynamicsProblem(bot::Robot,env::AbstractContactEnvironment;options...) end function DynamicsProblem(bot::Robot,policy::AbstractPolicy;options...) - DynamicsProblem(bot::Robot,policy,GravitySpace(true),Contactless(),Naive(),values(options)) + DynamicsProblem(bot::Robot,policy,Gravity(true),Contactless(),Naive(),values(options)) end function DynamicsProblem(bot::Robot,policy::AbstractPolicy,appar_model::AbstractApparatusModel;options...) - DynamicsProblem(bot::Robot,policy,GravitySpace(true),Contactless(),appar_model,values(options)) + DynamicsProblem(bot::Robot,policy,Gravity(true),Contactless(),appar_model,values(options)) end function DynamicsProblem(bot::Robot,appar_model::AbstractApparatusModel;options...) - DynamicsProblem(bot::Robot,NoPolicy(),GravitySpace(true),Contactless(),appar_model,values(options)) + DynamicsProblem(bot::Robot,NoPolicy(),Gravity(true),Contactless(),appar_model,values(options)) end function DynamicsProblem(bot::Robot,contact_model::AbstractContactModel;options...) - DynamicsProblem(bot::Robot,NoPolicy(),GravitySpace(true),contact_model,Naive(),values(options)) + DynamicsProblem(bot::Robot,NoPolicy(),Gravity(true),contact_model,Naive(),values(options)) end -function DynamicsProblem(bot::Robot,env::AbstractContactEnvironment,contact_model::AbstractContactModel;options...) +function DynamicsProblem(bot::Robot,env::StaticEnvironment,contact_model::AbstractContactModel;options...) DynamicsProblem(bot::Robot,NoPolicy(),env,contact_model,Naive(),values(options)) end - function DynamicsProblem(bot::Robot,policy::AbstractPolicy, - env::AbstractContactEnvironment, + env::StaticEnvironment, contact_model::AbstractContactModel, appar_model::AbstractApparatusModel=Naive(),; options... diff --git a/yard/nonsmooth/slider_crank.jl b/yard/nonsmooth/slider_crank.jl index 2173fe8..4ca5daf 100644 --- a/yard/nonsmooth/slider_crank.jl +++ b/yard/nonsmooth/slider_crank.jl @@ -30,8 +30,8 @@ sc = slider_crank(;coordsType=RB.QCF.QC) # Contact Surfaces planes = RB.StaticContactSurfaces( [ - RB.HalfSpace([0,0, 1.0],[0,0,-0.026]), - RB.HalfSpace([0,0,-1.0],[0,0, 0.026]) + RB.Plane([0,0, 1.0],[0,0,-0.026]), + RB.Plane([0,0,-1.0],[0,0, 0.026]) ] ) @@ -45,15 +45,8 @@ tspan = (0.0,1.0) # No Contact Dynamics sc = slider_crank(;coordsType=RB.NCF.NC) -(;q,s) = sc.structure.state.system -RB.auxi_function(sc.structure,q,s) -get_add_var(sc) - -appars = RB.get_apparatuses(sc) -appars[2].num_of_add_var - -prob = RB.DynamicsProblem(sc,RB.GravitySpace(true)) +prob = RB.DynamicsProblem(sc,RB.Gravity(true)) RB.solve!( prob, From 72e9565c6e5664f4a96d04082aecf9e157a9c91f Mon Sep 17 00:00:00 2001 From: Perseus Date: Thu, 16 May 2024 12:01:51 +0800 Subject: [PATCH 12/20] update cable-hole --- src/mechanics/dynamics.jl | 33 +- ...hong06_CCP_constant_mass_cluster_cables.jl | 14 +- .../Zhong06_CCP_constant_mass_hole.jl | 415 ++++++++++++++++++ .../Zhong06_constant_mass_hole.jl | 226 ++++++++++ src/mechanics/solvers.jl | 3 + src/structures/linearization.jl | 23 + src/structures/mutate.jl | 20 + src/structures/structure.jl | 45 ++ yard/ex1/define.jl | 83 ++++ yard/ex1/main1.jl | 108 +++++ yard/ex1/main2.jl | 108 +++++ 11 files changed, 1071 insertions(+), 7 deletions(-) create mode 100644 src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_hole.jl create mode 100644 src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_hole.jl create mode 100644 yard/ex1/define.jl create mode 100644 yard/ex1/main1.jl create mode 100644 yard/ex1/main2.jl diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index 2d7404c..abc2d31 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -73,6 +73,20 @@ function generalized_force!(F,bot::Robot,policy::AbstractPolicy,q,q̇,t,s=nothin user_defined_force!(F,t) end +function generalized_force_hole!(F,bot::Robot,policy::AbstractPolicy,q,q̇,t,s,s_temp;gravity=true,(user_defined_force!)=(F,t)->nothing) + (;structure) = bot + clear_forces!(structure) + actuate!(bot,policy,q,q̇,t) + lazy_update_bodies!(structure,q,q̇) + # update_apparatuses!(structure) + update_apparatuses_hole!(structure, s, s_temp) + if gravity + apply_gravity!(structure;factor=1) + end + assemble_forces!(F,structure) + user_defined_force!(F,t) +end + function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t,s=nothing) generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,NoPolicy(),q,q̇,t,s=nothing) end @@ -98,7 +112,7 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,∂F∂s̄,∂ζ∂ ζ .= 0 clear_forces!(structure) lazy_update_bodies!(structure,q,q̇) - update_apparatuses!(structure) + update_apparatuses!(structure,s) generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) build_tangent_stiffness_matrix!(∂F∂q̌,structure) build_tangent_damping_matrix!(∂F∂q̌̇,structure) @@ -107,6 +121,23 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,∂F∂s̄,∂ζ∂ build_∂ζ∂q!(∂ζ∂q, cluster_cache, structure) end +function generalized_force_jacobian_hole!(∂F∂q̌,∂F∂q̌̇,∂F∂s̄,∂ζ∂q,ζ,bot::Robot,policy::AbstractPolicy,q,q̇,t,cluster_cache,s=nothing) + (;structure,hub) = bot + ∂F∂q̌ .= 0 + ∂F∂q̌̇ .= 0 + ∂F∂s̄ .= 0 + ∂ζ∂q .= 0 + ζ .= 0 + clear_forces!(structure) + lazy_update_bodies!(structure,q,q̇) + update_apparatuses!(structure) + generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) + build_tangent_stiffness_matrix!(∂F∂q̌,structure) + build_tangent_damping_matrix!(∂F∂q̌̇,structure) + build_ζ_hole!(ζ, cluster_cache, structure) + build_∂ζ∂q!(∂ζ∂q, cluster_cache, structure) +end + struct ContactCache{cacheType} cache::cacheType end diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index 08af31c..4fd4889 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -14,7 +14,7 @@ function generate_cache( solver::DynamicsSolver{ Zhong06, <:InnerLayerContactSolver, - <:MonolithicApparatusSolver + <:MonolithicApparatusSolver{SmoothedFischerBurmeister} }, ::Val{true}; dt,kargs... @@ -23,7 +23,7 @@ function generate_cache( (;bot,policy,env) = prob (;structure) = bot options = merge( - (gravity=false,factor=1,checkpersist=true), #default + (gravity=true,factor=1,checkpersist=true), #default prob.options, solver.options, ) @@ -229,6 +229,8 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C Jac_α1 = zeros(T,nx,nx) Res_α2 = zero(Δx) Jac_α2 = zeros(T,nx,nx) + s_bak = deepcopy(s0) + s_temp = deepcopy(s0) mr = norm(M,Inf) mass_norm = mr α0 = 1.0 @@ -303,10 +305,10 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C cluster_cache, timestep,iteration ) - if (tₖ₋₁ == 0.096) & (iteration == 1) - @show size(Jac) - write("jac1.bin", Jac) - end + # if (tₖ₋₁ == 0.096) & (iteration == 1) + # @show size(Jac) + # write("jac1.bin", Jac) + # end if na == 0 normRes = norm(Res) if normRes < ftol diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_hole.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_hole.jl new file mode 100644 index 0000000..a8ab251 --- /dev/null +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_hole.jl @@ -0,0 +1,415 @@ +struct Zhong06_CCP_Constant_Mass_Hole_Cache{solT, cacheType} + solver::solT + cache::cacheType +end + +function generate_cache( + simulator::Simulator{<:DynamicsProblem{ + RobotType, + policyType, + EnvType, + RestitutionFrictionCombined{NewtonRestitution,CoulombFriction}, + EulerEytelwein, + }}, + solver::DynamicsSolver{ + Zhong06, + <:InnerLayerContactSolver, + <:MonolithicApparatusSolver{CableHole} + }, + ::Val{true}; + dt,kargs... + ) where {RobotType,policyType,EnvType} + (;prob) = simulator + (;bot,policy,env) = prob + (;structure) = bot + options = merge( + (gravity=true,factor=1,checkpersist=true), #default + prob.options, + solver.options, + ) + F!(F,q,q̇,t) = generalized_force_hole!(F,bot,policy,q,q̇,t;gravity=options.gravity) + Jac_F!(∂F∂q,∂F∂q̇,∂Q̌∂s̄,∂ζ∂q,ζ,qₘ,q̇ₘ,tₘ,cluster_cache) = generalized_force_jacobian_hole!(∂F∂q,∂F∂q̇,∂Q̌∂s̄,∂ζ∂q,ζ,bot,policy,qₘ,q̇ₘ,tₘ,cluster_cache) + + M = Matrix(assemble_M(structure)) + Φ = make_cstr_function(bot) + A = make_cstr_jacobian(bot) + ψ = build_ψ_hole(structure) + + nq = size(M,2) + T = get_numbertype(bot) + Ψ(q,q̇) = Vector{T}() + ∂Ψ∂q(q,q̇) = Matrix{T}(undef,0,nq) + B(q) = Matrix{T}(undef,0,nq) + + # ∂𝐌𝐚∂𝐪(q,a) = zeros(T,nq,nq) + ∂Aᵀλ∂q(q::AbstractVector,λ) = cstr_forces_jacobian(structure,q,λ) + # ∂𝚽𝐪𝐯∂𝒒(q,v) = RB.∂Aq̇∂q(structure,v) + ∂Bᵀμ∂q(q,μ) = zeros(T,nq,nq) + (; + contacts_bits, + persistent_bits, + μs_sys, + es_sys, + gaps_sys + ) = prepare_contacts(bot,env) + + cache = @eponymtuple( + F!,Jac_F!, + M,Φ,A,Ψ,B,∂Ψ∂q,∂Aᵀλ∂q,∂Bᵀμ∂q,ψ, + contacts_bits, + persistent_bits, + μs_sys, + es_sys, + gaps_sys, + options, + ) + Zhong06_CCP_Constant_Mass_Hole_Cache(solver, cache) +end + +function make_step_k( + solver_cache::Zhong06_CCP_Constant_Mass_Hole_Cache, + nq,nλ,ns,na, + qₖ₋₁,sₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁, + pₖ,vₖ, + invM, + h,mass_norm) + (;F!,Jac_F!,M,Φ,A,ψ,∂Aᵀλ∂q) = solver_cache.cache + + n1 = nq + n2 = nq+nλ + n3 = nq+nλ+ns + nΛ = 3na + nx = n3 + function ns_stepk!( + 𝐫𝐞𝐬,𝐉, + Fₘ,∂F∂q,∂F∂q̇, + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, + 𝐁,𝐛,𝐜ᵀ,𝐲, + x,Λₖ, + structure, + contact_cache, + cluster_cache, + timestep,iteration,doin=true + ) + qₖ = @view x[ 1:n1] + λₘ = @view x[n1+1:n2] + sₖ = @view x[nq+nλ+1:nx] + qₘ = (qₖ.+qₖ₋₁)./2 + sₘ = (sₖ.+sₖ₋₁)./2 + q̇ₘ = (qₖ.-qₖ₋₁)./h + vₘ = q̇ₘ + tₘ = tₖ₋₁+h/2 + F!(Fₘ,qₘ,q̇ₘ,tₘ) + Jac_F!(∂F∂q, ∂F∂q̇, ∂Q̌∂s̄, ∂ζ∂q, ζ, qₘ,q̇ₘ,tₘ, cluster_cache) + + ∂F∂s̄ = transpose(∂Q̌∂s̄) + + Aₖ₋₁ = A(qₖ₋₁) + Aᵀₖ₋₁ = transpose(Aₖ₋₁) + Aₖ = A(qₖ) + + 𝐫𝐞𝐬[ 1:nq ] .= M*(qₖ.-qₖ₋₁) .- + h.*pₖ₋₁ .- + (h^2)/2 .*Fₘ .+ + mass_norm.*Aᵀₖ₋₁*λₘ + 𝐫𝐞𝐬[nq+1:nq+nλ] .= mass_norm.*Φ(qₖ) + 𝐫𝐞𝐬[nq+nλ+1:nx] .= ψ(sₖ) + + n = length(ζ) + ∂s̄∂s̄ = I(n) + κ₁ = 10; κ₂ = 10 + cosₘ = 1/2 + coqₘ = 1/2 + coes = [((ζ[i]/κ₁)^2 + (κ₂*sₖ[i])^2)^(-1/2) for i in 1:n] + coζ = diagm(coes.*[ζ[i]/κ₁^2 for i in 1:n] .- [1/κ₁ for i in 1:n]) + cos̄ = diagm(coes.*[κ₂^2*sₖ[i] for i in 1:n] .- [κ₂ for i in 1:n]) + + 𝐉 .= 0.0 + 𝐉[ 1:nq , 1:nq ] .= M.-(h^2)/2 .*(1/2 .*∂F∂q.+1/h.*∂F∂q̇) + 𝐉[ 1:nq ,nq+1:nq+nλ] .= mass_norm.*transpose(Aₖ₋₁) + 𝐉[ 1:nq ,nq+nλ+1:end] .= 0.0 + + 𝐉[nq+1:nq+nλ, 1:nq ] .= mass_norm.*Aₖ + 𝐉[nq+1:nq+nλ, nq+1:nq+nλ ] .= 0.0 + 𝐉[nq+1:nq+nλ, nq+nλ+1:end ] .= 0.0 + + 𝐉[nq+nλ+1:end,1:nq] .= coqₘ*coζ*∂ζ∂q + 𝐉[nq+nλ+1:end,nq+1:nq+nλ] .= 0.0 + 𝐉[nq+nλ+1:end,nq+nλ+1:end] .= cos̄*∂s̄∂s̄ + + lu𝐉 = lu(𝐉) + + if (na != 0) + (; + H, + restitution_coefficients, + D, + ) = contact_cache.cache + Dₘ = contact_cache.cache.Dper + Dₖ = contact_cache.cache.Dimp + 𝐁 .= 0 + 𝐁[ 1:n1,1:nΛ] .= h.*mass_norm.*transpose(D)*H + 𝐫𝐞𝐬 .-= 𝐁*Λₖ + + if doin + pₖ .= Momentum_k(qₖ₋₁,pₖ₋₁,qₖ,λₘ,M,A,mass_norm,h) + vₖ .= invM*pₖ + ∂vₘ∂qₖ = 1/h*I + ∂vₖ∂qₖ = 2/h*I + mass_norm/(h).*invM*(∂Aᵀλ∂q(qₖ,λₘ)) + ∂vₖ∂λₘ = mass_norm.*invM*transpose(Aₖ-Aₖ₋₁)/(h) + + v́⁺ = Dₘ*vₘ .+ Dₖ*vₖ + ∂v́⁺∂qₖ = Dₘ*∂vₘ∂qₖ .+ Dₖ*∂vₖ∂qₖ + 𝐜ᵀ .= 0 + v́ₖ₋₁ = Dₖ*vₖ₋₁ + for i = 1:na + is = 3(i-1) + vⁱₖ₋₁ = @view v́ₖ₋₁[is+1:is+3] + vⁱ⁺ = @view v́⁺[is+1:is+3] + vₜⁱₖ₋₁ = norm(vⁱₖ₋₁[2:3]) + vₜⁱ⁺ = norm(vⁱ⁺[2:3]) + vₙⁱₖ₋₁ = vⁱₖ₋₁[1] + vₙⁱ = vⁱ⁺[1] + v́ₜⁱ = vₜⁱ⁺ + restitution_coefficients[i]*min(vₙⁱₖ₋₁,0) + 𝐛[is+1:is+3] .= [v́ₜⁱ,0,0] + Dⁱₘ = @view Dₘ[is+1:is+3,:] + Dⁱₖ = @view Dₖ[is+1:is+3,:] + 𝐜ᵀ[is+1 , 1:n1] .= 1/(norm(v́⁺[is+2:is+3])+1e-14)*(v́⁺[is+2]*∂v́⁺∂qₖ[is+2,:] .+ v́⁺[is+3]*∂v́⁺∂qₖ[is+3,:]) + 𝐜ᵀ[is+1:is+3, 1:n1] .+= ∂v́⁺∂qₖ[is+1:is+3,:] + 𝐜ᵀ[is+1:is+3,n1+1:n2] .= Dⁱₖ*∂vₖ∂λₘ + end + # 𝐜ᵀinv𝐉 = 𝐜ᵀ*inv(𝐉) + 𝐲 .= (v́⁺ + 𝐛) + end + end + lu𝐉 + end + ns_stepk! +end + +function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Hole_Cache; + dt, + ftol=1e-14,xtol=ftol, + verbose=false,verbose_contact=false, + maxiters=50, + max_restart=3, + progress=true,exception=true) + (;prob,controller,tspan,restart,totalstep) = sim + (;bot,env) = prob + (;structure,traj,contacts_traj) = bot + (;M,A,contacts_bits,options) = solver_cache.cache + q0 = traj.q[begin] + λ0 = traj.λ[begin] + s0 = traj.s[begin] + q̇0 = traj.q̇[begin] + activate_frictional_contacts!(structure,env,solver_cache,q0) + invM = inv(M) + pₖ₋₁ = M*q̇0 + pₖ = zero(pₖ₋₁) + T = eltype(q0) + nq = length(q0) + nλ = length(λ0) + ns = length(s0) + F = zeros(T,nq) + ∂F∂q = zeros(T,nq,nq) + ∂F∂q̇ = zeros(T,nq,nq) + nx = nq + nλ + ns + Δx = zeros(T,nx) + x = zero(Δx) + Res = zero(Δx) + Jac = zeros(T,nx,nx) + Res_α0 = zero(Δx) + Jac_α0 = zeros(T,nx,nx) + Res_α1 = zero(Δx) + Jac_α1 = zeros(T,nx,nx) + Res_α2 = zero(Δx) + Jac_α2 = zeros(T,nx,nx) + mr = norm(M,Inf) + mass_norm = mr + α0 = 1.0 + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, cluster_cache = init_cluster_matrix(structure) + + iteration = 0 + prog = Progress(totalstep; dt=1.0, enabled=progress) + for timestep = 1:totalstep + #---------Time Step k Control----------- + # control!(sim,cache) + #---------Time Step k Control----------- + cₖ₋₁ = contacts_traj[timestep] + cₖ = contacts_traj[timestep+1] + qₖ₋₁ = traj.q[timestep] + sₖ₋₁ = traj.s[timestep] + q̇ₖ₋₁ = traj.q̇[timestep] + # pₖ₋₁ = traj.p[timestep] + # λₖ₋₁ = traj.λ[timestep] + tₖ₋₁ = traj.t[timestep] + qₖ = traj.q[timestep+1] + sₖ = traj.s[timestep+1] + q̇ₖ = traj.q̇[timestep+1] + # pₖ = traj.p[timestep+1] + λₘ = traj.λ[timestep+1] + pₖ₋₁ = M*q̇ₖ₋₁ + qˣ = qₖ₋₁ .+ dt./2 .*q̇ₖ₋₁ + qₖ .= qₖ₋₁ .+ dt .*q̇ₖ₋₁ + q̇ₖ .= q̇ₖ₋₁ + contact_cache = activate_frictional_contacts!(structure,env,solver_cache,qˣ;checkpersist=options.checkpersist) + (;na,L) = contact_cache.cache + isconverged = false + normRes = typemax(T) + iteration_break = 0 + isconverged = false + nΛ = 3na + Λₖ = zeros(T,nΛ) + Λʳₖ = copy(Λₖ) + ΔΛₖ = copy(Λₖ) + 𝐁 = zeros(T,nx,nΛ) + 𝐁t = zeros(T,nx,nΛ) + 𝐛 = zeros(T,nΛ) + 𝐜ᵀ = zeros(T,nΛ,nx) + 𝐍 = zeros(T,nΛ,nΛ) + 𝐲 = zeros(T,nΛ) + get_frictional_directions_and_positions!(structure, contact_cache, qₖ₋₁, q̇ₖ₋₁, Λₖ) + ns_stepk! = make_step_k( + solver_cache, + nq,nλ,ns,na, + qₖ₋₁,sₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁, + pₖ,q̇ₖ, + invM, + dt,mass_norm + ) + restart_count = 0 + Λ_guess = 0.1 + while restart_count < max_restart + Λₖ .= repeat([Λ_guess,0,0],na) + x[ 1:nq] .= qₖ + x[ nq+1:nq+nλ] .= 0.0 + x[nq+nλ+1:nx] .= sₖ₋₁ + Λʳₖ .= Λₖ + Nmax = maxiters + for iteration = 1:maxiters + luJac = ns_stepk!( + Res,Jac, + F,∂F∂q,∂F∂q̇, + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, + 𝐁,𝐛,𝐜ᵀ,𝐲, + x,Λʳₖ, + structure, + contact_cache, + cluster_cache, + timestep,iteration + ) + # if (tₖ₋₁ == 0.096) & (iteration == 1) + # @show size(Jac) + # write("jac1.bin", Jac) + # end + if na == 0 + normRes = norm(Res) + if normRes < ftol + isconverged = true + iteration_break = iteration-1 + break + end + Δx .= luJac\(-Res) + x .+= Δx + else # na!=0 + normRes = norm(Res) + if normRes < ftol + isconverged = true + iteration_break = iteration-1 + break + elseif normRes > 1e10 + # force restart + iteration_break = iteration-1 + isconverged = false + break + elseif iteration == maxiters + iteration_break = iteration-1 + isconverged = false + end + get_distribution_law!(structure,contact_cache,x[1:nq]) + sd = 1/norm(Res)^2*I + ϕ0 = 0.5 + dϕ0 = -1.0 + c1 = 0.2 + α0 = 2.0 + 𝐍 .= 𝐜ᵀ*(luJac\𝐁) + for line_search_step = 1:5 + α0 /= 2 + 𝐡 = 𝐲 .-𝐜ᵀ*(luJac\(Res + (1/α0) .*𝐁*Λʳₖ)) + yₖini = 1/α0 .*𝐍*Λʳₖ + 𝐡 + Λₖini = deepcopy(Λʳₖ) + Λₖini[begin+1:3:end] .= 0.0 + Λₖini[begin+2:3:end] .= 0.0 + yₖini .= abs.(yₖini) + yₖini[begin+1:3:end] .= 0.0 + yₖini[begin+2:3:end] .= 0.0 + IPM!(Λₖ,na,nΛ,Λₖini,yₖini,(1/α0).*𝐍 .+ L,𝐡;ftol,Nmax) + ΔΛₖ .= (Λₖ - Λʳₖ) + minusResΛ = -Res + 𝐁*((1/α0).*ΔΛₖ) + Δx .= luJac\minusResΛ + ns_stepk!( + Res_α0,Jac_α0, + F,∂F∂q,∂F∂q̇, + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, + 𝐁t,𝐛,𝐜ᵀ,𝐲, + x.+Δx,Λʳₖ.+ΔΛₖ, + structure, + contact_cache, + cluster_cache, + timestep,iteration,false + ) + ϕα0 = (transpose(Res_α0)*sd*Res_α0)/2 + if ϕα0 <= ϕ0 + c1*α0*dϕ0 + break + end + end + Λₖ .= Λʳₖ .+ ΔΛₖ + Λʳₖ .= Λₖ + x .+= Δx + end + end + if isconverged + break + end + restart_count += 1 + if na > 0 + Λ_guess = max(Λ_guess/10,maximum(abs.(Λₖ[begin:3:end]))) + end + end + qₖ .= x[ 1:nq] + λₘ .= x[ nq+1:nq+nλ] + sₖ .= x[nq+nλ+1:nx] + pₖ .= Momentum_k(qₖ₋₁,pₖ₋₁,qₖ,λₘ,M,A,mass_norm,dt) + q̇ₖ .= invM*pₖ + Dₘ = contact_cache.cache.Dper + Dₖ = contact_cache.cache.Dimp + if na != 0 + update_contacts!(cₖ[contacts_bits],cₖ₋₁[contacts_bits],Dₘ*(qₖ.-qₖ₋₁).+Dₖ*q̇ₖ,2*Λₖ./(mass_norm*dt)) + end + + if !isconverged + @warn "Newton max iterations $maxiters, at timestep=$timestep, normRes=$(normRes), restart_count=$(restart_count), num_active_contacts=$(na), α0=$(α0)" + if exception + @error "Not converged!" + break + else + # sim.convergence = false + # break + end + end + + #---------Time Step k finisher----------- + if verbose || (na > 0 && verbose_contact) + dg_step = ceil(Int,log10(totalstep))+1 + dg_dt = max(1,-floor(Int,log10(dt))) + wd_t = ceil(Int,log10(traj.t[end]))+dg_dt+1+1 + progfmt = Printf.Format("Prog.: %5.1f%%, step: %$(dg_step)u, time: %$(wd_t).$(dg_dt)f, iters: %s, contacts: %s \n") + progstr = Printf.format(progfmt, + floor(timestep/totalstep*100;digits=1), timestep, traj.t[timestep], iteration_break, na + ) + print(progstr) + end + next!(prog) + end + bot +end diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_hole.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_hole.jl new file mode 100644 index 0000000..9a5f172 --- /dev/null +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_hole.jl @@ -0,0 +1,226 @@ +struct Zhong06_Constant_Mass_Hole_Cache{solT,cacheType} + solver::solT + cache::cacheType +end + +function generate_cache( + simulator::Simulator{<:AbstractDynamicsProblem}, + solver::DynamicsSolver{Zhong06,Nothing,MonolithicApparatusSolver{CableHole}}, + ::Val{true}; + dt,kargs... + ) + (;prob) = simulator + (;bot,policy) = prob + (;traj,structure) = bot + options = merge( + (gravity=false,factor=1,checkpersist=true), #default + prob.options, + solver.options, + ) + @show "Yes" + (;M,M⁻¹,M̌,M̌⁻¹,Ḿ,M̄)= build_mass_matrices(structure) + A = make_cstr_jacobian(structure) + Φ = make_cstr_function(structure) + ψ = build_ψ_hole(structure) + F!(F,q,s,s_temp,q̇,t) = generalized_force_hole!(F,bot,policy,q,q̇,t,s,s_temp;gravity=options.gravity) + Jac_F!(∂F∂q,∂F∂q̇,∂Q̌∂s̄,∂ζ∂q,ζ,qₘ,q̇ₘ,tₘ,cluster_cache) = generalized_force_jacobian_hole!(∂F∂q,∂F∂q̇,∂Q̌∂s̄,∂ζ∂q,ζ,bot,policy,qₘ,q̇ₘ,tₘ,cluster_cache) + q̌0 = traj.q̌[begin] + λ0 = traj.λ[begin] + q̇0 = traj.q̇[begin] + q̇0 = traj.q̇[begin] + p̌0 = traj.p̌[begin] .= Ḿ*q̇0 + s0 = traj.s[begin] + T = eltype(q̌0) + nq̌ = length(q̌0) + nλ = length(λ0) + ns = length(s0) + ∂F∂q̌ = zeros(T,nq̌,nq̌) + ∂F∂q̌̇ = zeros(T,nq̌,nq̌) + nx = nq̌ + nλ + ns + xₖ = vcat(q̌0,λ0,s0) + Res = zero(xₖ) + Jac = Res*transpose(Res) + Zhong06_Constant_Mass_Hole_Cache( + solver, + @eponymtuple( + F!,Jac_F!, + Ḿ,M̌,M̄,M̌⁻¹,A,Φ,ψ, + ∂F∂q̌,∂F∂q̌̇, + nq̌,nλ,nx, + xₖ, + Res, + Jac, + options + ) + ) +end + +function retrieve!(sim,cache::Zhong06_Constant_Mass_Hole_Cache) + +end + +function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Hole_Cache; + dt,ftol=1e-14,verbose=false,maxiters=50, + progress=true,exception=true) + (;prob,controller,tspan,restart,totalstep) = sim + (;bot,) = prob + (;traj) = bot + (; + F!,Jac_F!, + Ḿ,M̌,M̄,M̌⁻¹,A,Φ,ψ, + ∂F∂q̌,∂F∂q̌̇, + nq̌,nλ,nx, + xₖ, + Res, + Jac + ) = cache.cache + mr = norm(Ḿ,Inf) + mass_norm = mr + s_temp = zeros(nx-nλ-nq̌) + h = dt + T = get_numbertype(bot) + function make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ,s_temp,qₖ₋₁,sₖ₋₁, p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) + @inline @inbounds function inner_Res_stepk!(Res,x) + q̌ₖ .= x[ 1:nq̌ ] + λₖ .= x[nq̌+1:nq̌+nλ] + sₖ .= x[nq̌+nλ+1:nx] + qₘ = (qₖ.+qₖ₋₁)./2 + sₘ = (sₖ.+sₖ₋₁)./2 + q̇ₘ = (qₖ.-qₖ₋₁)./h + tₘ = tₖ₋₁+h/2 + F!(F̌,qₘ, sₖ, s_temp, q̇ₘ, tₘ) + Res[ 1:nq̌ ] .= Ḿ*(qₖ.-qₖ₋₁) .- + h.*p̌ₖ₋₁ .- + (h^2)/2 .*F̌ .+ + mass_norm.*Aᵀₖ₋₁*λₖ + Res[nq̌+1:nq̌+nλ] .= mass_norm.*Φ(qₖ) + Res[nq̌+nλ+1:nx] .= ψ(sₖ) + end + end + + function Jac_stepk!(Jac,x,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,∂Q̌∂s̄,∂ζ∂q,∂ζ∂s̄,ζ,Aᵀₖ₋₁,tₖ₋₁,cluster_cache) + q̌ₖ .= x[1:nq̌] + sₖ .= x[nq̌+nλ+1:end] + qₘ = (qₖ.+qₖ₋₁)./2 + q̇ₘ = (qₖ.-qₖ₋₁)./h + tₘ = tₖ₋₁+h/2 + sₘ = (sₖ.+sₖ₋₁)./2 + Jac_F!(∂F∂q̌, ∂F∂q̌̇, ∂Q̌∂s̄, ∂ζ∂q, ζ, qₘ,q̇ₘ,tₘ, cluster_cache) + n = length(ζ) + ∂s̄∂s̄ = I(n) + ∂F∂s̄ = transpose(∂Q̌∂s̄) + + κ₁ = 10; κ₂ = 10 + cosₘ = 1/2 + coqₘ = 1/2 + coes = [((ζ[i]/κ₁)^2 + (κ₂*sₖ[i])^2)^(-1/2) for i in 1:n] + coζ = diagm(coes.*[ζ[i]/κ₁^2 for i in 1:n] .- [1/κ₁ for i in 1:n]) + cos̄ = diagm(coes.*[κ₂^2*sₖ[i] for i in 1:n] .- [κ₂ for i in 1:n]) + + Jac[ 1:nq̌ , 1:nq̌ ] .= M̌.-(h^2)/2 .*(1/2 .*∂F∂q̌.+1/h.*∂F∂q̌̇) + Jac[ 1:nq̌ ,nq̌+1:nq̌+nλ] .= mass_norm.*Aᵀₖ₋₁ + Jac[ 1:nq̌ ,nq̌+nλ+1:end] .= 0.0 + + Jac[nq̌+1:nq̌+nλ, 1:nq̌ ] .= mass_norm.*A(qₖ) + Jac[nq̌+1:nq̌+nλ, nq̌+1:nq̌+nλ ] .= 0.0 + Jac[nq̌+1:nq̌+nλ, nq̌+nλ+1:end ] .= 0.0 + + Jac[nq̌+nλ+1:end,1:nq̌] .= coζ*∂ζ∂q*coqₘ + Jac[nq̌+nλ+1:end,nq̌+1:nq̌+nλ] .= 0.0 + Jac[nq̌+nλ+1:end,nq̌+nλ+1:end] .= cos̄*∂s̄∂s̄ + end + + iteration_break = 0 + prog = Progress(totalstep; dt=1.0, enabled=progress) + dg_step = ceil(Int,log10(totalstep))+1 + dg_dt = max(1,-floor(Int,log10(h))) + wd_t = ceil(Int,log10(traj.t[end]))+dg_dt+1+1 + progfmt = Printf.Format("Progress: %5.1f%%, step: %$(dg_step)u, time: %$(wd_t).$(dg_dt)f, iterations: %s \n") + + ∂Q̌∂s̄, ∂ζ∂q, ∂ζ∂s̄, ζ, cluster_cache = init_cluster_matrix(bot.structure) + + for timestep = 1:totalstep + #---------Step k Control----------- + # control!(sim,cache) + #---------Step k Control----------- + tₖ₋₁ = traj.t[timestep] + tₖ = traj.t[timestep+1] + qₖ₋₁ = traj.q[timestep] + sₖ₋₁ = traj.s[timestep] + q̌ₖ₋₁ = traj.q̌[timestep] + q̌̇ₖ₋₁ = traj.q̌̇[timestep] + p̌ₖ₋₁ = traj.p̌[timestep] + qₖ = traj.q[timestep+1] + sₖ = traj.s[timestep+1] + q̌ₖ = traj.q̌[timestep+1] + q̌̇ₖ = traj.q̌̇[timestep+1] + q̃̇ₖ = traj.q̃̇[timestep+1] + λₖ = traj.λ[timestep+1] + p̌ₖ = traj.p̌[timestep+1] + F̌ = traj.F̌[timestep+1] + xₖ[ 1:nq̌] .= q̌ₖ₋₁ .+ h.*q̌̇ₖ₋₁ + xₖ[nq̌+1:nq̌+nλ] .= 0 + xₖ[nq̌+nλ+1:nx] .= sₖ₋₁ + Aᵀₖ₋₁ = transpose(A(qₖ₋₁)) + @show 0, s_temp + Res_stepk! = make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ,s_temp,qₖ₋₁,sₖ₋₁,p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) + isconverged = false + normRes = typemax(T) + if true#Jac_F! isa Missing + dfk = OnceDifferentiable(Res_stepk!,xₖ,Res) + Res_stepk_result = nlsolve(dfk, xₖ; ftol, iterations=maxiters, method=:newton) + isconverged = converged(Res_stepk_result) + iteration_break = Res_stepk_result.iterations + Res_stepk_result.iterations + xₖ .= Res_stepk_result.zero + else + for iteration = 1:maxiters + Res_stepk!(Res,xₖ) + normRes = norm(Res) + if normRes < ftol + isconverged = true + iteration_break = iteration-1 + break + end + # FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) + Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,∂Q̌∂s̄,∂ζ∂q,∂ζ∂s̄,ζ,Aᵀₖ₋₁,tₖ₋₁,cluster_cache) + xₖ .+= Jac\(-Res) + end + # dfk = OnceDifferentiable(Res_stepk!,Jac_stepk!,xₖ,Res) + end + @show xₖ[nq̌+nλ+1:end] + s_temp += xₖ[nq̌+nλ+1:end] * dt + @show 1, s_temp + + if !isconverged + # Res_stepk!(Res,xₖ) + # Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) + # write("j1.bin", Jac) + # FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) + # write("j2.bin", Jac) + if exception + error("Not Converged! Step=$timestep, normRes=$normRes") + else + # sim.convergence = false + break + end + end + q̌ₖ .= xₖ[ 1:nq̌ ] + λₖ .= xₖ[nq̌+1:nq̌+nλ] + sₖ .= xₖ[nq̌+nλ+1:nx] + Momentum_k!(p̌ₖ,p̌ₖ₋₁,qₖ,qₖ₋₁,λₖ,Ḿ,A,Aᵀₖ₋₁,mass_norm,h) + q̌̇ₖ .= M̌⁻¹*(p̌ₖ.-M̄*q̃̇ₖ ) + #---------Step k finisher----------- + #---------Step k finisher----------- + if verbose + progstr = Printf.format( + progfmt, + floor(timestep/totalstep*100;digits=1), timestep, tₖ, iteration_break + ) + print(progstr) + end + next!(prog) + end + + bot +end diff --git a/src/mechanics/solvers.jl b/src/mechanics/solvers.jl index 91d6ac0..94e7fa7 100644 --- a/src/mechanics/solvers.jl +++ b/src/mechanics/solvers.jl @@ -37,6 +37,7 @@ struct ProjectedGaussJacobi <: AbstractComplementaritySolver end const PGJ = ProjectedGaussJacobi struct SmoothedFischerBurmeister <: AbstractComplementaritySolver end struct SemismoothNewton <: AbstractComplementaritySolver end +struct CableHole <: AbstractComplementaritySolver end abstract type AbstractContactSolver <: AbstractSolver end @@ -411,10 +412,12 @@ include("dynamics_solvers/Zhong06_family/Zhong06_nonconstant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_mono.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl") +include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_hole.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_nonconstant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass_mono.jl") include("dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl") +include("dynamics_solvers/Zhong06_family/Zhong06_constant_mass_hole.jl") # include("dynamics_solvers/Zhong06_family/Zhong06_nonholonomic_nonsmooth.jl") include("dynamics_solvers/Zhong06_family/Adjoint_Zhong06_nonconstant_mass.jl") diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index dc459c5..20df6b4 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -918,6 +918,29 @@ function build_ζ!(ζ, cluster_cache, st) end end +function build_ζ_hole!(ζ, cluster_cache, st) + (; apparatuses, connectivity) = st + (; apparid2sys_add_var_idx) = connectivity.indexed + ζ⁺ = @view ζ[begin:2:end] + ζ⁻ = @view ζ[begin+1:2:end] + foreach(apparatuses) do appar + if isa(appar.joint, ClusterJoint) + (; force, joint, id) = appar + (; sps) = joint + (; segs) = force + nsp = length(sps) + idx_begin = Int((apparid2sys_add_var_idx[id][1]-1) / 2) + for i in 1:nsp + Fₙ = norm(segs[i+1].force.state.force + segs[i].force.state.force) + Fᵢ₊₁ = segs[i+1].force.state.tension + Fᵢ = segs[i].force.state.tension + ζ⁺[idx_begin+i] = sps[i].μ*Fₙ - Fᵢ₊₁ + Fᵢ + ζ⁻[idx_begin+i] = Fᵢ₊₁ - Fᵢ + sps[i].μ*Fₙ + end + end + end +end + function build_ζ(st) (; apparatuses, connectivity) = st (; apparid2sys_add_var_idx) = connectivity.indexed diff --git a/src/structures/mutate.jl b/src/structures/mutate.jl index e72f268..188fa49 100644 --- a/src/structures/mutate.jl +++ b/src/structures/mutate.jl @@ -68,6 +68,26 @@ function update_apparatuses!(st::AbstractStructure, s̄::AbstractVector{T}) wher update_apparatuses!(st) end +function update_apparatuses_hole!(st::AbstractStructure, s̄::AbstractVector{T}, s_temp::AbstractVector{T}) where {T} + (;apparatuses) = st + dt = 1e-3 + st.state.system.s .= s̄*dt + s_temp + @show s̄, s_temp + foreach(apparatuses) do appar + if isa(appar, Apparatus{<:ClusterJoint}) + (;id) = appar + (;sps) = appar.joint + idx = st.connectivity.indexed.apparid2sys_add_var_idx[id] + for (i, sp) in enumerate(sps) + sp.s⁺ = s̄[idx[2i-1]] * dt + s_temp[idx[2i-1]] + sp.s⁻ = s̄[idx[2i]] * dt + s_temp[idx[2i]] + sp.s = sp.s⁺ - sp.s⁻ + end + end + end + update_apparatuses!(st) +end + function update_apparatus!(st::AbstractStructure, appar::Apparatus) #default no update end diff --git a/src/structures/structure.jl b/src/structures/structure.jl index 7e17aa8..d789b71 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -462,6 +462,51 @@ function build_ψ(structure::AbstractStructure) inner_ψ end +function build_ψ_hole(structure::AbstractStructure) + (;apparatuses) = structure + nholes = 0 + nh = 0 + FB = FischerBurmeister(1e-14, 10., 10.) + foreach(apparatuses) do appar + if isa(appar, Apparatus{<:ClusterJoint}) + nholes += 1 + nh += length(appar.joint.sps) + end + end + function _inner_ψ(s̄) + ψ = Vector{eltype(s̄)}(undef,2nh) + ψ⁺ = @view ψ[begin:2:end] + ψ⁻ = @view ψ[begin+1:2:end] + s⁺ = @view s̄[begin:2:end] + s⁻ = @view s̄[begin+1:2:end] + ih = 0 + foreach(apparatuses) do appar + if isa(appar, Apparatus{<:ClusterJoint}) + (;sps) = appar.joint + (;segs) = appar.force + nsi = length(sps) + for (i, sp) in enumerate(sps) + Fₙ = norm(segs[i+1].force.state.force + segs[i].force.state.force) + Fᵢ₊₁ = segs[i+1].force.state.tension + Fᵢ = segs[i].force.state.tension + ζ⁺ = sp.μ*Fₙ - Fᵢ₊₁ + Fᵢ + ζ⁻ = Fᵢ₊₁ - Fᵢ + sp.μ*Fₙ + ψ⁺[ih+i] = FB(ζ⁺, s⁺[ih+i]) + ψ⁻[ih+i] = FB(ζ⁻, s⁻[ih+i]) + # @show ζ⁺, ζ⁻ + end + ih += nsi + end + end + ψ + end + + function inner_ψ(s̄) + _inner_ψ(s̄) + end + inner_ψ +end + function build_F̌(st,bodyid,pid,f) T = get_numbertype(st) (;num_of_free_coords,bodyid2sys_free_coords) = st.connectivity.indexed diff --git a/yard/ex1/define.jl b/yard/ex1/define.jl new file mode 100644 index 0000000..661b760 --- /dev/null +++ b/yard/ex1/define.jl @@ -0,0 +1,83 @@ +function build_structure() + pos_list = [[-sqrt(3), 0.0, 1.0+0.2/sqrt(3)] [1-sqrt(3), 0, 1.0+0.2/sqrt(3)] [1.0, 0, 0.2/sqrt(3)]] + nb = length(pos_list[1, :]) + + function rigidbody(id, pos) + if id <= 2 + contactable = false + else + contactable = true + end + visible = true + cᵢ = Int[] + Φᵢ = collect(1:6) + + rᵢ = pos + if id == 3 + radius = 0.1 + # aps = vcat([[0.0 0.0 0.0]], [radius*[-sin(β) 0.0 -cos(β)] for β in 0:0.1:π/2]) + aps = [[0.0 0.0 0.0], radius*[-sin(π/6) 0.0 -cos(π/6)]] + else + aps = [[0.0 0.0 0.0]] + end + θ = 0 + α = [cos(θ) -sin(θ) 0; sin(θ) cos(θ) 0; 0 0 1] + r̄g = [0.0 0.0 0.0] + m = 2.0 + I = [1.0 0 0; 0 1.0 0; 0 0 1.0] + nrp = length(aps) + ṙₒ = zeros(3) + ω = zeros(Float64, 3) + prop = RB.RigidBodyProperty( + id, contactable, m, SMatrix{3, 3}(I), SVector{3}(r̄g), [SVector{3}(aps[i]) for i in 1:nrp]; visible + ) + + state = RB.RigidBodyState(prop, rᵢ, α, ṙₒ, ω) + nmcs = RB.NCF.NC1P3V(SVector{3}(rᵢ)) + coords = RB.NonminimalCoordinates(nmcs, cᵢ, Φᵢ) + sphere = Meshes.Sphere((0.0, 0.0, 0.0), 0.1) + simple_mesh = Meshes.discretize(sphere, Meshes.RegularDiscretization(30, 30)) + mesh = simple_mesh |> RB.simple2mesh + RB.RigidBody(prop, state, coords, mesh) + end + + rbs = [rigidbody(i, pos_list[:, i]) for i in 1:nb] + bodies = TypeSortedCollection(rbs) + + pre = 9.8*6 + restlens = [1.0 2.0] + kc = 1e3 + ncluster = 1 + cluster_segs = [[RB.DistanceSpringDamperSegment(restlens[i], kc, prestress=pre) for i in 1:2] for _ in 1:ncluster] + cluster_sps = [[RB.SlidingPoint(0.4) for i in 1:1] for _ in 1:ncluster] + + cluster_matrix = [[1 1 2 1; 2 1 3 1]] + clusters = RB.connect_clusters(bodies, cluster_sps, cluster_segs, cluster_matrix) + cst1 = RB.FixedBodyConstraint(ncluster+1, rbs[1]) + cst2 = RB.FixedBodyConstraint(ncluster+2, rbs[2]) + apparatuses = TypeSortedCollection(vcat([cst1], [cst2], clusters)) + + indexed = RB.index(bodies, apparatuses) + numbered = RB.number(bodies, apparatuses) + cnt = RB.Connectivity(numbered, indexed) + structure = RB.Structure(bodies, apparatuses, cnt) + + gauges = Int[] + actuators = [ + RB.ExternalForceActuator( + i, + cluster, + RB.NaiveOperator(1), + 0.0, + [0.0] + ) + for (i, cluster) in enumerate(clusters) + ] + hub = RB.ControlHub( + structure, + gauges, + actuators, + RB.Coalition(structure, gauges, actuators,) + ) + bot = RB.Robot(structure, hub) +end \ No newline at end of file diff --git a/yard/ex1/main1.jl b/yard/ex1/main1.jl new file mode 100644 index 0000000..6627d4f --- /dev/null +++ b/yard/ex1/main1.jl @@ -0,0 +1,108 @@ +using TestEnv +TestEnv.activate() + +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/tensegrity.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = joinpath(pathof(RB),"../../tmp") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../yard/ex1/define.jl")) +includet(joinpath(pathof(RB),"../../yard/ex1/define.jl")) + +θ = pi / 6 +ground_plane = RB.StaticContactSurfaces( + [ + RB.HalfSpace([tan(θ),0,1], [1.0,0.0,0.0]) + ] +); + +test = build_structure() +# plot_traj!(test; +# ground=ground_plane) + +policy = RB.TimePolicy( + @eponymtuple( + f = (t) -> [2t] + ) +) + + +RB.solve!( + RB.DynamicsProblem( + test, policy, + ground_plane, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ), + RB.EulerEytelwein(); + ), + RB.DynamicsSolver( + RB.Zhong06(), + # RB.InnerLayerContactSolver( + # RB.InteriorPointMethod() + # ), + RB.MonolithicApparatusSolver( + RB.CableHole() + # RB.SmoothedFischerBurmeister() + ), + ); + tspan = (0.0, 0.031), + dt = 1e-3, + ftol = 1e-9, + verbose = true +) + +test = build_structure() +plot_traj!(test; + ground=ground_plane) + +dts = [1e-2, + 9e-3, 8e-3, 7e-3, 6e-3, 5e-3, 4e-3, 3e-3, 2e-3, 1e-3, + 9e-4, 8e-4, 7e-4, 6e-4, 5e-4, 4e-4, 3e-4, 2e-4, 1e-4, + 1e-5] +pm_dts = [] +for dt in dts + @show dt + RB.solve!( + RB.DynamicsProblem( + test, policy, + ground_plane, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ), + RB.EulerEytelwein(); + ), + RB.DynamicsSolver( + RB.Zhong06(), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan = (0.0, 0.5), + dt, + ftol = dt==1e-5 ? 1e-12 : 1e-9, + verbose = true + ) + push!(pm_dts, deepcopy(test)) +end + + +idx = [1,2,3,4,5,6,9,10,14,15,17] +idx = collect(8:19) +fig = Figure() +ax = Axis(fig[1,1],ylabel = "Abs. Err.") +_,err_nmsi = RB.get_err_avg(pm_dts;bid=3,pid=1,di=3) +plot_convergence_order!(ax,dts[begin:end-1][idx],err_nmsi[idx];orders=[1, 2],label="NMSI") +# plot_convergence_order!(ax,dts[begin:end-1],err_nmsi;orders=[1, 2],label="NMSI") +fig \ No newline at end of file diff --git a/yard/ex1/main2.jl b/yard/ex1/main2.jl new file mode 100644 index 0000000..14ea717 --- /dev/null +++ b/yard/ex1/main2.jl @@ -0,0 +1,108 @@ +using TestEnv +TestEnv.activate() + +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/tensegrity.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = joinpath(pathof(RB),"../../tmp") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../yard/ex1/define.jl")) +includet(joinpath(pathof(RB),"../../yard/ex1/define.jl")) + +θ = pi / 6 +ground_plane = RB.StaticContactSurfaces( + [ + RB.HalfSpace([tan(θ),0,1], [1.0,0.0,0.0]) + ] +); + +test = build_structure() +# plot_traj!(test; +# ground=ground_plane) + +policy = RB.TimePolicy( + @eponymtuple( + f = (t) -> [t] + ) +) + + +RB.solve!( + RB.DynamicsProblem( + test, policy, + ground_plane, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ), + RB.EulerEytelwein(); + ), + RB.DynamicsSolver( + RB.Zhong06(), + # RB.InnerLayerContactSolver( + # RB.InteriorPointMethod() + # ), + RB.MonolithicApparatusSolver( + RB.CableHole() + # RB.SmoothedFischerBurmeister() + ), + ); + tspan = (0.0, 0.061), + dt = 1e-3, + ftol = 1e-9, + verbose = true +) + +test = build_structure() +plot_traj!(test; + ground=ground_plane) + +dts = [1e-2, + 9e-3, 8e-3, 7e-3, 6e-3, 5e-3, 4e-3, 3e-3, 2e-3, 1e-3, + 9e-4, 8e-4, 7e-4, 6e-4, 5e-4, 4e-4, 3e-4, 2e-4, 1e-4, + 1e-5] +pm_dts = [] +for dt in dts + @show dt + RB.solve!( + RB.DynamicsProblem( + test, policy, + ground_plane, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ), + RB.EulerEytelwein(); + ), + RB.DynamicsSolver( + RB.Zhong06(), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ), + RB.MonolithicApparatusSolver( + RB.SmoothedFischerBurmeister() + ), + ); + tspan = (0.0, 0.5), + dt, + ftol = dt==1e-5 ? 1e-12 : 1e-9, + verbose = true + ) + push!(pm_dts, deepcopy(test)) +end + + +idx = [1,2,3,4,5,6,9,10,14,15,17] +idx = collect(8:19) +fig = Figure() +ax = Axis(fig[1,1],ylabel = "Abs. Err.") +_,err_nmsi = RB.get_err_avg(pm_dts;bid=3,pid=1,di=3) +plot_convergence_order!(ax,dts[begin:end-1][idx],err_nmsi[idx];orders=[1, 2],label="NMSI") +# plot_convergence_order!(ax,dts[begin:end-1],err_nmsi;orders=[1, 2],label="NMSI") +fig \ No newline at end of file From 8b849e8c533ee7c3a38fa070c1f523492a6755ba Mon Sep 17 00:00:00 2001 From: Perseus Date: Thu, 16 May 2024 12:53:15 +0800 Subject: [PATCH 13/20] fix small bugs --- src/mechanics/dynamics.jl | 12 ++++++------ src/postprocess/vis.jl | 2 +- src/structures/mutate.jl | 1 + src/structures/structure.jl | 2 +- yard/ex1/main1.jl | 18 +++++++++--------- 5 files changed, 18 insertions(+), 17 deletions(-) diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index fa796d9..e18868f 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -87,8 +87,8 @@ function generalized_force_hole!(F,bot::Robot,policy::AbstractPolicy,q,q̇,t,s,s user_defined_force!(F,t) end -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t,s=nothing) - generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,NoPolicy(),q,q̇,t,s=nothing) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t,∂F∂s,s=nothing) + generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,NoPolicy(),q,q̇,t,∂F∂s,s) end function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,) @@ -341,7 +341,7 @@ function activate_frictional_contacts!(structure,contact_env::StaticEnvironment, (;indexed,numbered) = structure.connectivity (;bodyid2sys_loci_idx) = numbered (;num_of_bodies) = indexed - (;surfaces) = contact_env + (;geometry) = contact_env T = eltype(q) nq = length(q) na = 0 @@ -356,7 +356,7 @@ function activate_frictional_contacts!(structure,contact_env::StaticEnvironment, for pid in eachindex(loci_states) locus_state = loci_states[pid] (;frame,contact_state) = locus_state - gap, normal = contact_gap_and_normal(frame.position,surfaces) + gap, normal = contact_gap_and_normal(frame.position,geometry) if !checkpersist contact_state.active = false end @@ -503,7 +503,7 @@ function activate_contacts!(structure,contact_env::StaticEnvironment,solver_cach (;indexed,numbered) = structure.connectivity (;bodyid2sys_loci_idx) = numbered (;num_of_bodies) = indexed - (;surfaces) = contact_env + (;geometry) = contact_env T = eltype(q) nq = length(q) na = 0 @@ -518,7 +518,7 @@ function activate_contacts!(structure,contact_env::StaticEnvironment,solver_cach for pid in eachindex(loci_states) locus_state = loci_states[pid] (;frame,contact_state) = locus_state - gap, normal = contact_gap_and_normal(frame.position,surfaces) + gap, normal = contact_gap_and_normal(frame.position,geometry) if !checkpersist contact_state.active = false end diff --git a/src/postprocess/vis.jl b/src/postprocess/vis.jl index 7757425..0d0745e 100644 --- a/src/postprocess/vis.jl +++ b/src/postprocess/vis.jl @@ -307,7 +307,7 @@ function get_groundmesh(plane::Plane,rect) end function get_groundmesh(static_env::StaticEnvironment,rect) - map(static_env.surfaces) do surface + map(static_env.geometry) do surface GB.Mesh(rect, Meshing.MarchingCubes()) do v signed_distance(v,surface) end diff --git a/src/structures/mutate.jl b/src/structures/mutate.jl index ab46f38..b3446ba 100644 --- a/src/structures/mutate.jl +++ b/src/structures/mutate.jl @@ -320,3 +320,4 @@ function apply_gravity!(st;factor=1) foreach(bodies) do body body.state.mass_locus_state.force .+= gravity_acceleration*body.prop.mass end +end diff --git a/src/structures/structure.jl b/src/structures/structure.jl index 27b678d..b4862f4 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -411,7 +411,7 @@ function make_auxi_jacobian(structure::AbstractStructure,s0) T = get_numbertype(structure) num_of_dim = get_num_of_dims(structure) - κ₁ = 10; κ₂ = 100 + κ₁ = 10; κ₂ = 10 ζ = zeros(T, num_of_add_var) diff --git a/yard/ex1/main1.jl b/yard/ex1/main1.jl index 6627d4f..2bf1168 100644 --- a/yard/ex1/main1.jl +++ b/yard/ex1/main1.jl @@ -23,12 +23,12 @@ ground_plane = RB.StaticContactSurfaces( ); test = build_structure() -# plot_traj!(test; -# ground=ground_plane) +plot_traj!(test; + ground=ground_plane) policy = RB.TimePolicy( @eponymtuple( - f = (t) -> [2t] + f = (t) -> [0.1t] ) ) @@ -45,15 +45,15 @@ RB.solve!( ), RB.DynamicsSolver( RB.Zhong06(), - # RB.InnerLayerContactSolver( - # RB.InteriorPointMethod() - # ), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ), RB.MonolithicApparatusSolver( - RB.CableHole() - # RB.SmoothedFischerBurmeister() + # RB.CableHole() + RB.SmoothedFischerBurmeister() ), ); - tspan = (0.0, 0.031), + tspan = (0.0, 0.5), dt = 1e-3, ftol = 1e-9, verbose = true From d2bf6dedc3b1f973c9e44dd04d62813f85587858 Mon Sep 17 00:00:00 2001 From: Perseus Date: Fri, 17 May 2024 13:52:14 +0800 Subject: [PATCH 14/20] fix bugs --- src/mechanics/dynamics.jl | 2 +- ...hong06_CCP_constant_mass_cluster_cables.jl | 3 +-- src/structures/structure.jl | 23 ++++++++++--------- yard/ex1/main1.jl | 2 +- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index e18868f..1b1120c 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -103,7 +103,7 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy:: build_tangent_damping_matrix!(∂F∂q̌̇,structure) end -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,∂F∂s,s) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,∂F∂s,s::AbstractVector) (;structure,hub) = bot ∂F∂q̌ .= 0 ∂F∂q̌̇ .= 0 diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index 5d9f8c7..88e866f 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -117,8 +117,7 @@ function make_step_k( 𝐉[ 1:nq , 1:nq ] .= M.-(h^2)/2 .*(1/2 .*∂F∂q.+1/h.*∂F∂q̇) 𝐉[ 1:nq , nq+1:nq+nλ] .= mass_norm.*transpose(Aₖ₋₁) 𝐉[ 1:nq ,nq+nλ+1:nx] .= - (h^2)/2 * 1/2 .*∂F∂s - - 𝐉[nq+1:nq+nλ, 1:nq ] .= mass_norm.*Aₖ + 𝐉[nq+1:nq+nλ, 1:nq] .= mass_norm.*Aₖ 𝐉[nq+nλ+1:nx,1:nq] .= ∂S∂q# 1/2 * coζ*∂ζ∂q 𝐉[nq+nλ+1:nx,nq+nλ+1:nx] .= ∂S∂s# 1/2 *coζ*∂ζ∂s + cos̄*I diff --git a/src/structures/structure.jl b/src/structures/structure.jl index b4862f4..c19ae4f 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -44,7 +44,8 @@ function StructureState(bodies,apparatuses,cnt::Connectivity) q̈ = zero(q) F = zero(q) λ = Vector{T}(undef,num_of_cstr) - s = Vector{T}(undef,num_of_add_var) + # s = Vector{T}(undef,num_of_add_var) + s = zeros(T, num_of_add_var) c = get_local_coords(bodies,numbered) p = zero(q) p̌ = Vector{T}(undef,num_of_free_coords) @@ -76,15 +77,15 @@ function StructureState(bodies,apparatuses,cnt::Connectivity) members[body.prop.id].q̇ .= q̇ end #fixme assign to the right places - ## foreach(apparatuses) do appar - ## (;joint) = appar - ## if isa(joint, ClusterJoint) - ## for sp in joint.sps - ## append!(s, sp.s⁺) - ## append!(s, sp.s⁻) - ## end - ## end - ## end + # foreach(apparatuses) do appar + # (;joint) = appar + # if isa(joint, ClusterJoint) + # for sp in joint.sps + # append!(s, sp.s⁺) + # append!(s, sp.s⁻) + # end + # end + # end StructureState(system,members) end @@ -411,7 +412,7 @@ function make_auxi_jacobian(structure::AbstractStructure,s0) T = get_numbertype(structure) num_of_dim = get_num_of_dims(structure) - κ₁ = 10; κ₂ = 10 + κ₁ = 10; κ₂ = 100 ζ = zeros(T, num_of_add_var) diff --git a/yard/ex1/main1.jl b/yard/ex1/main1.jl index 2bf1168..db0f1c5 100644 --- a/yard/ex1/main1.jl +++ b/yard/ex1/main1.jl @@ -28,7 +28,7 @@ plot_traj!(test; policy = RB.TimePolicy( @eponymtuple( - f = (t) -> [0.1t] + f = (t) -> [t] ) ) From 82739c9f12079fdf719bbd2b64c522ca2548a09f Mon Sep 17 00:00:00 2001 From: Perseus Date: Sat, 18 May 2024 09:16:34 +0800 Subject: [PATCH 15/20] remove cluster_cache --- src/mechanics/dynamics.jl | 18 ++++- ...hong06_CCP_constant_mass_cluster_cables.jl | 17 ++-- src/members/apparatus.jl | 77 +++++++++++++++++++ src/structures/constraints.jl | 56 +++++++++++++- src/structures/linearization.jl | 49 ++++++++++++ src/structures/structure.jl | 7 +- yard/ex1/main1.jl | 2 +- yard/jixiebi/Group2_1.jl | 2 +- 8 files changed, 214 insertions(+), 14 deletions(-) diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index 1b1120c..d116f9e 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -131,7 +131,21 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy:: build_tangent_damping_matrix!(∂F∂q̌̇,structure) end -function generalized_force_jacobian!(∂F∂s,structure,q,q̇,t,s,) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,∂F∂s,bot::Robot,policy::AbstractPolicy,q,q̇,t,s::AbstractVector) + (;structure,hub) = bot + ∂F∂q̌ .= 0 + ∂F∂q̌̇ .= 0 + ∂F∂s .= 0 + # clear_forces!(structure) + # lazy_update_bodies!(structure,q,q̇) + # update_apparatuses!(structure) + generalized_force_jacobian!(∂F∂s, structure, q, q̇, t, s) + generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) + build_tangent_stiffness_matrix!(∂F∂q̌,structure) + build_tangent_damping_matrix!(∂F∂q̌̇,structure) +end + +function generalized_force_jacobian!(∂F∂s,structure::AbstractStructure,q,q̇,t,s) (;apparatuses,connectivity) = structure (; apparid2sys_add_var_idx, @@ -141,7 +155,7 @@ function generalized_force_jacobian!(∂F∂s,structure,q,q̇,t,s,) appar_add_var_idx = apparid2sys_add_var_idx[appar.id] appar_free_coords_idx = apparid2sys_free_coords_idx[appar.id] generalized_force_jacobian!( - (@view ∂F∂s[appar_free_coords_idx,appar_add_var_idx]), + (@view ∂F∂s[unique(appar_free_coords_idx),appar_add_var_idx]), appar, structure, q,q̇,t, diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index 88e866f..44b1d2e 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -28,7 +28,8 @@ function generate_cache( solver.options, ) F!(F,q,q̇,t,s) = generalized_force!(F,bot,policy,q,q̇,t,s;gravity=options.gravity) - Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, q,q̇,t, cluster_cache) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, bot,policy, q,q̇,t, ∂F∂s, cluster_cache) + # Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, q,q̇,t, cluster_cache) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, bot,policy, q,q̇,t, ∂F∂s, cluster_cache) + Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, q,q̇,t,s) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, ∂F∂s, bot,policy, q,q̇,t, s) M = Matrix(assemble_M(structure)) Φ = make_cstr_function(bot) @@ -88,7 +89,7 @@ function make_step_k( x,Λₖ, structure, contact_cache, - cluster_cache, + # cluster_cache, timestep,iteration,doin=true ) qₖ = @view x[ 1:nq] @@ -100,8 +101,10 @@ function make_step_k( vₘ = q̇ₘ tₘ = tₖ₋₁+h/2 F!(Fₘ,qₘ,q̇ₘ,tₘ,sₘ,) - Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, qₘ,q̇ₘ,tₘ, cluster_cache) - Jac_S!(∂S∂q, ∂S∂s, qₖ, sₖ, cluster_cache) + # Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, qₘ,q̇ₘ,tₘ, cluster_cache) + Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, qₘ,q̇ₘ,tₘ, sₖ) + # Jac_S!(∂S∂q, ∂S∂s, qₖ, sₖ, cluster_cache) + Jac_S!(∂S∂q, ∂S∂s, qₖ, sₖ) Aₖ₋₁ = A(qₖ₋₁) Aᵀₖ₋₁ = transpose(Aₖ₋₁) Aₖ = A(qₖ) @@ -217,7 +220,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C mr = norm(M,Inf) mass_norm = mr α0 = 1.0 - cluster_cache = init_cluster_matrix(structure) + # cluster_cache = init_cluster_matrix(structure) iteration = 0 prog = Progress(totalstep; dt=1.0, enabled=progress) @@ -285,7 +288,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C x,Λʳₖ, structure, contact_cache, - cluster_cache, + # cluster_cache, timestep,iteration ) # if (tₖ₋₁ == 0.096) & (iteration == 1) @@ -345,7 +348,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C x.+Δx,Λʳₖ.+ΔΛₖ, structure, contact_cache, - cluster_cache, + # cluster_cache, timestep,iteration,false ) ϕα0 = (transpose(Res_α0)*sd*Res_α0)/2 diff --git a/src/members/apparatus.jl b/src/members/apparatus.jl index 5a581c3..5ebd243 100644 --- a/src/members/apparatus.jl +++ b/src/members/apparatus.jl @@ -22,6 +22,19 @@ struct ApparatusCache{JCache,FCache} force_cache::FCache end +struct ApparatusClusterCache{INT, FLO, MAT} + ns::INT + nsegs::INT + nsp::INT + κ₁::FLO + κ₂::FLO + ∂ζ∂s::MAT + ∂s∂s::MAT + Tb::MAT + N::MAT +end + + struct Apparatus{jointType,forceType,cacheType} id::Int joint::jointType @@ -32,6 +45,70 @@ struct Apparatus{jointType,forceType,cacheType} cache::cacheType end +function Apparatus(id::Int,joint::ClusterJoint,force::ClusterDistanceSpringDampers, + num_of_add_var::Int,full_coords_idx,free_coords_idx + ) + T = get_numbertype(joint) + ## T = get_numbertype(force) + (;num_of_cstr,) = joint + num_appar_free_idx = length(free_coords_idx) + + (;segs) = force + (;sps) = joint + Type = Float64 + nsp = length(sps) + ns = 2 * nsp + nsegs = length(segs) + κ₁ = 10. + κ₂ = 100. + # n = length(sps) + ap = [-segs[i+1].force.k for i in 1:nsp-1] + ap0 = [segs[i].force.k + segs[i+1].force.k/sps[i].α for i in 1:nsp] + ap1 = [-segs[i+1].force.k/sps[i].α for i in 1:nsp-1] + an0 = [segs[i].force.k + segs[i+1].force.k*sps[i].α for i in 1:nsp] + an1 = [-segs[i+1].force.k*sps[i].α for i in 1:nsp-1] + A⁺ = diagm(-1=>ap, 0=>ap0, 1=>ap1) + A⁻ = diagm(-1=>ap, 0=>an0, 1=>an1) + A = [A⁺ -A⁺; -A⁻ A⁻] + T = get_TransMatrix(nsegs-1) + + N = zeros(Type, nsegs, 2nsegs-2) + N[1, 1:2] = [1 -1] + N[end, end-1:end] = [-1 1] + for i in 2:nsegs-1 + N[i, 2i-3:2i] = [-1 1 1 -1] + end + + b⁺ = zeros(Type, nsegs-1, nsegs) + b⁻ = zeros(Type, nsegs-1, nsegs) + for i in 1:nsp + k1 = segs[i].force.k + k2 = segs[i+1].force.k + α = sps[i].α + b⁺[i, i:i+1] = [-k1 k2/α] + b⁻[i, i:i+1] = [k1 -k2*α] + end + b = vcat(b⁺, b⁻) + Tb = T * b + ∂ζ∂s = T * A * T' + ∂s∂s = diagm(0=>ones(Type, ns)) + + cache = ApparatusClusterCache( + ns, + nsegs, + nsp, + κ₁, + κ₂, + ∂ζ∂s, + ∂s∂s, + Tb, + N + ) + + + Apparatus(id,joint,force,num_of_add_var,full_coords_idx,free_coords_idx,cache) +end + function Apparatus(id::Int,joint::AbstractJoint,force::AbstractForce, num_of_add_var::Int,full_coords_idx,free_coords_idx ) diff --git a/src/structures/constraints.jl b/src/structures/constraints.jl index a331e57..0bb3a44 100644 --- a/src/structures/constraints.jl +++ b/src/structures/constraints.jl @@ -278,8 +278,9 @@ function auxi_function!(ret, structure::Structure, q, s, s0 ) + (;κ₁,κ₂) = appar.cache - FB = FischerBurmeister(1e-14, 10., 100.) + FB = FischerBurmeister(1e-14, κ₁, κ₂) (;sps) = appar.joint (;segs) = appar.force @@ -300,6 +301,59 @@ function auxi_jacobian!(∂S∂q̌,∂S∂s, appar::Apparatus, structure::Abstra #default do nothing end +function auxi_jacobian!(∂S∂q̌,∂S∂s, + appar::Apparatus{<:ClusterJoint, <:ClusterDistanceSpringDampers}, + structure::AbstractStructure, + q, s, s0 + ) + (;apparatuses, connectivity) = structure + (;indexed) = connectivity + (;num_of_free_coords, apparid2sys_add_var_idx, bodyid2sys_free_coords) = indexed + (;ns, nsegs, nsp, κ₁, κ₂, ∂ζ∂s, ∂s∂s, Tb) = appar.cache + (; force, joint, id) = appar + (; sps) = joint + (; segs) = force + + T = get_numbertype(structure) + ndim = get_num_of_dims(structure) + + ζ = zeros(T, ns) + + ζ⁺ = @view ζ[begin:2:end] + ζ⁻ = @view ζ[begin+1:2:end] + for i in 1:nsp + ζ⁺[i] = segs[i+1].force.state.tension / sps[i].α - segs[i].force.state.tension + ζ⁻[i] = segs[i].force.state.tension - sps[i].α * segs[i+1].force.state.tension + end + coes = [((ζ[i]/κ₁)^2 + (κ₂*s[i])^2)^(-1/2) for i in 1:ns] + coζ = diagm(coes.*[ζ[i]/κ₁^2 for i in 1:ns] .- [1/κ₁ for i in 1:ns]) + cos̄ = diagm(coes.*[κ₂^2*s[i] for i in 1:ns] .- [κ₂ for i in 1:ns]) + + num_of_free = size(∂S∂q̌, 2) + ∂l∂q = zeros(T, nsegs, num_of_free) + foreach(segs) do seg + idx = seg.id + J̌ = zeros(T, ndim, num_of_free) + (; hen, egg) = seg.joint.hen2egg + body_hen = hen.body + body_egg = egg.body + C_hen = body_hen.cache.Cps[hen.pid] + C_egg = body_egg.cache.Cps[egg.pid] + free_idx_hen = body_hen.coords.free_idx + free_idx_egg = body_egg.coords.free_idx + mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] + mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] + (; direction) = seg.force.state + J̌[:, mfree_egg] .+= C_egg[:, free_idx_egg] + J̌[:, mfree_hen] .-= C_hen[:, free_idx_hen] + ∂l∂q[idx, :] = direction'*J̌ + end + + ∂ζ∂q = Tb * ∂l∂q + ∂S∂q̌ .= 1/2 * coζ * ∂ζ∂q + ∂S∂s .= 1/2 * coζ * ∂ζ∂s + cos̄ * ∂s∂s +end + function auxi_jacobian!(∂S∂q̌,∂S∂s, appar::Apparatus{<:PrototypeJoint,<:TorsionalSpringDamper}, structure::AbstractStructure, diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index ec4ab37..82a8263 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -756,6 +756,7 @@ function build_tangent_damping_matrix!(∂Q̌∂q̌̇,st) end end + function init_cluster_matrix(st) (; bodies, apparatuses, connectivity) = st (; indexed, numbered) = connectivity @@ -899,6 +900,54 @@ function generalized_force_jacobian!(∂F∂s, cluster_cache, st) end end +function generalized_force_jacobian!(∂F∂s, appar::Apparatus{<:ClusterJoint}, st::AbstractStructure,q,q̇,t,s) + (; indexed) = st.connectivity + (; apparid2sys_free_coords_idx, apparid2sys_add_var_idx) = indexed + (; N, nsegs) = appar.cache + (; segs) = appar.force + + T = get_numbertype(st) + ndim = get_num_of_dims(st) + D = zeros(T, ndim) + appar_free_coords_idx = apparid2sys_free_coords_idx[appar.id] + kc = [seg.force.k for seg in segs] + foreach(segs) do seg + (; free_coords_idx, id) = seg + (; hen, egg) = seg.joint.hen2egg + if id == 1 + cluster_idx = collect(1:2) + elseif id == nsegs + cluster_idx = collect(2nsegs-3:2nsegs-2) + else + cluster_idx = collect(2id-3:2id) + end + num_of_cluster_idx = length(cluster_idx) + num_free_coords_idx = length(free_coords_idx) + seg_free_coords_idx = appar_free_coords_idx[free_coords_idx] + J̌ = zeros(T,ndim,num_free_coords_idx) + lkn = zeros(T, num_of_cluster_idx, ndim) + body_hen = hen.body + body_egg = egg.body + C_hen = body_hen.cache.Cps[hen.pid] + C_egg = body_egg.cache.Cps[egg.pid] + free_idx_hen = body_hen.coords.free_idx + free_idx_egg = body_egg.coords.free_idx + ncoords_hen = length(free_idx_hen) + (; k, c, state) = seg.force + (; direction, tension) = state + if tension == 0 + else + D .= direction + J̌ .= 0 + J̌[:,free_idx_hen] .-= C_hen[:,free_idx_hen] + J̌[:,ncoords_hen.+free_idx_egg] .+= C_egg[:,free_idx_egg] + kN = kc[id] .* N[id, cluster_idx] + @tullio lkn[k, l] = D[l] * kN[k] + ∂F∂s[seg_free_coords_idx, cluster_idx] .-= transpose(lkn * J̌) + end + end +end + function build_Ǩ(st) _,λ = check_static_equilibrium_output_multipliers(st) build_Ǩ(st,λ) diff --git a/src/structures/structure.jl b/src/structures/structure.jl index c19ae4f..0e4229f 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -383,14 +383,15 @@ function make_auxi_jacobian(structure::AbstractStructure,s0) (;indexed,) = connectivity (; apparid2sys_free_coords_idx, - apparid2sys_add_var_idx + apparid2sys_add_var_idx, + num_of_free_coords ) = indexed foreach(apparatuses) do appar appar_add_var_idx = apparid2sys_add_var_idx[appar.id] appar_sys_free_idx = apparid2sys_free_coords_idx[appar.id] auxi_jacobian!( - (@view ∂S∂q̌[appar_add_var_idx,appar_sys_free_idx]), + (@view ∂S∂q̌[appar_add_var_idx,unique(appar_sys_free_idx)]), (@view ∂S∂s[appar_add_var_idx,appar_add_var_idx]), appar,structure, q, @@ -515,6 +516,8 @@ function make_auxi_jacobian(structure::AbstractStructure,s0) # @show maximum(∂ζ∂q) ∂ζ∂s = reduce(blockdiag, A_list) + # @show Tb + # @show ∂ζ∂s ∂S∂q .= 1/2 * coζ*∂ζ∂q ∂S∂s .= 1/2 *coζ*∂ζ∂s + cos̄*I diff --git a/yard/ex1/main1.jl b/yard/ex1/main1.jl index db0f1c5..2ce79dd 100644 --- a/yard/ex1/main1.jl +++ b/yard/ex1/main1.jl @@ -28,7 +28,7 @@ plot_traj!(test; policy = RB.TimePolicy( @eponymtuple( - f = (t) -> [t] + f = (t) -> [0] ) ) diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index f691edf..d7b40a7 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -84,7 +84,7 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 15.0), + tspan=(0.0, 1.0), dt, ftol=1e-7,verbose=true, maxiters=50 From ed3c9daf222aaec6a6ee07c9f367fb6977921f7c Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Tue, 21 May 2024 12:27:26 +0800 Subject: [PATCH 16/20] fix type instability in `generalized_force_jacobian!`, `auxi_jacobian!`, and `assemble_forces!`; --- src/structures/constraints.jl | 3 ++- src/structures/linearization.jl | 12 +++++------- src/structures/mutate.jl | 4 ++-- 3 files changed, 9 insertions(+), 10 deletions(-) diff --git a/src/structures/constraints.jl b/src/structures/constraints.jl index 0bb3a44..e4170bd 100644 --- a/src/structures/constraints.jl +++ b/src/structures/constraints.jl @@ -331,9 +331,9 @@ function auxi_jacobian!(∂S∂q̌,∂S∂s, num_of_free = size(∂S∂q̌, 2) ∂l∂q = zeros(T, nsegs, num_of_free) + J̌ = zeros(T, ndim, num_of_free) foreach(segs) do seg idx = seg.id - J̌ = zeros(T, ndim, num_of_free) (; hen, egg) = seg.joint.hen2egg body_hen = hen.body body_egg = egg.body @@ -344,6 +344,7 @@ function auxi_jacobian!(∂S∂q̌,∂S∂s, mfree_hen = bodyid2sys_free_coords[body_hen.prop.id] mfree_egg = bodyid2sys_free_coords[body_egg.prop.id] (; direction) = seg.force.state + J̌ .= 0 J̌[:, mfree_egg] .+= C_egg[:, free_idx_egg] J̌[:, mfree_hen] .-= C_hen[:, free_idx_hen] ∂l∂q[idx, :] = direction'*J̌ diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 82a8263..4de3cec 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -906,9 +906,6 @@ function generalized_force_jacobian!(∂F∂s, appar::Apparatus{<:ClusterJoint}, (; N, nsegs) = appar.cache (; segs) = appar.force - T = get_numbertype(st) - ndim = get_num_of_dims(st) - D = zeros(T, ndim) appar_free_coords_idx = apparid2sys_free_coords_idx[appar.id] kc = [seg.force.k for seg in segs] foreach(segs) do seg @@ -924,10 +921,12 @@ function generalized_force_jacobian!(∂F∂s, appar::Apparatus{<:ClusterJoint}, num_of_cluster_idx = length(cluster_idx) num_free_coords_idx = length(free_coords_idx) seg_free_coords_idx = appar_free_coords_idx[free_coords_idx] - J̌ = zeros(T,ndim,num_free_coords_idx) - lkn = zeros(T, num_of_cluster_idx, ndim) body_hen = hen.body body_egg = egg.body + T = get_numbertype(body_hen) + ndim = get_num_of_dims(body_hen) + J̌ = zeros(T,ndim,num_free_coords_idx) + lkn = zeros(T, num_of_cluster_idx, ndim) C_hen = body_hen.cache.Cps[hen.pid] C_egg = body_egg.cache.Cps[egg.pid] free_idx_hen = body_hen.coords.free_idx @@ -937,12 +936,11 @@ function generalized_force_jacobian!(∂F∂s, appar::Apparatus{<:ClusterJoint}, (; direction, tension) = state if tension == 0 else - D .= direction J̌ .= 0 J̌[:,free_idx_hen] .-= C_hen[:,free_idx_hen] J̌[:,ncoords_hen.+free_idx_egg] .+= C_egg[:,free_idx_egg] kN = kc[id] .* N[id, cluster_idx] - @tullio lkn[k, l] = D[l] * kN[k] + @tullio lkn[k, l] = direction[l] * kN[k] ∂F∂s[seg_free_coords_idx, cluster_idx] .-= transpose(lkn * J̌) end end diff --git a/src/structures/mutate.jl b/src/structures/mutate.jl index b3446ba..a88d753 100644 --- a/src/structures/mutate.jl +++ b/src/structures/mutate.jl @@ -290,8 +290,8 @@ end $(TYPEDSIGNATURES) """ function assemble_forces!(st::Structure) - (;bodies,state) = st - (;system,members) = state + (;bodies,) = st + (;system,members) = st.state foreach(bodies) do body (;F) = members[body.prop.id] (;state,cache) = body From 535c9b7691278f76f47cdb85f0c697aaca3af15a Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Tue, 21 May 2024 13:54:31 +0800 Subject: [PATCH 17/20] add `contact_gap_and_normal!` for dispatch on `contact_body`; 15s-simulation runs 1:40; --- src/mechanics/contact.jl | 184 ++++++++++++++++++++++----------------- yard/jixiebi/Group2_1.jl | 11 ++- 2 files changed, 111 insertions(+), 84 deletions(-) diff --git a/src/mechanics/contact.jl b/src/mechanics/contact.jl index 3f93309..2be7947 100644 --- a/src/mechanics/contact.jl +++ b/src/mechanics/contact.jl @@ -290,7 +290,7 @@ function contact_gap_and_normal(x::AbstractVector,halvspaces::Vector{<:HalfSpace end function contact_gap_and_normal(x::AbstractVector,contact::RigidSphere,bodies) - (;bid) = contact + (;bid) = contact_body foreach(bodies) do body if body.prop.id == bid radius = body.prop.loci[1].position[1] @@ -302,101 +302,121 @@ function contact_gap_and_normal(x::AbstractVector,contact::RigidSphere,bodies) end end +function contact_gap_and_normal!( + gaps, normals, local_positions, contact_ids, + x::AbstractVector, i, contact_body::RigidSphere, bodies, + ) + (; bid) = contact_body + foreach(bodies) do body + if (body.prop.id == bid) + (;X) = body.state.origin_frame.axes + r = body.state.origin_frame.position + radius = body.prop.loci[1].position[1] + gap = norm(x - r) - radius + normal = (x - r) / norm(x - r) + gaps[i] = gap + normals[i] = normal + contact_ids[i] = i + local_positions[i] = X\(x - r) + end + end +end + +function contact_gap_and_normal!( + gaps, normals, local_positions, contact_ids, + x::AbstractVector, i, contact_body::RigidCylinder, bodies, + ) + (; bid) = contact_body + foreach(bodies) do body + if (body.prop.id == bid) + (;X) = body.state.origin_frame.axes + rc = body.state.origin_frame.position + p = x - rc + p̄ = X\p + px, py, pz = p̄ + radius = body.prop.loci[1].position[1] + halflen = body.prop.loci[1].position[2] + if abs(px) > halflen + gap = 1.0 + normal = SVector(1.0, 0.0, 0.0) + elseif norm(SVector(py, pz)) > radius + gap = 1.0 + normal = SVector(1.0, 0.0, 0.0) + else + gap = norm(SVector(py, pz)) - radius + normal = X*SVector(0.0, py, pz) + end + if gap < 0 + ## @show gap + end + gaps[i] = gap + normals[i] = normal / norm(normal) + contact_ids[i] = i + local_positions[i] = p̄ + end + end +end + +function contact_gap_and_normal!( + gaps, normals, local_positions, contact_ids, + x::AbstractVector, i, contact_body::RigidCube, bodies, + ) + (; bid) = contact_body + foreach(bodies) do body + if (body.prop.id == bid) + (;X) = body.state.origin_frame.axes + rc = body.state.origin_frame.position + p = x - rc + p̄ = X\p + px, py, pz = p̄ + hx, hy, hz= body.prop.loci[1].position + if (abs(px) > hx) || (abs(py) > hy) || (abs(pz) > hz) + gap = 1.0 + normal = SVector(1.0, 0.0, 0.0) + else + normal_vector = [SVector(1.0, 0.0, 0.0), + SVector(-1.0, 0.0, 0.0), + SVector(0.0, 1.0, 0.0), + SVector(0.0, -1.0, 0.0), + SVector(0.0, 0.0, 1.0), + SVector(0.0, 0.0, -1.0)] + gap_vector = [hx-px, px+hx, hy-py, py+hy, hz-pz, pz+hz] + min_idx = argmin(gap_vector) + gap = - gap_vector[min_idx] + normal = X*normal_vector[min_idx] + # @show px, py, pz + # @show gap + end + gaps[i] = gap + normals[i] = normal + contact_ids[i] = i + local_positions[i] = p̄ + end + end +end + function contact_gap_and_normal(x::AbstractVector, contact_bodies::Vector{<:ContactRigid}, bodies) ncb = length(contact_bodies) gaps = zeros(Float64, ncb) normals = Vector{SVector{3,Float64}}(undef, ncb) - local_poss = Vector{SVector{3,Float64}}(undef, ncb) + local_positions = Vector{SVector{3,Float64}}(undef, ncb) contact_ids = Vector{Int}(undef, ncb) - for (i, contact) in enumerate(contact_bodies) - if isa(contact, RigidSphere) - (; bid) = contact - foreach(bodies) do body - if (body.prop.id == bid) - (;X) = body.state.origin_frame.axes - r = body.state.origin_frame.position - radius = body.prop.loci[1].position[1] - gap = norm(x - r) - radius - normal = (x - r) / norm(x - r) - gaps[i] = gap - normals[i] = normal - contact_ids[i] = i - local_poss[i] = inv(X)*(x - r) - end - end - elseif isa(contact, RigidCylinder) - (; bid) = contact - foreach(bodies) do body - if (body.prop.id == bid) - (;X) = body.state.origin_frame.axes - rc = body.state.origin_frame.position - p = x - rc - px, py, pz = inv(X) * p - radius = body.prop.loci[1].position[1] - halflen = body.prop.loci[1].position[2] - if abs(px) > halflen - gap = 1.0 - normal = SVector(1.0, 0.0, 0.0) - elseif norm(SVector(py, pz)) > radius - gap = 1.0 - normal = SVector(1.0, 0.0, 0.0) - else - gap = norm(SVector(py, pz)) - radius - normal = X*SVector(0.0, py, pz) - end - if gap < 0 - @show gap - end - gaps[i] = gap - normals[i] = normal / norm(normal) - contact_ids[i] = i - local_poss[i] = SVector(px, py, pz) - end - end - elseif isa(contact, RigidCube) - (; bid) = contact - foreach(bodies) do body - if (body.prop.id == bid) - (;X) = body.state.origin_frame.axes - rc = body.state.origin_frame.position - p = x - rc - px, py, pz = inv(X) * p - hx, hy, hz= body.prop.loci[1].position - if (abs(px) > hx) || (abs(py) > hy) || (abs(pz) > hz) - gap = 1.0 - normal = SVector(1.0, 0.0, 0.0) - else - normal_vector = [SVector(1.0, 0.0, 0.0), - SVector(-1.0, 0.0, 0.0), - SVector(0.0, 1.0, 0.0), - SVector(0.0, -1.0, 0.0), - SVector(0.0, 0.0, 1.0), - SVector(0.0, 0.0, -1.0)] - gap_vector = [hx-px, px+hx, hy-py, py+hy, hz-pz, pz+hz] - min_idx = argmin(gap_vector) - gap = - gap_vector[min_idx] - normal = X*normal_vector[min_idx] - # @show px, py, pz - # @show gap - end - gaps[i] = gap - normals[i] = normal - contact_ids[i] = i - local_poss[i] = SVector(px, py, pz) - end - end - end + for (i, contact_body) in enumerate(contact_bodies) + contact_gap_and_normal!( + gaps, normals, local_positions, contact_ids, + x, i,contact_body, bodies, + ) end if all(gaps .< 0) icb = argmax(gaps) contact_bodies[icb].pid += 1 - return gaps[icb], normals[icb], contact_ids[icb], local_poss[icb] + return gaps[icb], normals[icb], contact_ids[icb], local_positions[icb] else idx = findall((x) -> x >= 0, gaps) positive_gaps = @view gaps[idx] positive_normals = @view normals[idx] positive_contact_body_ids = @view contact_ids[idx] icb = argmin(positive_gaps) - return positive_gaps[icb], positive_normals[icb], positive_contact_body_ids[icb], local_poss[icb] + return positive_gaps[icb], positive_normals[icb], positive_contact_body_ids[icb], local_positions[icb] end end diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index d7b40a7..9850eda 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -54,7 +54,14 @@ C = zeros(nq,nq) RB.build_tangent_damping_matrix!(K,bot1.structure) @time RB.build_tangent_damping_matrix!(K,bot1.structure) -bot1.structure.connectivity.indexed.apparid2sys_add_var_idx +appars = sort(bot1.structure.apparatuses) +appars[1].force.segs |> eltype |> isconcretetype +(;q,q̇,t,s) = bot1.structure.state.system +RB.generalized_force_jacobian!(K,bot1.structure,q,q̇,t,s) + +RB.contact_gap_and_normal( + zeros(3), rigid_contacts.contact_bodies, bot1.structure.bodies +) fig = plot_traj!(bot1; # atsteps=[3320], @@ -84,7 +91,7 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 1.0), + tspan=(0.0, 15.0), dt, ftol=1e-7,verbose=true, maxiters=50 From 2086767d8321f71bcf05306ca5e8490b644b00e7 Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Tue, 21 May 2024 17:30:31 +0800 Subject: [PATCH 18/20] remove unused `generalized_force_jacobian!`; ready to ditch `Zhong06_CCP_constant_mass_cluster_cables.jl`; 4s-simulations on Win run 25s; --- src/mechanics/dynamics.jl | 28 -------- .../Zhong06_CCP_constant_mass.jl | 2 +- ...hong06_CCP_constant_mass_cluster_cables.jl | 72 ++++++++----------- yard/jixiebi/Group2_1.jl | 4 +- 4 files changed, 33 insertions(+), 73 deletions(-) diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index d116f9e..136908e 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -117,34 +117,6 @@ function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy:: build_tangent_damping_matrix!(∂F∂q̌̇,structure) end -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,policy::AbstractPolicy,q,q̇,t,∂F∂s,cluster_cache,s=nothing) - (;structure,hub) = bot - ∂F∂q̌ .= 0 - ∂F∂q̌̇ .= 0 - ∂F∂s .= 0 - clear_forces!(structure) - lazy_update_bodies!(structure,q,q̇) - update_apparatuses!(structure, s) - generalized_force_jacobian!(∂F∂s, cluster_cache, structure) - generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) - build_tangent_stiffness_matrix!(∂F∂q̌,structure) - build_tangent_damping_matrix!(∂F∂q̌̇,structure) -end - -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,∂F∂s,bot::Robot,policy::AbstractPolicy,q,q̇,t,s::AbstractVector) - (;structure,hub) = bot - ∂F∂q̌ .= 0 - ∂F∂q̌̇ .= 0 - ∂F∂s .= 0 - # clear_forces!(structure) - # lazy_update_bodies!(structure,q,q̇) - # update_apparatuses!(structure) - generalized_force_jacobian!(∂F∂s, structure, q, q̇, t, s) - generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) - build_tangent_stiffness_matrix!(∂F∂q̌,structure) - build_tangent_damping_matrix!(∂F∂q̌̇,structure) -end - function generalized_force_jacobian!(∂F∂s,structure::AbstractStructure,q,q̇,t,s) (;apparatuses,connectivity) = structure (; diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl index 00dd2c3..dbe6f00 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl @@ -192,7 +192,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cache; λ0 = traj.λ[begin] s0 = traj.s[begin] q̇0 = traj.q̇[begin] - activate_contacts!(structure,env,solver_cache,q0) + activate_frictional_contacts!(structure,env,solver_cache,q0) invM = inv(M) pₖ₋₁ = M*q̇0 pₖ = zero(pₖ₋₁) diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl index 44b1d2e..e595b5b 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl @@ -28,8 +28,7 @@ function generate_cache( solver.options, ) F!(F,q,q̇,t,s) = generalized_force!(F,bot,policy,q,q̇,t,s;gravity=options.gravity) - # Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, q,q̇,t, cluster_cache) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, bot,policy, q,q̇,t, ∂F∂s, cluster_cache) - Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, q,q̇,t,s) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, ∂F∂s, bot,policy, q,q̇,t, s) + Jac_F!(∂F∂q, ∂F∂q̇,∂F∂s, q,q̇,t,s) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, bot,policy, q,q̇,t, ∂F∂s, s) M = Matrix(assemble_M(structure)) Φ = make_cstr_function(bot) @@ -70,60 +69,58 @@ function make_step_k( structure, solver_cache::Zhong06_CCP_Constant_Mass_Cluster_Cables_Cache, nq,nλ,ns,na, - qₖ₋₁,sₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁, + qₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁,sₖ₋₁, pₖ,vₖ, invM, h,mass_norm) (;F!,Jac_F!,M,Φ,A,∂Aᵀλ∂q) = solver_cache.cache - nx = nq+nλ+ns nΛ = 3na + nx = nq+nλ+ns + - S = make_auxi_function(structure,sₖ₋₁) - Jac_S! = make_auxi_jacobian(structure,sₖ₋₁) + S = make_auxi_function(structure,deepcopy(sₖ₋₁)) + Jac_S! = make_auxi_jacobian(structure,deepcopy(sₖ₋₁)) function ns_stepk!( 𝐫𝐞𝐬,𝐉, - Fₘ,∂F∂q,∂F∂q̇, - ∂F∂s, ∂S∂q, ∂S∂s, + Fₘ,∂F∂q,∂F∂q̇,∂F∂s,∂S∂q,∂S∂s, 𝐁,𝐛,𝐜ᵀ,𝐲, x,Λₖ, - structure, contact_cache, - # cluster_cache, timestep,iteration,doin=true ) - qₖ = @view x[ 1:nq] + # @show timestep, iteration, na + qₖ = @view x[ 1:nq] λₘ = @view x[nq+1:nq+nλ] sₖ = @view x[nq+nλ+1:nx] qₘ = (qₖ.+qₖ₋₁)./2 - sₘ = (sₖ.+sₖ₋₁)./2 q̇ₘ = (qₖ.-qₖ₋₁)./h + sₘ = (sₖ .+ sₖ₋₁)./2 vₘ = q̇ₘ tₘ = tₖ₋₁+h/2 - F!(Fₘ,qₘ,q̇ₘ,tₘ,sₘ,) - # Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, qₘ,q̇ₘ,tₘ, cluster_cache) - Jac_F!(∂F∂q, ∂F∂q̇, ∂F∂s, qₘ,q̇ₘ,tₘ, sₖ) - # Jac_S!(∂S∂q, ∂S∂s, qₖ, sₖ, cluster_cache) - Jac_S!(∂S∂q, ∂S∂s, qₖ, sₖ) + F!(Fₘ,qₘ,q̇ₘ,tₘ,sₘ) + Jac_F!(∂F∂q,∂F∂q̇,∂F∂s,qₘ,q̇ₘ,tₘ,sₘ) + Jac_S!(∂S∂q,∂S∂s,qₖ,sₖ) Aₖ₋₁ = A(qₖ₋₁) Aᵀₖ₋₁ = transpose(Aₖ₋₁) Aₖ = A(qₖ) 𝐫𝐞𝐬[ 1:nq ] .= M*(qₖ.-qₖ₋₁) .- h.*pₖ₋₁ .- - (h^2)/2 .*Fₘ .+ + (h^2)/2 .*Fₘ .- mass_norm.*Aᵀₖ₋₁*λₘ - 𝐫𝐞𝐬[nq+1:nq+nλ] .= mass_norm.*Φ(qₖ) + 𝐫𝐞𝐬[nq+1:nq+nλ] .= -mass_norm.*Φ(qₖ) 𝐫𝐞𝐬[nq+nλ+1:nx] .= S(qₖ,sₖ) 𝐉 .= 0.0 - 𝐉[ 1:nq , 1:nq ] .= M.-(h^2)/2 .*(1/2 .*∂F∂q.+1/h.*∂F∂q̇) - 𝐉[ 1:nq , nq+1:nq+nλ] .= mass_norm.*transpose(Aₖ₋₁) - 𝐉[ 1:nq ,nq+nλ+1:nx] .= - (h^2)/2 * 1/2 .*∂F∂s - 𝐉[nq+1:nq+nλ, 1:nq] .= mass_norm.*Aₖ + 𝐉[ 1:nq, 1:nq] .= M .-h^2/2 .*(1/2 .*∂F∂q .+ 1/h.*∂F∂q̇) + 𝐉[ 1:nq,nq+1:nq+nλ] .= -mass_norm.*transpose(Aₖ₋₁) + 𝐉[ 1:nq, nq+nλ+1:nx] .= -(h^2)/2 .*(1/2 .*∂F∂s) + + 𝐉[nq+1:nq+nλ, 1:nq] .= -mass_norm.*Aₖ - 𝐉[nq+nλ+1:nx,1:nq] .= ∂S∂q# 1/2 * coζ*∂ζ∂q - 𝐉[nq+nλ+1:nx,nq+nλ+1:nx] .= ∂S∂s# 1/2 *coζ*∂ζ∂s + cos̄*I + 𝐉[nq+nλ+1:nx,1:nq] .= ∂S∂q + 𝐉[nq+nλ+1:nx,nq+nλ+1:nx] .= ∂S∂s lu𝐉 = lu(𝐉) @@ -162,9 +159,9 @@ function make_step_k( 𝐛[is+1:is+3] .= [v́ₜⁱ,0,0] Dⁱₘ = @view Dₘ[is+1:is+3,:] Dⁱₖ = @view Dₖ[is+1:is+3,:] - 𝐜ᵀ[is+1 , 1:nq] .= 1/(norm(v́⁺[is+2:is+3])+1e-14)*(v́⁺[is+2]*∂v́⁺∂qₖ[is+2,:] .+ v́⁺[is+3]*∂v́⁺∂qₖ[is+3,:]) - 𝐜ᵀ[is+1:is+3, 1:nq] .+= ∂v́⁺∂qₖ[is+1:is+3,:] - 𝐜ᵀ[is+1:is+3,nq+1:nq+nλ] .= Dⁱₖ*∂vₖ∂λₘ + 𝐜ᵀ[is+1 , 1:nq ] .= 1/(norm(v́⁺[is+2:is+3])+1e-14)*(v́⁺[is+2]*∂v́⁺∂qₖ[is+2,:] .+ v́⁺[is+3]*∂v́⁺∂qₖ[is+3,:]) + 𝐜ᵀ[is+1:is+3, 1:nq ] .+= ∂v́⁺∂qₖ[is+1:is+3,:] + 𝐜ᵀ[is+1:is+3,nq+1:nq+nλ] .= Dⁱₖ*∂vₖ∂λₘ end # 𝐜ᵀinv𝐉 = 𝐜ᵀ*inv(𝐉) 𝐲 .= (v́⁺ + 𝐛) @@ -201,9 +198,9 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C F = zeros(T,nq) ∂F∂q = zeros(T,nq,nq) ∂F∂q̇ = zeros(T,nq,nq) + ∂F∂s = zeros(T,nq,ns) ∂S∂q = zeros(T,ns,nq) - ∂S∂s = zeros(T,ns,ns) - ∂F∂s = zeros(T, nq, ns) + ∂S∂s = zeros(T,ns,ns) nx = nq + nλ + ns Δx = zeros(T,nx) x = zero(Δx) @@ -215,12 +212,9 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C Jac_α1 = zeros(T,nx,nx) Res_α2 = zero(Δx) Jac_α2 = zeros(T,nx,nx) - s_bak = deepcopy(s0) - s_temp = deepcopy(s0) mr = norm(M,Inf) mass_norm = mr α0 = 1.0 - # cluster_cache = init_cluster_matrix(structure) iteration = 0 prog = Progress(totalstep; dt=1.0, enabled=progress) @@ -231,7 +225,6 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C cₖ₋₁ = contacts_traj[timestep] cₖ = contacts_traj[timestep+1] qₖ₋₁ = traj.q[timestep] - sₖ₋₁ = traj.s[timestep] q̇ₖ₋₁ = traj.q̇[timestep] sₖ₋₁ = traj.s[timestep] # λₖ₋₁ = traj.λ[timestep] @@ -265,7 +258,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C structure, solver_cache, nq,nλ,ns,na, - qₖ₋₁,sₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁, + qₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁,sₖ₋₁, pₖ,q̇ₖ, invM, dt,mass_norm @@ -283,12 +276,10 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C luJac = ns_stepk!( Res,Jac, F,∂F∂q,∂F∂q̇, - ∂F∂s, ∂S∂q, ∂S∂s, + ∂F∂s,∂S∂q,∂S∂s, 𝐁,𝐛,𝐜ᵀ,𝐲, x,Λʳₖ, - structure, contact_cache, - # cluster_cache, timestep,iteration ) # if (tₖ₋₁ == 0.096) & (iteration == 1) @@ -342,13 +333,10 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_C Δx .= luJac\minusResΛ ns_stepk!( Res_α0,Jac_α0, - F,∂F∂q,∂F∂q̇, - ∂F∂s, ∂S∂q, ∂S∂s, + F,∂F∂q,∂F∂q̇,∂F∂s,∂S∂q,∂S∂s, 𝐁t,𝐛,𝐜ᵀ,𝐲, x.+Δx,Λʳₖ.+ΔΛₖ, - structure, contact_cache, - # cluster_cache, timestep,iteration,false ) ϕα0 = (transpose(Res_α0)*sd*Res_α0)/2 diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 9850eda..7b3f74e 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -71,6 +71,7 @@ fig = plot_traj!(bot1; # doslide = false, ) +BLAS.set_num_threads(1) RB.solve!( RB.DynamicsProblem( bot1,policy, @@ -91,12 +92,11 @@ RB.solve!( RB.SmoothedFischerBurmeister() ), ); - tspan=(0.0, 15.0), + tspan=(0.0, 4.0), dt, ftol=1e-7,verbose=true, maxiters=50 ) - tw = 468 fontsize = 10 GM.activate!(scalefactor=4.0) From 5d8a997024dd504c3b5e468c98f34593b7cfec8b Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Tue, 21 May 2024 18:55:52 +0800 Subject: [PATCH 19/20] remove files: `Zhong06_CCP_constant_mass_cluster_cables.jl`; `Zhong06_constant_mass_cluster_cables.jl`; `Zhong06_sliding_cable_FB.jl`; 4s-simulations on Win runs 27s; --- ...hong06_CCP_constant_mass_cluster_cables.jl | 396 ------------------ .../Zhong06_constant_mass_cluster_cables.jl | 221 ---------- .../Zhong06_sliding_cable_FB.jl | 234 ----------- src/mechanics/solvers.jl | 2 - 4 files changed, 853 deletions(-) delete mode 100644 src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl delete mode 100644 src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl delete mode 100644 src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_sliding_cable_FB.jl diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl deleted file mode 100644 index e595b5b..0000000 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl +++ /dev/null @@ -1,396 +0,0 @@ -struct Zhong06_CCP_Constant_Mass_Cluster_Cables_Cache{solT, cacheType} - solver::solT - cache::cacheType -end - -function generate_cache( - simulator::Simulator{<:DynamicsProblem{ - RobotType, - policyType, - EnvType, - RestitutionFrictionCombined{NewtonRestitution,CoulombFriction}, - EulerEytelwein, - }}, - solver::DynamicsSolver{ - Zhong06, - <:InnerLayerContactSolver, - <:MonolithicApparatusSolver{SmoothedFischerBurmeister} - }, - ::Val{true}; - dt,kargs... - ) where {RobotType,policyType,EnvType} - (;prob) = simulator - (;bot,policy,env) = prob - (;structure) = bot - options = merge( - (gravity=has_gravity(env),factor=1,checkpersist=true), #default - prob.options, - solver.options, - ) - F!(F,q,q̇,t,s) = generalized_force!(F,bot,policy,q,q̇,t,s;gravity=options.gravity) - Jac_F!(∂F∂q, ∂F∂q̇,∂F∂s, q,q̇,t,s) = generalized_force_jacobian!(∂F∂q, ∂F∂q̇, bot,policy, q,q̇,t, ∂F∂s, s) - - M = Matrix(assemble_M(structure)) - Φ = make_cstr_function(bot) - A = make_cstr_jacobian(bot) - - nq = size(M,2) - T = get_numbertype(bot) - Ψ(q,q̇) = Vector{T}() - ∂Ψ∂q(q,q̇) = Matrix{T}(undef,0,nq) - B(q) = Matrix{T}(undef,0,nq) - - # ∂𝐌𝐚∂𝐪(q,a) = zeros(T,nq,nq) - ∂Aᵀλ∂q(q::AbstractVector,λ) = cstr_forces_jacobian(structure,q,λ) - # ∂𝚽𝐪𝐯∂𝒒(q,v) = RB.∂Aq̇∂q(structure,v) - ∂Bᵀμ∂q(q,μ) = zeros(T,nq,nq) - (; - contacts_bits, - persistent_bits, - μs_sys, - es_sys, - gaps_sys - ) = prepare_contacts(bot,env) - - cache = @eponymtuple( - F!,Jac_F!, - M,Φ,A,Ψ,B,∂Ψ∂q,∂Aᵀλ∂q,∂Bᵀμ∂q, - contacts_bits, - persistent_bits, - μs_sys, - es_sys, - gaps_sys, - options, - ) - Zhong06_CCP_Constant_Mass_Cluster_Cables_Cache(solver, cache) -end - -function make_step_k( - structure, - solver_cache::Zhong06_CCP_Constant_Mass_Cluster_Cables_Cache, - nq,nλ,ns,na, - qₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁,sₖ₋₁, - pₖ,vₖ, - invM, - h,mass_norm) - (;F!,Jac_F!,M,Φ,A,∂Aᵀλ∂q) = solver_cache.cache - - nΛ = 3na - nx = nq+nλ+ns - - - S = make_auxi_function(structure,deepcopy(sₖ₋₁)) - Jac_S! = make_auxi_jacobian(structure,deepcopy(sₖ₋₁)) - function ns_stepk!( - 𝐫𝐞𝐬,𝐉, - Fₘ,∂F∂q,∂F∂q̇,∂F∂s,∂S∂q,∂S∂s, - 𝐁,𝐛,𝐜ᵀ,𝐲, - x,Λₖ, - contact_cache, - timestep,iteration,doin=true - ) - # @show timestep, iteration, na - qₖ = @view x[ 1:nq] - λₘ = @view x[nq+1:nq+nλ] - sₖ = @view x[nq+nλ+1:nx] - qₘ = (qₖ.+qₖ₋₁)./2 - q̇ₘ = (qₖ.-qₖ₋₁)./h - sₘ = (sₖ .+ sₖ₋₁)./2 - vₘ = q̇ₘ - tₘ = tₖ₋₁+h/2 - F!(Fₘ,qₘ,q̇ₘ,tₘ,sₘ) - Jac_F!(∂F∂q,∂F∂q̇,∂F∂s,qₘ,q̇ₘ,tₘ,sₘ) - Jac_S!(∂S∂q,∂S∂s,qₖ,sₖ) - Aₖ₋₁ = A(qₖ₋₁) - Aᵀₖ₋₁ = transpose(Aₖ₋₁) - Aₖ = A(qₖ) - - 𝐫𝐞𝐬[ 1:nq ] .= M*(qₖ.-qₖ₋₁) .- - h.*pₖ₋₁ .- - (h^2)/2 .*Fₘ .- - mass_norm.*Aᵀₖ₋₁*λₘ - 𝐫𝐞𝐬[nq+1:nq+nλ] .= -mass_norm.*Φ(qₖ) - 𝐫𝐞𝐬[nq+nλ+1:nx] .= S(qₖ,sₖ) - - 𝐉 .= 0.0 - 𝐉[ 1:nq, 1:nq] .= M .-h^2/2 .*(1/2 .*∂F∂q .+ 1/h.*∂F∂q̇) - 𝐉[ 1:nq,nq+1:nq+nλ] .= -mass_norm.*transpose(Aₖ₋₁) - 𝐉[ 1:nq, nq+nλ+1:nx] .= -(h^2)/2 .*(1/2 .*∂F∂s) - - 𝐉[nq+1:nq+nλ, 1:nq] .= -mass_norm.*Aₖ - - 𝐉[nq+nλ+1:nx,1:nq] .= ∂S∂q - 𝐉[nq+nλ+1:nx,nq+nλ+1:nx] .= ∂S∂s - - lu𝐉 = lu(𝐉) - - if (na != 0) - (; - H, - restitution_coefficients, - D, - ) = contact_cache.cache - Dₘ = contact_cache.cache.Dper - Dₖ = contact_cache.cache.Dimp - 𝐁 .= 0 - 𝐁[ 1:nq,1:nΛ] .= h.*mass_norm.*transpose(D)*H - 𝐫𝐞𝐬 .-= 𝐁*Λₖ - - if doin - pₖ .= Momentum_k(qₖ₋₁,pₖ₋₁,qₖ,λₘ,M,A,mass_norm,h) - vₖ .= invM*pₖ - ∂vₘ∂qₖ = 1/h*I - ∂vₖ∂qₖ = 2/h*I + mass_norm/(h).*invM*(∂Aᵀλ∂q(qₖ,λₘ)) - ∂vₖ∂λₘ = mass_norm.*invM*transpose(Aₖ-Aₖ₋₁)/(h) - - v́⁺ = Dₘ*vₘ .+ Dₖ*vₖ - ∂v́⁺∂qₖ = Dₘ*∂vₘ∂qₖ .+ Dₖ*∂vₖ∂qₖ - 𝐜ᵀ .= 0 - v́ₖ₋₁ = Dₖ*vₖ₋₁ - for i = 1:na - is = 3(i-1) - vⁱₖ₋₁ = @view v́ₖ₋₁[is+1:is+3] - vⁱ⁺ = @view v́⁺[is+1:is+3] - vₜⁱₖ₋₁ = norm(vⁱₖ₋₁[2:3]) - vₜⁱ⁺ = norm(vⁱ⁺[2:3]) - vₙⁱₖ₋₁ = vⁱₖ₋₁[1] - vₙⁱ = vⁱ⁺[1] - v́ₜⁱ = vₜⁱ⁺ + restitution_coefficients[i]*min(vₙⁱₖ₋₁,0) - 𝐛[is+1:is+3] .= [v́ₜⁱ,0,0] - Dⁱₘ = @view Dₘ[is+1:is+3,:] - Dⁱₖ = @view Dₖ[is+1:is+3,:] - 𝐜ᵀ[is+1 , 1:nq ] .= 1/(norm(v́⁺[is+2:is+3])+1e-14)*(v́⁺[is+2]*∂v́⁺∂qₖ[is+2,:] .+ v́⁺[is+3]*∂v́⁺∂qₖ[is+3,:]) - 𝐜ᵀ[is+1:is+3, 1:nq ] .+= ∂v́⁺∂qₖ[is+1:is+3,:] - 𝐜ᵀ[is+1:is+3,nq+1:nq+nλ] .= Dⁱₖ*∂vₖ∂λₘ - end - # 𝐜ᵀinv𝐉 = 𝐜ᵀ*inv(𝐉) - 𝐲 .= (v́⁺ + 𝐛) - end - end - lu𝐉 - end - ns_stepk! -end - -function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Cluster_Cables_Cache; - dt, - ftol=1e-14,xtol=ftol, - verbose=false,verbose_contact=false, - maxiters=50, - max_restart=3, - progress=true,exception=true) - (;prob,controller,tspan,restart,totalstep) = sim - (;bot,env) = prob - (;structure,traj,contacts_traj) = bot - (;M,A,contacts_bits,options) = solver_cache.cache - q0 = traj.q[begin] - λ0 = traj.λ[begin] - s0 = traj.s[begin] - q̇0 = traj.q̇[begin] - activate_frictional_contacts!(structure,env,solver_cache,q0) - invM = inv(M) - pₖ₋₁ = M*q̇0 - pₖ = zero(pₖ₋₁) - T = eltype(q0) - nq = length(q0) - nλ = length(λ0) - ns = length(s0) - F = zeros(T,nq) - ∂F∂q = zeros(T,nq,nq) - ∂F∂q̇ = zeros(T,nq,nq) - ∂F∂s = zeros(T,nq,ns) - ∂S∂q = zeros(T,ns,nq) - ∂S∂s = zeros(T,ns,ns) - nx = nq + nλ + ns - Δx = zeros(T,nx) - x = zero(Δx) - Res = zero(Δx) - Jac = zeros(T,nx,nx) - Res_α0 = zero(Δx) - Jac_α0 = zeros(T,nx,nx) - Res_α1 = zero(Δx) - Jac_α1 = zeros(T,nx,nx) - Res_α2 = zero(Δx) - Jac_α2 = zeros(T,nx,nx) - mr = norm(M,Inf) - mass_norm = mr - α0 = 1.0 - - iteration = 0 - prog = Progress(totalstep; dt=1.0, enabled=progress) - for timestep = 1:totalstep - #---------Time Step k Control----------- - # control!(sim,cache) - #---------Time Step k Control----------- - cₖ₋₁ = contacts_traj[timestep] - cₖ = contacts_traj[timestep+1] - qₖ₋₁ = traj.q[timestep] - q̇ₖ₋₁ = traj.q̇[timestep] - sₖ₋₁ = traj.s[timestep] - # λₖ₋₁ = traj.λ[timestep] - tₖ₋₁ = traj.t[timestep] - qₖ = traj.q[timestep+1] - q̇ₖ = traj.q̇[timestep+1] - sₖ = traj.s[timestep+1] - λₘ = traj.λ[timestep+1] - pₖ₋₁ = M*q̇ₖ₋₁ - qˣ = qₖ₋₁ .+ dt./2 .*q̇ₖ₋₁ - qₖ .= qₖ₋₁ .+ dt .*q̇ₖ₋₁ - q̇ₖ .= q̇ₖ₋₁ - contact_cache = activate_frictional_contacts!(structure,env,solver_cache,qˣ;checkpersist=options.checkpersist) - (;na,L) = contact_cache.cache - isconverged = false - normRes = typemax(T) - iteration_break = 0 - isconverged = false - nΛ = 3na - Λₖ = zeros(T,nΛ) - Λʳₖ = copy(Λₖ) - ΔΛₖ = copy(Λₖ) - 𝐁 = zeros(T,nx,nΛ) - 𝐁t = zeros(T,nx,nΛ) - 𝐛 = zeros(T,nΛ) - 𝐜ᵀ = zeros(T,nΛ,nx) - 𝐍 = zeros(T,nΛ,nΛ) - 𝐲 = zeros(T,nΛ) - get_frictional_directions_and_positions!(structure, contact_cache, qₖ₋₁, q̇ₖ₋₁, Λₖ) - ns_stepk! = make_step_k( - structure, - solver_cache, - nq,nλ,ns,na, - qₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁,sₖ₋₁, - pₖ,q̇ₖ, - invM, - dt,mass_norm - ) - restart_count = 0 - Λ_guess = 0.1 - while restart_count < max_restart - Λₖ .= repeat([Λ_guess,0,0],na) - x[ 1:nq] .= qₖ - x[ nq+1:nq+nλ] .= 0.0 - x[nq+nλ+1:nx] .= sₖ₋₁ - Λʳₖ .= Λₖ - Nmax = maxiters - for iteration = 1:maxiters - luJac = ns_stepk!( - Res,Jac, - F,∂F∂q,∂F∂q̇, - ∂F∂s,∂S∂q,∂S∂s, - 𝐁,𝐛,𝐜ᵀ,𝐲, - x,Λʳₖ, - contact_cache, - timestep,iteration - ) - # if (tₖ₋₁ == 0.096) & (iteration == 1) - # @show size(Jac) - # write("jac1.bin", Jac) - # end - if na == 0 - normRes = norm(Res) - if normRes < ftol - isconverged = true - iteration_break = iteration-1 - break - end - Δx .= luJac\(-Res) - x .+= Δx - else # na!=0 - normRes = norm(Res) - if normRes < ftol - isconverged = true - iteration_break = iteration-1 - break - elseif normRes > 1e10 - # force restart - iteration_break = iteration-1 - isconverged = false - break - elseif iteration == maxiters - iteration_break = iteration-1 - isconverged = false - end - get_distribution_law!(structure,contact_cache,x[1:nq]) - sd = 1/norm(Res)^2*I - ϕ0 = 0.5 - dϕ0 = -1.0 - c1 = 0.2 - α0 = 2.0 - 𝐍 .= 𝐜ᵀ*(luJac\𝐁) - for line_search_step = 1:5 - α0 /= 2 - 𝐡 = 𝐲 .-𝐜ᵀ*(luJac\(Res + (1/α0) .*𝐁*Λʳₖ)) - yₖini = 1/α0 .*𝐍*Λʳₖ + 𝐡 - Λₖini = deepcopy(Λʳₖ) - Λₖini[begin+1:3:end] .= 0.0 - Λₖini[begin+2:3:end] .= 0.0 - yₖini .= abs.(yₖini) - yₖini[begin+1:3:end] .= 0.0 - yₖini[begin+2:3:end] .= 0.0 - IPM!(Λₖ,na,nΛ,Λₖini,yₖini,(1/α0).*𝐍 .+ L,𝐡;ftol,Nmax) - ΔΛₖ .= (Λₖ - Λʳₖ) - minusResΛ = -Res + 𝐁*((1/α0).*ΔΛₖ) - Δx .= luJac\minusResΛ - ns_stepk!( - Res_α0,Jac_α0, - F,∂F∂q,∂F∂q̇,∂F∂s,∂S∂q,∂S∂s, - 𝐁t,𝐛,𝐜ᵀ,𝐲, - x.+Δx,Λʳₖ.+ΔΛₖ, - contact_cache, - timestep,iteration,false - ) - ϕα0 = (transpose(Res_α0)*sd*Res_α0)/2 - if ϕα0 <= ϕ0 + c1*α0*dϕ0 - break - end - end - Λₖ .= Λʳₖ .+ ΔΛₖ - Λʳₖ .= Λₖ - x .+= Δx - end - end - if isconverged - break - end - restart_count += 1 - if na > 0 - Λ_guess = max(Λ_guess/10,maximum(abs.(Λₖ[begin:3:end]))) - end - end - qₖ .= x[ 1:nq] - λₘ .= x[ nq+1:nq+nλ] - sₖ .= x[nq+nλ+1:nx] - pₖ .= Momentum_k(qₖ₋₁,pₖ₋₁,qₖ,λₘ,M,A,mass_norm,dt) - q̇ₖ .= invM*pₖ - Dₘ = contact_cache.cache.Dper - Dₖ = contact_cache.cache.Dimp - if na != 0 - update_contacts!(cₖ[contacts_bits],cₖ₋₁[contacts_bits],Dₘ*(qₖ.-qₖ₋₁).+Dₖ*q̇ₖ,2*Λₖ./(mass_norm*dt)) - end - - if !isconverged - @warn "Newton max iterations $maxiters, at timestep=$timestep, normRes=$(normRes), restart_count=$(restart_count), num_active_contacts=$(na), α0=$(α0)" - if exception - @error "Not converged!" - break - else - # sim.convergence = false - # break - end - end - - #---------Time Step k finisher----------- - if verbose || (na > 0 && verbose_contact) - dg_step = ceil(Int,log10(totalstep))+1 - dg_dt = max(1,-floor(Int,log10(dt))) - wd_t = ceil(Int,log10(traj.t[end]))+dg_dt+1+1 - progfmt = Printf.Format("Prog.: %5.1f%%, step: %$(dg_step)u, time: %$(wd_t).$(dg_dt)f, iters: %s, contacts: %s \n") - progstr = Printf.format(progfmt, - floor(timestep/totalstep*100;digits=1), timestep, traj.t[timestep], iteration_break, na - ) - print(progstr) - end - next!(prog) - end - bot -end diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl deleted file mode 100644 index 5367c6b..0000000 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl +++ /dev/null @@ -1,221 +0,0 @@ -struct Zhong06_Constant_Mass_Cluster_Cables_Cache{solT,cacheType} - solver::solT - cache::cacheType -end - -function generate_cache( - simulator::Simulator{<:AbstractDynamicsProblem}, - solver::DynamicsSolver{Zhong06,Nothing,MonolithicApparatusSolver{SmoothedFischerBurmeister}}, - ::Val{true}; - dt,kargs... - ) - (;prob) = simulator - (;bot,policy) = prob - (;traj,structure) = bot - options = merge( - (gravity=false,factor=1,checkpersist=true), #default - prob.options, - solver.options, - ) - @show "Yes" - (;M,M⁻¹,M̌,M̌⁻¹,Ḿ,M̄)= build_mass_matrices(structure) - A = make_cstr_jacobian(structure) - Φ = make_cstr_function(structure) - ψ = make_auxi_function_cluster(structure) - F!(F,q,s,q̇,t) = generalized_force!(F,bot,policy,q,q̇,t,s;gravity=options.gravity) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t) - q̌0 = traj.q̌[begin] - λ0 = traj.λ[begin] - q̇0 = traj.q̇[begin] - q̇0 = traj.q̇[begin] - p̌0 = traj.p̌[begin] .= Ḿ*q̇0 - s0 = traj.s[begin] - T = eltype(q̌0) - nq̌ = length(q̌0) - nλ = length(λ0) - ns = length(s0) - ∂F∂q̌ = zeros(T,nq̌,nq̌) - ∂F∂q̌̇ = zeros(T,nq̌,nq̌) - nx = nq̌ + nλ + ns - xₖ = vcat(q̌0,λ0,s0) - Res = zero(xₖ) - Jac = Res*transpose(Res) - Zhong06_Constant_Mass_Cluster_Cables_Cache( - solver, - @eponymtuple( - F!,Jac_F!, - Ḿ,M̌,M̄,M̌⁻¹,A,Φ,ψ, - ∂F∂q̌,∂F∂q̌̇, - nq̌,nλ,nx, - xₖ, - Res, - Jac, - options - ) - ) -end - -function retrieve!(sim,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache) - -end - -function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cluster_Cables_Cache; - dt,ftol=1e-14,verbose=false,maxiters=50, - progress=true,exception=true) - (;prob,controller,tspan,restart,totalstep) = sim - (;bot,) = prob - (;traj) = bot - (; - F!,Jac_F!, - Ḿ,M̌,M̄,M̌⁻¹,A,Φ,ψ, - ∂F∂q̌,∂F∂q̌̇, - nq̌,nλ,nx, - xₖ, - Res, - Jac - ) = cache.cache - mr = norm(Ḿ,Inf) - mass_norm = mr - h = dt - T = get_numbertype(bot) - function make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ,qₖ₋₁,sₖ₋₁, p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) - @inline @inbounds function inner_Res_stepk!(Res,x) - q̌ₖ .= x[ 1:nq̌ ] - λₖ .= x[nq̌+1:nq̌+nλ] - sₖ .= x[nq̌+nλ+1:nx] - qₘ = (qₖ.+qₖ₋₁)./2 - sₘ = (sₖ.+sₖ₋₁)./2 - q̇ₘ = (qₖ.-qₖ₋₁)./h - tₘ = tₖ₋₁+h/2 - F!(F̌,qₘ, sₘ, q̇ₘ, tₘ) - Res[ 1:nq̌ ] .= Ḿ*(qₖ.-qₖ₋₁) .- - h.*p̌ₖ₋₁ .- - (h^2)/2 .*F̌ .+ - mass_norm.*Aᵀₖ₋₁*λₖ - Res[nq̌+1:nq̌+nλ] .= mass_norm.*Φ(qₖ) - Res[nq̌+nλ+1:nx] .= ψ(sₖ) - end - end - - function Jac_stepk!(Jac,x,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁, ∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) - q̌ₖ .= x[1:nq̌] - sₖ .= x[nq̌+nλ+1:end] - qₘ = (qₖ.+qₖ₋₁)./2 - q̇ₘ = (qₖ.-qₖ₋₁)./h - tₘ = tₖ₋₁+h/2 - sₘ = (sₖ.+sₖ₋₁)./2 - Jac_F!(∂F∂q̌,∂F∂q̌̇,qₘ,q̇ₘ,tₘ) - ζ = build_ζ(bot.structure) - ∂ζ∂q = build_∂ζ∂q(bot.structure) - ∂ζ∂s = build_∂ζ∂s̄(bot.structure) - n = length(ζ) - ∂s̄∂s̄ = I(n) - ∂F∂s̄ = build_∂Q̌∂s̄(bot.structure) - κ₁ = 10; κ₂ = 100 - cosₘ = 1/2 - coqₘ = 1/2 - coes = diagm([((ζ[i]/κ₁)^2 + (κ₂*sₖ[i])^2)^(-1/2) for i in 1:n]) - coζ = coes*diagm([ζ[i]/κ₁^2 for i in 1:n]) - diagm([1/κ₁ for i in 1:n]) - cos̄ = coes*diagm([κ₂^2*sₖ[i] for i in 1:n]) - diagm([κ₂ for i in 1:n]) - - Jac[ 1:nq̌ , 1:nq̌ ] .= M̌.-(h^2)/2 .*(1/2 .*∂F∂q̌.+1/h.*∂F∂q̌̇) - Jac[ 1:nq̌ ,nq̌+1:nq̌+nλ] .= mass_norm.*Aᵀₖ₋₁ - Jac[ 1:nq̌ ,nq̌+nλ+1:end] .= -1/2 * h^2 .* ∂F∂s̄ * cosₘ - - Jac[nq̌+1:nq̌+nλ, 1:nq̌ ] .= mass_norm.*A(qₖ) - Jac[nq̌+1:nq̌+nλ, nq̌+1:nq̌+nλ ] .= 0.0 - Jac[nq̌+1:nq̌+nλ, nq̌+nλ+1:end ] .= 0.0 - - Jac[nq̌+nλ+1:end,1:nq̌] .= coζ*∂ζ∂q*coqₘ - Jac[nq̌+nλ+1:end,nq̌+1:nq̌+nλ] .= 0.0 - Jac[nq̌+nλ+1:end,nq̌+nλ+1:end] .= coζ*∂ζ∂s*cosₘ + cos̄*∂s̄∂s̄ - end - - iteration_break = 0 - prog = Progress(totalstep; dt=1.0, enabled=progress) - dg_step = ceil(Int,log10(totalstep))+1 - dg_dt = max(1,-floor(Int,log10(h))) - wd_t = ceil(Int,log10(traj.t[end]))+dg_dt+1+1 - progfmt = Printf.Format("Progress: %5.1f%%, step: %$(dg_step)u, time: %$(wd_t).$(dg_dt)f, iterations: %s \n") - - for timestep = 1:totalstep - #---------Step k Control----------- - # control!(sim,cache) - #---------Step k Control----------- - tₖ₋₁ = traj.t[timestep] - tₖ = traj.t[timestep+1] - qₖ₋₁ = traj.q[timestep] - sₖ₋₁ = traj.s[timestep] - q̌ₖ₋₁ = traj.q̌[timestep] - q̌̇ₖ₋₁ = traj.q̌̇[timestep] - p̌ₖ₋₁ = traj.p̌[timestep] - qₖ = traj.q[timestep+1] - sₖ = traj.s[timestep+1] - q̌ₖ = traj.q̌[timestep+1] - q̌̇ₖ = traj.q̌̇[timestep+1] - q̃̇ₖ = traj.q̃̇[timestep+1] - λₖ = traj.λ[timestep+1] - p̌ₖ = traj.p̌[timestep+1] - F̌ = traj.F̌[timestep+1] - xₖ[ 1:nq̌] .= q̌ₖ₋₁ .+ h.*q̌̇ₖ₋₁ - xₖ[nq̌+1:nq̌+nλ] .= 0 - xₖ[nq̌+nλ+1:nx] .= sₖ₋₁ - Aᵀₖ₋₁ = transpose(A(qₖ₋₁)) - Res_stepk! = make_Res_stepk(qₖ,q̌ₖ,λₖ,sₖ,qₖ₋₁,sₖ₋₁,p̌ₖ₋₁,F̌,Aᵀₖ₋₁,tₖ₋₁) - isconverged = false - normRes = typemax(T) - if false#Jac_F! isa Missing - dfk = OnceDifferentiable(Res_stepk!,xₖ,Res) - Res_stepk_result = nlsolve(dfk, xₖ; ftol, iterations=maxiters, method=:newton) - isconverged = converged(Res_stepk_result) - iteration_break = Res_stepk_result.iterations - Res_stepk_result.iterations - xₖ .= Res_stepk_result.zero - else - for iteration = 1:maxiters - Res_stepk!(Res,xₖ) - normRes = norm(Res) - if normRes < ftol - isconverged = true - iteration_break = iteration-1 - break - end - # FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) - Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) - xₖ .+= Jac\(-Res) - end - # dfk = OnceDifferentiable(Res_stepk!,Jac_stepk!,xₖ,Res) - end - - if !isconverged - # Res_stepk!(Res,xₖ) - # Jac_stepk!(Jac,xₖ,qₖ,sₖ,q̌ₖ,qₖ₋₁,sₖ₋₁,∂F∂q̌,∂F∂q̌̇,Aᵀₖ₋₁,tₖ₋₁) - # write("j1.bin", Jac) - # FiniteDiff.finite_difference_jacobian!(Jac,Res_stepk!,xₖ,Val{:central}) - # write("j2.bin", Jac) - if exception - error("Not Converged! Step=$timestep, normRes=$normRes") - else - # sim.convergence = false - break - end - end - q̌ₖ .= xₖ[ 1:nq̌ ] - λₖ .= xₖ[nq̌+1:nq̌+nλ] - sₖ .= xₖ[nq̌+nλ+1:nx] - Momentum_k!(p̌ₖ,p̌ₖ₋₁,qₖ,qₖ₋₁,λₖ,Ḿ,A,Aᵀₖ₋₁,mass_norm,h) - q̌̇ₖ .= M̌⁻¹*(p̌ₖ.-M̄*q̃̇ₖ ) - #---------Step k finisher----------- - #---------Step k finisher----------- - if verbose - progstr = Printf.format( - progfmt, - floor(timestep/totalstep*100;digits=1), timestep, tₖ, iteration_break - ) - print(progstr) - end - next!(prog) - end - - bot -end diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_sliding_cable_FB.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_sliding_cable_FB.jl deleted file mode 100644 index c624ed2..0000000 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_sliding_cable_FB.jl +++ /dev/null @@ -1,234 +0,0 @@ - - -struct FBZhong06Cache{MMT, AT, ΦT, ΨT} - mass_matrices::MMT - A::AT - Φ::ΦT - Ψ::ΨT -end - -function generate_cache( - simulator::Simulator{DynamicsProblem{RobotType,Contactless,SlidingTendon}}, - solver::DynamicsSolver{Zhong06}; - dt,kargs... - ) where RobotType - (;prob) = simulator - (;bot,dynfuncs) = prob - # F!,_ = dynfuncs - mm = build_mass_matrices(bot) - # (;M) = mm - A = make_cstr_jacobian(bot) - Φ = make_cstr_function(bot) - Ψ = make_Ψ(bot.structure) - FBZhong06Cache(mm,A,Φ,Ψ) -end - -function solve!(simulator::Simulator,cache::FBZhong06Cache; - dt,ftol=1e-14,verbose=false,iterations=50, - progress=true,exception=true) - (;prob,controller,tspan,restart,totalstep) = simulator - (;bot,dynfuncs) = prob - (;traj) = bot - (;F!,Jac_F!) = dynfuncs - (;actuate!) = controller - (;mass_matrices,A,Φ,Ψ) = cache - (;Ḿ,M̌,M̄,M̌⁻¹) = mass_matrices - q̌0 = traj.q̌[begin] - λ0 = traj.λ[begin] - q̇0 = traj.q̇[begin] - s0 = traj.s[begin] - T = eltype(q̌0) - nq̌ = length(q̌0) - nλ = length(λ0) - ns = length(s0) - ∂F∂q̌ = zeros(T,nq̌,nq̌) - ∂F∂q̌̇ = zeros(T,nq̌,nq̌) - p̌ᵏ⁻¹ = Ḿ*q̇0 - p̌ᵏ = zero(p̌ᵏ⁻¹) - step = 0 - initial_x = vcat(q̌0,λ0,s0) - initial_Res = zero(initial_x) - nx = length(initial_x) - mr = norm(Ḿ,Inf) - scaling = mr - - function make_Res_stepk(qᵏ,q̌ᵏ,λᵏ,sᵏ,qᵏ⁻¹,p̌ᵏ⁻¹,F̌,Aᵀ,tᵏ⁻¹) - @inline @inbounds function inner_Res_stepk!(Res,x) - h = dt - q̌ᵏ .= x[ 1:nq̌ ] - λᵏ .= x[nq̌+1:nq̌+nλ] - sᵏ .= x[nq̌+nλ+1:nx] - F!(F̌,(qᵏ.+qᵏ⁻¹)./2,(qᵏ.-qᵏ⁻¹)./h,sᵏ,tᵏ⁻¹+h/2) - Res[ 1:nq̌ ] .= Ḿ*(qᵏ.-qᵏ⁻¹) .- - h.*p̌ᵏ⁻¹ .- - (h^2)/2 .*F̌ .+ - scaling.*Aᵀ*λᵏ - Res[nq̌+1:nq̌+nλ] .= scaling.*Φ(qᵏ) - # Res[1:nq̌] .-= (h^2)/2 .* F̌ - Res[nq̌+nλ+1:nx] .= Ψ(sᵏ) - end - end - - - - function make_Jac_stepk(qᵏ,q̌ᵏ,sᵏ,qᵏ⁻¹,∂F∂q̌,∂F∂q̌̇,Aᵀ,tᵏ⁻¹) - @inline @inbounds function inner_Jac_stepk!(Jac,x) - h = dt - q̌ᵏ .= x[1:nq̌] - sᵏ .= x[nq̌+nλ+1:nx] - ζ = build_ζ(bot.structure) - ∂ζ∂q = build_∂ζ∂q(bot.structure, q̌ᵏ) - ∂ζ∂s = build_∂ζ∂s̄(bot.structure) - n = length(ζ) - ∂s̄∂s̄ = I(n) - κ₁ = 10; κ₂ = 10 - coes = diagm([((ζ[i]/κ₁)^2 + (κ₂*sᵏ[i])^2)^(-1/2) for i in 1:n]) - coζ = coes*diagm([ζ[i]/κ₁^2 for i in 1:n]) - diagm([1/κ₁ for i in 1:n]) - cos̄ = coes*diagm([κ₂^2*sᵏ[i] for i in 1:n]) - diagm([κ₂ for i in 1:n]) - # Jac_F!(∂F∂q̌,∂F∂q̌̇,(qᵏ.+qᵏ⁻¹)./2,(qᵏ.-qᵏ⁻¹)./h,tᵏ⁻¹+h/2) - ∂Q̌∂q̌̇ = build_tangent_stiffness_matriẋ(bot.structure) - ∂Q̌∂q̌ = build_tangent_stiffness_matrix(bot.structure) - ∂Q̌∂s̄ = build_∂Q̌∂s̄(bot.structure) - Jac[ 1:nq̌ , 1:nq̌ ] .= M̌.-h^2/2 .*(1/2 .*∂Q̌∂q̌.+1/h.*∂Q̌∂q̌̇) - Jac[ 1:nq̌ , nq̌+1:nq̌+nλ ] .= scaling.*Aᵀ - # @show nq̌, length(Jac[1, nq̌+nλ+1:end]) - # @show size(∂Q̌∂s̄) - Jac[ 1:nq̌ , nq̌+nλ+1:end] .= -1/2 * dt^2 .* ∂Q̌∂s̄ - Jac[nq̌+1:nq̌+nλ, 1:nq̌ ] .= scaling.*A(qᵏ) - Jac[nq̌+1:nq̌+nλ,nq̌+1:nq̌+nλ] .= 0.0 - Jac[nq̌+1:nq̌+nλ,nq̌+nλ+1:end] .= 0.0 - Jac[nq̌+nλ+1:end,1:nq̌] .= 1/2 * coζ*∂ζ∂q - Jac[nq̌+nλ+1:end,nq̌+1:nq̌+nλ+1] .= 0.0 - Jac[nq̌+nλ+1:end,nq̌+nλ+1:end] .= coζ *∂ζ∂s + cos̄*∂s̄∂s̄ - end - end - - function test(qᵏ,q̌ᵏ,sᵏ,qᵏ⁻¹,∂F∂q̌,∂F∂q̌̇,Aᵀ,tᵏ⁻¹) - @inline @inbounds function inner_Jac_stepk!(x) - h = dt - q̌ᵏ .= x[1:nq̌] - sᵏ .= x[nq̌+nλ+1:nx] - ζ = build_ζ(bot.structure) - ∂ζ∂q = Record_build_∂ζ∂q(bot.structure, q̌ᵏ,"t1.xlsx","t1") - ∂ζ∂s = build_∂ζ∂s̄(bot.structure) - n = length(ζ) - ∂s̄∂s̄ = I(n) - κ₁ = 10; κ₂ = 10 - coes = diagm([((ζ[i]/κ₁)^2 + (κ₂*sᵏ[i])^2)^(-1/2) for i in 1:n]) - coζ = coes*diagm([ζ[i]/κ₁^2 for i in 1:n]) - diagm([1/κ₁ for i in 1:n]) - cos̄ = coes*diagm([κ₂^2*sᵏ[i] for i in 1:n]) - diagm([κ₂ for i in 1:n]) - # Jac_F!(∂F∂q̌,∂F∂q̌̇,(qᵏ.+qᵏ⁻¹)./2,(qᵏ.-qᵏ⁻¹)./h,tᵏ⁻¹+h/2) - ∂Q̌∂q̌̇ = build_tangent_stiffness_matriẋ(bot.structure) - ∂Q̌∂q̌ = build_tangent_stiffness_matrix(bot.structure) - ∂Q̌∂s̄ = build_∂Q̌∂s̄(bot.structure) - # @show nq̌, length(Jac[1, nq̌+nλ+1:end]) - # @show size(∂Q̌∂s̄) - return coζ, ∂ζ∂q, q̌ᵏ - end - end - - total_iterations = 0 - prog = Progress(totalstep; dt=1.0, enabled=progress) - for timestep = 1:totalstep - #---------Step k Control----------- - # control!(sim,cache) - #---------Step k Control----------- - tᵏ⁻¹ = traj.t[timestep] - tᵏ = traj.t[timestep+1] - qᵏ⁻¹ = traj.q[timestep] - sᵏ⁻¹ = traj.s[timestep] - sᵏ = traj.s[timestep+1] - qᵏ = traj.q[timestep+1] - q̌ᵏ = traj.q̌[timestep+1] - q̌̇ᵏ = traj.q̌̇[timestep+1] - q̃̇ᵏ = traj.q̃̇[timestep+1] - λᵏ = traj.λ[timestep+1] - F̌ = traj.F̌[timestep+1] - initial_x[ 1:nq̌] .= traj.q̌[timestep] - initial_x[nq̌+1:nq̌+nλ] .= traj.λ[timestep] - initial_x[nq̌+nλ+1:nx] .= traj.s[timestep] - initial_x - Aᵀ = transpose(A(qᵏ⁻¹)) - if !(actuate! isa Missing) - actuate!(bot.structure, tᵏ⁻¹; dt) - end - Res_stepk! = make_Res_stepk(qᵏ,q̌ᵏ,λᵏ,sᵏ,qᵏ⁻¹,p̌ᵏ⁻¹,F̌,Aᵀ,tᵏ⁻¹) - if Jac_F! isa Missing - dfk = OnceDifferentiable(Res_stepk!,initial_x,initial_Res) - else - - Jac_stepk! = make_Jac_stepk(qᵏ,q̌ᵏ,sᵏ,qᵏ⁻¹,∂F∂q̌,∂F∂q̌̇,Aᵀ,tᵏ⁻¹) - dfk = OnceDifferentiable(Res_stepk!,Jac_stepk!,initial_x,initial_Res) - end - - # if timestep==totalstep - # nx = length(initial_x) - # output = zeros(nx, nx) - # FiniteDiff.finite_difference_jacobian!(output, Res_stepk!, initial_x) - # J = zeros(Float64, nx, nx) - # J[findall(x->abs(x)<1e-7, J)] .= 0 - # Jac_stepk!(J, initial_x) - # diff = J - output - - # test! = test(qᵏ,q̌ᵏ,sᵏ,qᵏ⁻¹,∂F∂q̌,∂F∂q̌̇,Aᵀ,tᵏ⁻¹) - # global coζ, dζdq, q̌ = test!(initial_x) - # h1,w1 = size(coζ); h2, w2 = size(dζdq) - # w3 = length(q̌) - # XLSX.openxlsx("t1.xlsx", mode="rw") do xf - # s1 = xf["前向差分"] - # s2 = xf["精确值"] - # s3 = xf["两者之差"] - # s4 = xf["Temp"] - # for i in 1:nx - # s1[i, 1:nx] = output[i, :] - # s2[i, 1:nx] = J[i, :] - # s3[i, 1:nx] = diff[i, :] - # end - # for i in 1:h1 - # s4[i, 1:w1] = coζ[i, :] - # end - # for i in h1+1:h1+h2 - # s4[i, 1:w2] = dζdq[i-h1, :] - # end - # for i in h1+h2+1 - # s4[i, 1:w3] = q̌[1:w3] - # end - # end - # end - - Res_stepk_result = nlsolve(dfk, initial_x; ftol, iterations, method=:newton) - - if converged(Res_stepk_result) == false - if exception - error("Not Converged! Step=$timestep") - else - # sim.convergence = false - break - end - end - total_iterations += Res_stepk_result.iterations - xᵏ = Res_stepk_result.zero - q̌ᵏ .= xᵏ[ 1:nq̌ ] - λᵏ .= xᵏ[nq̌+1:nq̌+nλ] - sᵏ .= xᵏ[nq̌+nλ+1:nx] - Momentum_k!(p̌ᵏ,p̌ᵏ⁻¹,qᵏ,qᵏ⁻¹,λᵏ,Ḿ,A,Aᵀ,dt) - q̌̇ᵏ .= M̌⁻¹*(p̌ᵏ.-M̄*q̃̇ᵏ ) - #---------Step k finisher----------- - step += 1 - p̌ᵏ,p̌ᵏ⁻¹ = p̌ᵏ⁻¹,p̌ᵏ - #---------Step k finisher----------- - if verbose - dg_step = ceil(Int,log10(totalstep))+1 - dg_dt = max(1,-floor(Int,log10(dt))) - wd_t = ceil(Int,log10(traj.t[end]))+dg_dt+1+1 - progfmt = Printf.Format("Progress: %5.1f%%, step: %$(dg_step)u, time: %$(wd_t).$(dg_dt)f, iterations: %s \n") - progstr = Printf.format(progfmt, - floor(timestep/totalstep*100;digits=1), timestep, tᵏ, Res_stepk_result.iterations - ) - print(progstr) - end - next!(prog) - end - - bot -end diff --git a/src/mechanics/solvers.jl b/src/mechanics/solvers.jl index f932472..4d83cc2 100644 --- a/src/mechanics/solvers.jl +++ b/src/mechanics/solvers.jl @@ -418,12 +418,10 @@ include("dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_nonconstant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_mono.jl") -include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_cluster_cables.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_hole.jl") include("dynamics_solvers/Zhong06_family/Zhong06_CCP_nonconstant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass.jl") include("dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass_mono.jl") -include("dynamics_solvers/Zhong06_family/Zhong06_constant_mass_cluster_cables.jl") include("dynamics_solvers/Zhong06_family/Zhong06_constant_mass_hole.jl") # include("dynamics_solvers/Zhong06_family/Zhong06_nonholonomic_nonsmooth.jl") From 7432a13077ac63b536809eaee7a200f82daed582 Mon Sep 17 00:00:00 2001 From: Jacob <88961633+jacobleft@users.noreply.github.com> Date: Tue, 21 May 2024 19:31:26 +0800 Subject: [PATCH 20/20] merge branch 'dev'; # Conflicts: # examples/robots/jixiebi.jl # src/control/control.jl # src/get.jl # src/mechanics/contact.jl # src/mechanics/dynamics.jl # src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_hole.jl # src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl # src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass_hole.jl # src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_sliding_cable_FB.jl # src/members/apparatus.jl # src/postprocess/vis.jl # src/structures/constraints.jl # src/structures/linearization.jl # src/structures/mutate.jl # src/structures/structure.jl # test/vis.jl # yard/jixiebi/Group2_1.jl --- ...351\235\242\345\275\242\347\212\266-1.STL" | Bin ...-\351\232\217\345\212\250\346\256\265.STL" | Bin ...351\235\242\345\275\242\347\212\266-2.STL" | Bin 0 -> 147084 bytes ...351\235\242\345\275\242\347\212\266-3.STL" | Bin ...-\351\232\217\345\212\250\346\256\265.STL" | Bin ...-\351\232\217\345\212\250\346\256\265.STL" | Bin 0 -> 139584 bytes ...-\351\232\217\345\212\250\346\256\265.STL" | Bin ...-\351\232\217\345\212\250\346\256\265.STL" | Bin ...-\351\232\217\345\212\250\346\256\265.STL" | Bin ...-\351\232\217\345\212\250\346\256\265.STL" | Bin 0 -> 131184 bytes ...270\255\351\227\264\346\242\2016.0-32.STL" | Bin 0 -> 418084 bytes ...270\255\351\227\264\346\242\2016.0-40.STL" | Bin 0 -> 416884 bytes ...5\351\227\264\351\203\250\345\210\206.STL" | Bin ...\345\212\250-\351\232\217\345\212\250.STL" | Bin ...\344\275\223-\347\224\265\346\234\272.STL" | Bin 0 -> 1443984 bytes ...260\276\351\263\215-v1 - \347\241\254.STL" | Bin ...5\260\276\351\263\215-v1-\350\275\257.STL" | Bin .../tail/\346\221\206\346\235\206-v1.2.2.STL" | Bin ...7\346\234\254\346\226\207\346\241\243.txt" | 0 .../tail/\350\202\213\347\211\207-3.STL" | Bin .../tail/\350\202\213\347\211\207-4.STL" | Bin ...\211\207-5 - \345\211\257\346\234\254.STL" | Bin ...\211\207-7 - \345\211\257\346\234\254.STL" | Bin ... \347\241\254\350\277\236\346\216\245.STL" | Bin ...275\223\345\244\264\351\203\250-1.2.3.STL" | Bin examples/bodies/build_2d_tri.jl | 4 +- examples/bodies/make_3d_tri.jl | 2 +- .../EWei/define.jl => examples/robots/EWei.jl | 199 ++++--- examples/robots/Tbars.jl | 34 +- examples/robots/bai.jl | 180 +++++++ examples/robots/cube.jl | 65 +++ examples/robots/pointmass.jl | 19 +- examples/robots/prism.jl | 488 +++++++++--------- examples/robots/superball.jl | 38 +- examples/robots/tower.jl | 42 +- examples/robots/two_tri.jl | 39 +- src/Rible.jl | 3 + src/control/control.jl | 11 +- src/get.jl | 37 +- src/mechanics/contact.jl | 35 +- src/mechanics/dynamic_relax.jl | 2 +- src/mechanics/dynamics.jl | 43 +- .../Moreau_family/Moreau_CCP_constant_mass.jl | 14 +- .../Moreau_family/Moreau_constant_mass.jl | 2 +- .../Adjoint_Zhong06_constant_mass.jl | 2 +- .../Adjoint_Zhong06_nonconstant_mass.jl | 2 +- .../Zhong06_CCP_constant_mass_mono.jl | 114 ++-- .../Zhong06_CCP_nonconstant_mass.jl | 2 +- .../Zhong06_family/Zhong06_constant_mass.jl | 24 +- .../Zhong06_frictionless_nonconstant_mass.jl | 2 +- ...ng06_frictionless_nonconstant_mass_mono.jl | 2 +- .../Zhong06_nonconstant_mass.jl | 2 +- src/mechanics/inverse_statics.jl | 27 +- src/mechanics/stiffness.jl | 2 +- src/members/abstract_body.jl | 3 +- src/members/forces/gravitational.jl | 2 + src/members/loci.jl | 4 + src/members/rigids/natural_coordinates/NCF.jl | 4 +- .../rigids/natural_coordinates/functions.jl | 6 +- .../rigids/natural_coordinates/mass_matrix.jl | 278 +++++++++- src/members/rigids/rigid_body.jl | 98 +++- src/postprocess/analysis.jl | 39 ++ src/postprocess/vis.jl | 35 +- src/structures/linearization.jl | 179 ++++--- src/structures/mutate.jl | 71 ++- src/structures/structure.jl | 64 +-- test/Project.toml | 2 +- test/vis.jl | 50 +- yard/DualTriangles/static_stability.jl | 2 +- yard/ES/main.jl | 2 +- yard/EWei/main.jl | 59 +-- yard/EWei/t2.jl | 2 +- yard/EWei/test1.jl | 2 +- yard/LC/free_copy.jl | 2 +- yard/URDF/urdf.jl | 2 +- yard/adjoint.jl | 3 +- yard/adjoint/diffcontact.jl | 155 ++++++ yard/gravitational/cube.jl | 176 +++++++ yard/jixiebi/Group2_1.jl | 2 +- yard/jixiebi/dyfun.jl | 2 +- yard/links/dynamics.jl | 2 +- yard/links/link2.jl | 4 +- yard/manipulator/controller_Lya.jl | 2 +- yard/manipulator/eigen.jl | 2 +- yard/manipulator/free.jl | 2 +- yard/manipulator/man_vibra.jl | 2 +- yard/manipulator/planning.jl | 2 +- yard/manipulator/static_stability.jl | 2 +- yard/ming/ming.jl | 2 +- yard/ming/verify.jl | 2 +- yard/nonsmooth/cube.jl | 50 -- yard/nonsmooth/make_notebooks.jl | 22 +- yard/nonsmooth/superball.jl | 65 ++- yard/spine3d/main.jl | 2 +- .../deps.jl => stability_stiffness.jl} | 0 yard/stiffness/Tbars.jl | 76 +-- yard/stiffness/main.jl | 288 +++++++---- yard/tail/bai.jl | 401 +++++++------- yard/tail/curve.jl | 23 - yard/tail/dynamics.jl | 2 +- yard/tail/plotting.jl | 65 --- yard/tail/swing.jl | 74 --- yard/tail/test.jl | 53 -- 103 files changed, 2419 insertions(+), 1404 deletions(-) rename "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-1.STL" => "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-1.STL" (100%) rename "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-10-\351\232\217\345\212\250\346\256\265.STL" => "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-10-\351\232\217\345\212\250\346\256\265.STL" (100%) create mode 100644 "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-2.STL" rename "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-3.STL" => "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-3.STL" (100%) rename "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-4-\351\232\217\345\212\250\346\256\265.STL" => "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-4-\351\232\217\345\212\250\346\256\265.STL" (100%) create mode 100644 "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-5-\351\232\217\345\212\250\346\256\265.STL" rename "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-6-\351\232\217\345\212\250\346\256\265.STL" => "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-6-\351\232\217\345\212\250\346\256\265.STL" (100%) rename "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-7-\351\232\217\345\212\250\346\256\265.STL" => "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-7-\351\232\217\345\212\250\346\256\265.STL" (100%) rename "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-8-\351\232\217\345\212\250\346\256\265.STL" => "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-8-\351\232\217\345\212\250\346\256\265.STL" (100%) create mode 100644 "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-9-\351\232\217\345\212\250\346\256\265.STL" create mode 100644 "assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\346\242\2016.0-32.STL" create mode 100644 "assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\346\242\2016.0-40.STL" rename "yard/EWei/STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\351\203\250\345\210\206.STL" => "assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\351\203\250\345\210\206.STL" (100%) rename "yard/EWei/STL/\350\243\205\351\205\215\344\275\223-\344\270\273\345\212\250-\351\232\217\345\212\250.STL" => "assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\273\345\212\250-\351\232\217\345\212\250.STL" (100%) create mode 100644 "assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\347\224\265\346\234\272.STL" rename "yard/tail/\345\260\276\351\263\215-v1 - \347\241\254.STL" => "assets/tail/\345\260\276\351\263\215-v1 - \347\241\254.STL" (100%) rename "yard/tail/\345\260\276\351\263\215-v1-\350\275\257.STL" => "assets/tail/\345\260\276\351\263\215-v1-\350\275\257.STL" (100%) rename "yard/tail/\346\221\206\346\235\206-v1.2.2.STL" => "assets/tail/\346\221\206\346\235\206-v1.2.2.STL" (100%) rename "yard/tail/\346\226\260\345\273\272\346\226\207\346\234\254\346\226\207\346\241\243.txt" => "assets/tail/\346\226\260\345\273\272\346\226\207\346\234\254\346\226\207\346\241\243.txt" (100%) rename "yard/tail/\350\202\213\347\211\207-3.STL" => "assets/tail/\350\202\213\347\211\207-3.STL" (100%) rename "yard/tail/\350\202\213\347\211\207-4.STL" => "assets/tail/\350\202\213\347\211\207-4.STL" (100%) rename "yard/tail/\350\202\213\347\211\207-5 - \345\211\257\346\234\254.STL" => "assets/tail/\350\202\213\347\211\207-5 - \345\211\257\346\234\254.STL" (100%) rename "yard/tail/\350\202\213\347\211\207-7 - \345\211\257\346\234\254.STL" => "assets/tail/\350\202\213\347\211\207-7 - \345\211\257\346\234\254.STL" (100%) rename "yard/tail/\350\202\213\347\211\207-7 - \347\241\254\350\277\236\346\216\245.STL" => "assets/tail/\350\202\213\347\211\207-7 - \347\241\254\350\277\236\346\216\245.STL" (100%) rename "yard/tail/\350\243\205\351\205\215\344\275\223\345\244\264\351\203\250-1.2.3.STL" => "assets/tail/\350\243\205\351\205\215\344\275\223\345\244\264\351\203\250-1.2.3.STL" (100%) rename yard/EWei/define.jl => examples/robots/EWei.jl (81%) create mode 100644 examples/robots/bai.jl create mode 100644 examples/robots/cube.jl create mode 100644 src/members/forces/gravitational.jl create mode 100644 yard/adjoint/diffcontact.jl create mode 100644 yard/gravitational/cube.jl rename yard/{stiffness/deps.jl => stability_stiffness.jl} (100%) delete mode 100644 yard/tail/curve.jl delete mode 100644 yard/tail/plotting.jl delete mode 100644 yard/tail/swing.jl delete mode 100644 yard/tail/test.jl diff --git "a/yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-1.STL" "b/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-1.STL" similarity index 100% rename from "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-1.STL" rename to "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-1.STL" diff --git "a/yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-10-\351\232\217\345\212\250\346\256\265.STL" "b/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-10-\351\232\217\345\212\250\346\256\265.STL" similarity index 100% rename from "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-10-\351\232\217\345\212\250\346\256\265.STL" rename to "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-10-\351\232\217\345\212\250\346\256\265.STL" diff --git "a/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-2.STL" "b/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-2.STL" new file mode 100644 index 0000000000000000000000000000000000000000..79ebb1b780def0519fca3c8d91dcc441b1d267c0 GIT binary patch literal 147084 zcmbrn2Y405_y50iq<0lWt~3!)dP#0>b~jik3Ic*6APCZX?<538iXVDMq?rgPO=`-` zCMZe=1w|H~?BFUMQiwH?OhdcsFqpMrtng;KWvq`jv4~7sTxrc>=k&R7&uljMmXI z{pfJ3%C4^s({$%*?b%#`+}GbsxJ?A!4j1Y zxYj0z^-t*o#-0|!$Mk{!L@a)CWMa(eXdNw|6!<9RX01cU^|o#w6)OH2(W1`U#O`NR zA4sh1@Igw;mkt?kyeWL_xNlBQjYofWa>wQk9gS5zNJoM@9nze;!Toj$_HAMbw<@!l8BlS^Dx z2~;J1T3+usW}i{CzaRqT21XcD>L;JQ9<8J0(tTY|q}n%fpgUI$_PrhP`nwgAPux^} zAhB>lYdwFF-NyYv!pHK7jUtLRDVn^Kt}d1kRrIXr;^|sCR1k~r*NphPYL4XM8PPgg zK8%mn|2q7Y5lQy|e@W8{?JpDY{EBl)z5i2vAki%_NAGno#rS!I@Nw^t>;5IM4*LQZC$kI$)rNxn)c?B=Kkj!HcRSoU-f~+ z(2o-Ixoy8NUK}fYTxoG7{IPsxleV}BRJ~L(sPApF+E^}$=J!g4)#$t@{1OquQh)6N zY3Z9MsDCkkfw7EKoU4p@em)i#C=h;k(&@xAnS}jY^^#Kb*J9(0y&=MWqBaLNCBCqx zMdC$Qu8`2QRJyv$jSDhYEwjIrB%Ww@IZ&nMYQ|^JCAEIKRoJ&7A9jA7-|c$d(koB= z#Q0PC2>W$z!kjO^2>-`LpbD>uriFj^r2p>!UhvN+0nw-_JBIhVG#4d;5sK z{@}j${<>&YL0czowmga)Ez+#TfsAP`%>cLRH~jpX(PoO*K+wO*~jQ*?%$b ze18NHX!%vv*U7TJs@Lk3q?7*JdDi+@glaqcKw@3#rTSAn-#3cWv!ZEF*UA>L>+PNX zLwD?&$ONhum6)UVtu(xtJBvod{_~Un7Cp6S$@b1P{nWqXjPHiK>s7+6$`K>_ z-}LXKmI3pN#0+XnHVhk{*_Ql%uR%m|Ox}ovw^agF1wZenA6+=qxG_YOt)t~WwTUxM_JualzJq56^@wOxxkkkH8>$Z^`s=#>V`^WcC$*@W*6x#05$30n z5jU=>1gd5~Sx}GI-rWfAD~N+9rbg_v-irA7?`Rz@r>O@hv$vb<0q}}wTBY&}B1Zi= zAmaPKR3AuuJ%2;wKU2FH-FgTgrKumhJhXVkH7Ys&7OHrJlM&Bj(UrG@5v9NG>%T@m z(1OGO>IXXxdpENmEOYkTh{wyn-&A!7FN<>9$$?1Pr1$Cjp;dAb;P+Sua~J6A{EyBcwR`+)FQ zXncjaLPCtY%F^BB5!vi#u0#x~IVn8f8I?fQ&o^^e`+n+XY?EWS>pkyA{Mxi|_;MQc zq2;$c4XhSR`WS;k<3u}G7lYXXn}6OH_SCPc4)Iw@L7()JDnGYRrp0E zP*wI!H|uceA;ySC;_80!cdp^`;U+$PW2wPy$$;}`BP8K^2F35%s`KB!n&lD<^c&mR+nXBi&il*M!`7KT}@m!Dju5n@;>aD+$C&D+$cGn!Do$$}6NS&e7%8s9jfP`%v>?%a=t=40dR#H`;YFZ| z(;4whTn2r`CQp?_xKB})RNItv>RB<{Zo{3M|SklLtA^mi;Akm~#Vft;K zIrZ^8^j|LmRh*`|qa=FAo|8U?&3{iv3lcSoiCRu8EMI1$|9TOq;JAMGN2ENlN)BwCR0 zHGNC^cxPJ-`S2o8#c54rqVa+L(#P-PcSNEEiRPbokUo6H-yk1e1gbbq^<5Hg?HDF~ zR9-nF5-ms^D*ul3p=k#B@FGyfY4J=5VqU4U5zCs#CcKl`w%aW=-CIk{=*H5@Cbq$v z_V4<05y4C2!?F{hS{y?33>`jSnMMDB1gf}?vR6_c?4#I%gy^sK(M(wMa5O(JQY`S> z-edJzQa^~lg(_Ud)wC4{-;`H3|JKK>@h2K*Ud42S)8hK18?9dwH8G=dfqeZ8Zvs`E z_L)qSJK9nDC@}MW3R;l(=`T?eH7#o1PHGLk2vl*}XEO0q*WS{{t=|u%paqG0Lpn+y z7snPz)if^xRh;&jOmuv0g!J)M>-SU8g2boSJ4qh}i_an-UIeN*?K7EpCug+uv8~zW zAX<=E@_lFNgYFIa@FGyfX`jhN&fevMbg8v=2km(juX5m=s#nH0hR{6zq^MV31gbdg zGnwdiVUP5&HFdm>79?)>4Wk@sTFqNxB;!S(iqk%mi3$nzQUw3?l`%S6kZ5yiGWp1e zFLk##`S2o8#c7|(#Nul)(nnWogpL*@0>(BjN6A9u!;3%_r>Pv0=+*R7>0{9F!8%%y z$iMD)>0{0G+~mWHKozHbCKIFD?36zCAM2~51&Ka~b3}>j`S$g@X`1Fmpo-HzlZkH* z{UUu_9ot<;3li0u7neRZWLzd6UIeN*?K7E}cjvzJadb;Z9W6*azt|^zytVvS^5I3G ziqk%mi4tEHv&41Cd7!0^79@VSQ%(Blz2y-3@FGyfX`jhNu}_|rKE57r>S#gYv2OLr zM@IZ7Uj)gA7lA5H`%EU*JsXfd%EVOH(Sn3;iZ07Bd-)pj;YFZ|(>{}lV&z_!K9&?M zsiOsnYz<$LKE_p_E6U+Ppo-HzlZk#!J4+uge0MVvEl4B`drkV-cY8GX@FGyfX`ji& z+=cz5kJ8IhBGH1xss^p3k0Dc#{zNOV8-iX{I2arQ$9R1LUV zTM}^zb6f;kkobP)i;~Fk*B370^uq4avUuz)BUe;=nV#0GsEOtCE;$n4Ci3iV%Cjw8 zKJd3tg;zoKf%l`~_d{i_{ulO3Dvlpj0xd{vI5kAlhbu;>dK0L^aj;6D1&LNK4U#^x zS6(Kc3_)=%K>}4co>zUK1&N&z{iKi8L)Ocu!tsFws&HPS`ala3SQoqrRN?$eCD4Kd z)&*}uRoTyDx}g%zvz=~aO=QtBP~8+QgXme(Gt=p*YLCNS_ztQThrpgl%@q=;`d{`w zQNs7rQK_jaffgjNC-NpxwP1R0>ErJr)m=W&f&}(Nst+Vkl{U4f^f7Q>VOLE=i$cg= z&F-Vv3twF%u)q4_`g_txgZ=#tHCJds0(&BF0#(Ngca}Z|eDI^o2U?I&dm{G2e zH_rs552|le*N{L95>Bmj6Gs+5y;Ibmm=*P-mR>3+(_I%lA2scNb!GZc_;ch7eV_%2 ziKEI(V%7XI4sp}&iMGdi zeK%K;{~ki1%DW##3lfoiYRGcbG`G5ZAb~3EgVp;n@X8VT4WHSgON*%Edw!7VrYGiW;ks66LE_W6za??!T$hIssM^%}z9hEo;#q~r8P{F3AW^!cm^=H-Wn?~L zRIS;;B_FoTbooFF5?dEkls?k>y6+$osOq~zvB79_?;)sV!Z*6v&(fvVJd6(muwweZD%{CuDViOu)xO5#$iJ6A}c zs@UbqlBhFQ+!yqL79{TE68ZO;>2HgB??s^MzZraWuSMr}5okdoe}Z57xN}6*Nc4dO zsvd75dK&7_|GrLb3KD2RBH!HzN&IiN=JJ6AstWb2Dv5|ZM_oS9f`mVBq$HlYe(E6v zs?PVQE{SsE6I=vZkf^g-m&BFpUq6IERo@adC2=X|CoTdlNPK=XN)kmIe*O>wReKxM zlf?R56I}#akVsu1)~|f#^WVAWoJgSR<|4j>Ri-s@`9KR2g&%7!eN@{$@F4`Ma7?7u zE3_bS_=k4VN48u~xqZOM3spE$Q+?pu>6br$W~aD5LtB^FiEoru0xd}FEL>62x$}q> zdj8|K1PN5(8)cP13ljPB*O5NnKk%5#2NI~lH_ECHv>;J#t08@yO&2i-{Kw@$0#*1% zStZbdMD5G3N*}#SpLh8{0#*1%S@nSyB%+qQDSiAjORQ}3AD06ORN)(Cl|Ty;!*_}| zSU$7rxUDW9NT3SeD62lug2c-sdP*Nr=NGwrAb~1;qpbQs3ldNN!|M!Qv)m(#N=#?h!ItkQjQgq$FYoyzTOV1ghHg%qNKo)ta~nv>=g~!oi2Q`KnoHxGl>@;sJlp@YDT#=(#L{h?s|n5Bp$oIS`xn=ch@Ta^ZkQh|Dhoq0U5^ux#k6UUa zP=)WjRRS$Y^w=VTt1LM6~^eOKG1^1-Tb_kQ9DB0=}n*tV~tb-El50b zwX7`1w`20Ud?0};jG0n>paqHUKNXZdI(IAL@__`ZF!oFJffgis{d~g|_q<~BCtN;| zKo!QYsXowxMDH(mOCP@HeJ&qJpbBI0R3B(TqT01Z(#QPim0doNKo!Omsy@(y#A{RD zl0Mqy6(fHB7&c5RbAyk0#&#RM)iRfB>uh0BmIQHvo0S< zpbB@vs6Nnwgnr__EXV0V9>8R&-awe2NI~l)ksZi^}+5+ zG$OO^kB+a1kzg2k#&7#IO^FXezos6s5(HTok8{Fw{ZR-0H^ z5O<5dUl~izYsjRcwP|c)Xdh>apZ6R}t-ffgkAeS)Sb5nD1>NT7-%t29lC*pdWVkl?s1 zP2-5IwWqF>7bUNHx=LkiEwL5lh}MkC94Wgw;~RND;?L%wG(Mo$iF;Z5R11(74PBiuEB7rK7Xw@_&Qdasv3lg}aPW6EVs_>boT{Y3iDv7H* zEqP-lv><^y12ygH%5jp&UD=370#)8^3HCS~ZKi1=797VbYB|t?1jnt>el?74lh+Cf zRBd??ong#&2lo{2zMTqqcCHe~OgEcS-Bx(1HZNd(kw0kJJBP zE7>NNdgqBsNT7<}x6tVi_#Q`IE3_cNZ)<2DAil?u1on{FbE>0rt|#0kq6G<#pU^ZV z%0l`;0#zInqG?LB2oo}nge^#LREMT1(IO8JsNzT!O;e&?B!LzrI68%Pg=5sq0|cr# zMu&D3Vf2n9(1HX<+0d98qjw%4P{pxEv_lx9kR*W?Bsf}#PJh5Cqz4F8amt_u363hyi05c^qd+q`OHG{oO&k)a;@Emkdlq*IJN|3Cs&9A!nTee$Fb?48kq1V>iU znW}cgR>%husN!fb`@|FUffghPoO!r_ESj=eXd6wT9Dv~Jvu2vMgo?c@qR^dKN`I4i$?-g9EE6~ zq=V%^3lbc8NGBTD5sjg1g#@ZNn$kWI2z{Uh367xDG>**trN(Yq@(YEgS3&|+92IJx zY}E7B!IEf~yetkaNN^;mrg4Pn>cfpHiEGvUNU3-vP{q-$_6bcb((216s!?Q0MSSjf zj|uh2w0A{)2C?L5L4xA|=mZ;#9FT1Z5~$)B1e(#)t{e7XKZ9sNg5wS}O^HsBK9E2a zM@DFx5@jI?v>?IJ5Spe$Sv)|XiX%KUO^Ftf1X_^bs18k2qD3AcP{oldbViVjdMP%@ zC)?ec8=A(W1qqH$8T}bYy=)6xC+pSb$uBDesyN~%qcTVDw7Rff5*?er6pt1pILam? zo}+h$PWw{U#FtJrRR~mZGhmdSB+!BcN7GS1C?lO#w8$lEVz;slKScsn98;JP&(VhM7Uqz> zbFS2{E1?AmjtZo+PGq#7+u8nv^9+0#!KESKBLW zYk4n#rincUYP*ZAC|Z!<_k*;OO8Xn6KE`enkw6u{X|zxHLmy~Cg5O8d9h7e^gFjr7 z&tSnHD^)}SRs6=(KB;iY@_dpwJUnJNT7<} z#M>uel8+F979{xXyQV2`^<_;&0#zJQV4wYoKG1>$M-k90RYoT)s#Z?k!Q?aBS0RBa zj*PHRp>1)mzI=m~e&*Xav>?IJ5SqqO7B3l}t`v3mk1HyHDm(>@#!T-lk;E&H?~X$Y z5**c`X&f!mb!dCp`s6BYDFmwU6fn9{a6iz31V^W6niBOQ?*|g7!c)LhA80{>qim@E zkkLEqzF95rhkwUoaY&#FPXVKK`rj8<6j!(Il3j6VL4u=&G>xN>o)~*bJ|AQL8lVuU z!c)N1a-anXj(VcD1f!|swL$__9Lc3=d{!9V540e`(OWbEz^E|k0|`{&DPU?j(1HX< zp;2Fp(QVQP5~#vcz*HY-L4u>{G);-plRl6@6`lg7`ala392KZ(O0=Q$fds04P)-+< zUZ`G)|Dpv6j&7teoQ#^hJ@d4zyUXrvi9-TacnX-N#s3;3YvL257Q~?i369dFldoj- z=ah4en@V)@n`TWUlso+cypgRN*OL zG>_cG>!OFVrN*HJ367f8G$k5WUR@+mg{Oe=-4M^YNTCG@j{c>ylQF9J0RmNc3Yh8x zEl6+_v!*H0(b5MJsKR&_P5Zt4dA_M!+bQ82iq&Z=#9T|SU_k z`d*oB#MKeRsI&sXqHRlUZ$`O7ODdgv9!ck(|5(?Zt4YiA2kZR0Wc!~)V1AKk+H$>B z;kRiyUS|1y?WqDB;d8(bj~_^X>m^^uo>qZ97@!`9Vhd%kFac zWAg=v{+4&g2gjo=^!^i_B!7oal3&-*O>`RjSnzsk(;dZ5s3k`tvd~g%L)Z6>%6?Ju z)<5S7HhO05j;k&LRdX^=$KM+eM2R}NgC8Vo3E!QJw$M`O)D$akjd4b8!=0<5=PfY$J+Cs~b)n>}m zUw1a@ws+_1hw&$p^XtDRc0RBAKq6)8Gbzm`cQy)l5I%0LJeoXaZLXxVAjQ#-Ux zZhlqufkdzOi|H>n>S1i@Cwv^s*&{i+Z6Nun8!CaSYxEr(@vJl-B#4nMUQa&v?sLg? z{*AWK5>>0Qp1nkW;}WT`eAKqbHcc+pp++cl&n@iIXa_Q z^6R%%0#(?$Qtw>2Q1ZdXeJ97;;NqxwK% z*_U(mK`SR1F+|hJ%hmo#I+C$F>7I)~Ro#dM`r>}E#z9GZ+VNmgowFO0th><`TKIcj zlZ_8YyK_|}YF$$Fk4uu?x~Jv}iBlz4>v#4~HWG=Z$h%9ElaBrOe$r_dfhzkuPr1el zLVO+XyYaP?KD{4pq2!%X_S5Hg&g$T4vY8})E=3Ho;ejryTE6xl* z*>%470+^C3Bu3t~^j9V>Gb)Y~B~L!p(Jw}F%UuMjxO_g7=g#q!I{U|eK5P3YM4*aB zOS(9RUi_{~j2YG5pSo&MgOwp4_HQ{vVanCuNla6ecf*gu3wK)>?v#TGR5cC@>W`OS zZTu#$RhvV-660qT@qb4?&?2sz_;Q-KqH3;uXa7jdQ>TW1tt(eZ^f!UwSYpuHYtr3O!L+LR5WIae@BZqM)%~K7-o}T}|4v zV2}ScJ+){#_3>Q2{(C9LxKPVr=j!R*x08O!e#pN!^qjK=3DHW-rEiXkc16?vXqch{6dkO5ueaF5iQ~?W8%ApV$6uYMDZLw z>L*`%u6RVVP@BlPLgL0R&GnuGcN=|VE86UC~W%N zPDuX!jW;7|hWaQbQ1wgZS1Lshr)k%hY)fwU>?l8d*U}RGtN2Ey=(l+c?=!_pTKN0R zBbWYt(6}M{+9TATpZv8{M0e`X(Sn3pj(r1`BrpH>gNT9DJ0pRrj!_#Uv+X!&d?9=1 z1=FV|4}E=5#J|)#qXh}I98c4@KbA`m1YnM}={N#Yqwzar}_168BJa5II z@GhazE9VMT2b$eWIo9-mF|?H+wzRvF{O+oE!|&4w87=>0eu35*A=}sL_)|BMr^Z$b zj|+{$*@DEzd=0E;YwtCVH4{DtkNGco$fjFiWkMr;CQv25Q6_4>m?zMg(|_Ghe(F*} zSazCCpe6gPUe^34zcCiPEy;7klRp)-Q6i z;g*xC4^1>!N)G?B_-;xiS$xuVCk)pl^ByySQL*%bR`cA949W;)|7*b>{j?Bc+xo`HWWz1Pwh;gXykv zsH#+2ty*q~H6Z%BHz^YMPKUnv;z6K_(>{~mE?ph?we)f1yYUuUkid6S6cO)1po-Hz zli!k+N~tZsn~`30tc4aN@Esd{vCxA+6{meBzwKLJ`+ezSPsCwmP^$`sguWpoJDB@SP{^=ky>@#c7|(Z(ln!IU#*qc%z4f79{Z9t)_VqsNyuA zl1J~cBCbmxr|)&P(1HZMgZ3s+#c7|(XX!N$%Pm)fSKMu9p#=$iORi~N1gbdgGda@f z@|UHhk56tjv(SPB#z|?K7lA5H`%I45nls@A>EqqzehV!~V7wQ_RCy4n;r(v><_Tgqr3>po-J7&BPy(wrx0^=cRxx|A&6{meBM`q?4&fiM8 z|KEZXv><_TofKc=L7f+k-$Ar+p^xa9iaYC9l=k zb$ueyf&}g{quqBN1gbdgGkJ&Gq167;M=xtfBwCQbJ!Z5g(1Sn~r+p^xaO-@pi}aB% z@lqsOkib1=bU!=@RB_s8^4`}L)!IoPGe63sqXh}vIjd=21gbdgGsW&)iWL5leM}me zTSp5LxVP7vKozHbChw5m{X1W))Czw^q6G=uUrpy9co3-Kw9n*y+Z8|Jd;ayogh;d? zfxEsb;=qGI6{meBe7lA5H`%K=$yCMI0>7&rxI{~yHfjfXT&5J-4r|EkEaxe0-UEE&Hi0&MT79?;d zv!;0wsNyt@;pB;=8($nC%W<>twn(%ffjhD_&5J-4r+p@$Nc#MWcchQscixFa3lg|z zoc8N^5UAp`&*YOSzRuQI`k1k|oQ@VGaDP3WXyHMiiqk%m_v-ijxVrRlykI~_3lg|n zo}Ld60#%&$nY>qjLcfC2#|vHC=x9L#_mWa{p9g^|PSgF6CzARH9+l(vv6p)4XhA}a zN%bO7#c7|(J6YH7n<;&K@zF3HEl6MtEX|`l2vl*Jz8fxMYwOOaA$_c_H&#ar5*V3F zd!9T9RB_s8a*XiJOpZN2nEtA~R{ySx*3p6l zMy^vNhX;WwPWw!bq2IlguT?I(R%k&2Bk-v|_aIQkX*wTH?giLYx>!K0$uy%c5aW5D zsKT8Dn)V>Udl!&Ee-vv_>Wx5=+6xj&t&Y}b##{QeGb@ccjk`qIZ^`md8h1ocWNO>D z0x@+ignjU7w60qCEtw$nr|2zNmnFtX`Aflh?E@c=n-rd~B3egFt1nXYlN}cun;!5n zGo?eoe|Sas*5#@XBn*0ER)eCD#x@bTE%|e&K)&}cgenh9e2 zfi8h5Z}BMri>>A+71%C2FwV zNiT6`kn#CIcdqh()+10Q*xnzUAFbnWSue-y|4>ZP)i>P4i7mYXKWrN5|7xz9DPPR@-l6yPaqkFXQLtZN`R>L3-7}+gwEXw& z6unx-aYl!(?p#g!w|`*X@=yKKW~e@pNYDPE9+fi2*!7<9Q91X(K!JMe{3E8T1gh{F zQdHQH=s=NQen`k46RoeH_YtM`b~Eno?Gn}K(_+@lmwOmT4|a)CpC~>5(7@3ghyBLX zXdUmtNAzB8JVjQ-jdYiz>aAgcU(fyKuQplD6%y?~sixn1y0>wBoG8a18-@q|+I8Ol z?uROYsy`Q0)C<4Z%lI@}5dI%y0~5NBNPKd1v|gs685#CfXXCx4R7-w)Ch`}G*m-Z6 zyByo!8yVR3(ry3P52AJat(o+`t|VQB%9GvYST%BVphAT_5#=VTxk6%O!jF+pQruFL z=^|H8jO-QoWly-j<~)@^m3nnM*P0lZUHQYrj-%`rj@v6FBI&(hhhgs;n-&Tm=AGEU ztDRyJ_qqsF;T6%eh9hGG|83};c!I7KUZ48@0(EIrZ|qp(zE-y%j}0uF(JXQK7&TW& zEVv#QJYAu)k!^!4`QizI=X%vjTrpN9P}Q8?%87D(o+yYuVG{x=7s@4e9~Z5o<(VQY zQYMw}VmzPX&Q;UPF@bOXE|z$Y2)v3&Y&g6zrPkaoMzvJoW9XQez`>^X6V8oS2~^=z zKyBi*@qyvS+Jx2k;cD&3Lj$|j0%|L5A2vXNhMGawjfpkh zy&-%&H)(j_iI<+&{h~8AAhwK5ntS5?|9hHiP=aHaWzp*{3cJ3ycqJ-u{g%SE%Z=aEp~|%M7EB zBtEV%G%#R%h3#X>2U?E(yVc6rFw-cWv#YCK<;*c8u>V$zZ8NAJ#A}6wcw<(NMgYU| zh+KVO3=XUx`r+1B{-+YC>fb47RV%g7SSX3x)%yi*ywz@dKI+wGyb!dO)mm*#APYs- zSo`SRo%mh$?K61?=#evn0yE3c+58Flz~9Py&$5cnUS|B5*Cy;eqs{jW55!czwe26* zJx9WRLwAg5+GTrWkR0`GaFqj9YOXGA857uCWkiFD^n9omekUk?x5gdIs=R2q@q_fS zDevIG@T9lujt%+X5~2#P2=zEMh6HA(4XEFZ?gw6<6l<$Bc+>{t7Tssncj+$&2lfxC zUhib+4zdp$RF5@n^v}Zr zo3wu#{6sYoEkDpRk&E6ni)R9ViS{(i7#@gkz^c0V41*( zz^R5E8cqn^K_*bOeD+-H%^oR6c6#RNE!n9NfkPvvH9SlGIa+2?`>~KBk3{>S=4xfF zQGxKB`x`C}wLa_vi9_Fxw>JIxm9bW~SI^BD9VpYURM?B57LEy2wWjv52E`hP_K{AB z+dC#u@!E@Fg{YRGW%G{a*6<;_jYHJds<|3pZd~A>MH9nhhTwr;>31LTE1gb3ROM(=aA^H+cJ3ecCV9~j?VXsk-gO=7qi&}3{U&H zZu%3^fiM33F)Rm-;V{2Qd`4rt8>J7(v7M$J7#$PnQTl$^AEADbe+yMT3vEo9 zWzYFlt_gu|mrI2oq`np{caxW=9KUkVs1WL%?Oge5PYCQ=`gHivQ18qZBwEl2pcO?x z@d#k?f(e0dZ`2Hr4~-d^K-I-pRs~m3e9^`A;#!?A7aM5u+H2u6X1+ z5S{I6Qd4>cF;}Qs)}Vp@RE@pH>Cu8%Gj&+tg}+WEt)!L#ElKxvUDR-AZeZuC&-x*O z3UT|BKBX28eIQZS>ZMmH`HgX}pYU;P*PuXLiR7fus1-#5Rb`EV`q@FdjJACR@okGi zf#v0PB$cPO9W5PcHu*fY24XgezeH!a_8AZuR&sSx$^KbSz(ewr0OMm>X=6>Hiz z=eh^lS8ka!gy!dH`7-+^{n&ypjcG01xynE8y+CrcT1neOYXIy6i3D0f*i8{hVg-SA zvNq@vxU#Ky(xD~lwL;a3!HN3TVV@fZn+hVeVCTTVY*!O^Eu~p1Sf1>jq-P(z)_8+d z>a|*Y;GMv_jz(8B8t{a4$-KF*GvA|+CK34<;jUlX-x)y3svfR(5&5UlJeh<} zIP@S;#c7|(XQbpAxl68D-nc~TiSUgYB=Ce4P4gm9#cBIXG|R`%X~?Z|jE)v0@T3@u z_3|K4#c7|(XV#QzP+Z=@)pV`Uf&`v;Lvc$U1gbdgGx>|qlP>3q6y?ZsV4RK?B=Afg z+STbnpo-J>7okVjo*;eH-abM{3lexj7mX7=2vl*}XYyHLpKbV7`lyxIM@I`1c+wcH zg?kXF;2vl*}XYyHk;l`WNN7$TvI$DsxllU~v zi$E2peI}m?xXkD(eMBW)j6@3(c%mS^=ky>@#c7|(XB)=$>MMPG)933*v><^eBT{?i zL7VXzY7nsPs{B*StuyAb}@5(wRLT1gbdgv%d(vX^iyoK?#2(T9Ck#Dyf=# z5UAobwI%Y4&@0Q)XpjE7wptTF3lezZCY_t*L7|+> zrT*N5KozHbCZA#Y#Hn%8$DcWJMxq4?JOPzfQauP%aoT6{S*$N!9U*;GJ32lRElA)= zu5>n+2Z1V1Q;e59Q#QTb0O_Ou@~x3*K>|;trE^I=2vl*}{v!0O(%q$xLfz6M(Sih? ztgC5W1gbdgGx?0)k!w0hA6BW`k!V2zPY9-+lO6=BIPEj}tm5$*+?Evj^L!*)kie6U zHO-4a6{meBf34t70=FeI&h3mu3ljLP13LN6gFqFheI|c(A+7Cjd950~F)b1;NZ>ac z=UZf&_k5!ka)9rzvi!NcB`YNBd`f&P#okKY$h_ z@M|UB1gbdgGx;kqH;b^3H9OY_(Sn3}qJtNKDo*p41?e1`&qvE^wf=026tp0LCrEe` zsN%HGOg{1CzSd0oX!&m$3oS_Cc`2IaMWBk) z_V)*`rZtp4cGan6p#=#%_l5Q}co3-KwEg|Tsi!MR9~&~FEVLkj=hx7AY#s!vI8EPV zl_%-M_b)Dee9^e2g%%|693DDJ$Adr>r+p@$2z1iSCVlL?)xkmw5_p~vo%rHGpo-Hz zlTS99`u%TmZcsL@n}rr6@LVLiRvrYZI89?wc|z0oBX&t2t84YO(1HY>??fk4co3-K zwEg|TC#J8KK8_|1ve1GAo>N8R5)T4Zoc5V~VpfSCCrKZ(ZVtE5f&`woMZ3>D2vl*} zXY$EkHP62&eOzxi#zG4ccy1V-2I)bdiqrI6WO;&Fbd$g3+_{5)yoDAd@cc7P^CD2i zY5V(waWPG$kCPjsEwmuPdsOZ7;k*b`;jUIqn>k@cgc$EOx)yEm`J(*AWISsWPZ9Md zP{nDV$tRLt9MM{qWAW-}3oS_CDWaO@MWBk)_IIk=U7IP(5v1MAXh8x`5v7ypJP1^A znw~*<_}h-#V_fhtbh z-#?#Ix1D@GwpSl*p#=#%6O{J+co3-Kw9n-4fBaE*z4UQ1VW5Q;B=GAY6!qdkpo-Hz zlfPr~SGOC|$DMVZEwmtkUqR6{F9KDZ_L<^KE3~We^)j;m*dEi&LJJc3ofdBbRh*{# z@kA8)xH=$A`uJ>IO$#kZ;5V_n2~=^KzD?fOARkk&x0XJ(%q(o71quANmp6ebPSgB@ zzQ{*=czgDcK2BUeo`M!6@cUTa1gbdgGsPDGX+^jh&p)cHnwEkVB=Cz`-UO;R?KAo7 zT)SWA`T4{@il?9j3H&}5%|AQ{RB_s8^4Gb_j$|JTR}@Y`3li#=fxHM*aoT6{*SX?v z@Z6wEou(;hK?1)-MB^(D0#%&$nf!&Lc7aSE+1^S)3ljK!Bx-j(2vl*JVuXwQNBePJ zo6l=YTU!KD(1HYh=gFHu6{o4)m0z4{G?B}3HN8~|T9Cl+RZ)-WL7x?=GQ7E&t7EvPVr69%0%%pVVoIjDx zK8^jyH%A1&Pxd$HK?GWm_>iJ^UZ?1tX7`&@%dqE#k-_hWu4yp;LzO_4i2V^K6;_r+ z|G>y##JcqjCKG{{hPSp_jW*6SHvQM!m8)l-9~FH1TH%JvCaFG7mxT9#78)@6#=x^dl|s~o;D!FiH`T8`*oY5!m<;sX*Ifx310TcH5}$5P}PSb&(g-k8tX3!qRND^!R8-bYWViV zXbUaZ_szBHP;^_@i|$;F-ZCcGsM+?06osVRK_vc{89_Jof-L#0alyA|mkE0{RwYnX zfTHvYP?TQ5-vm+j>+!*kMOuZGnGkKErEz8?VA?P4TxDMs9o$%AY*-*h^?}6PjxDT_ z6m59osPK`eW=ybUtGQv((JFzeN)*vJlOh_QI3kGlZ^Q&k)>;}?p9r*wcoq>gdH1k8 zSM5&61Ye$!7FKG!>H~>xtBP48DJFU1F5#n8{|UhtKfDxncdSaFYE@=L^YS!7Y&;uvTnv ze3d7|`@0BKwaJWoeRh)|_RWb6&VBOv@VL>@7Fs%F#?y9>bLVR7PqD#Hw<5wHCjwgr zB+gf@u|>r4mRv4;RLe6l*sek2@a>~i0#%=$ekSraij>|qPY?yVO$?sQ{%-hH@;NlZ)!kf8#AW@&9UfNT{@7?Lb$JW1l1Y?%BOBy?0%@wNf zTNf0O(sFEY{7V&*U!l5-79?(L|1mN@MPScX;jc^P$D^no?0YO^$|tAl%R<3 z0pkTR{LJv+xeIxc=Thr~mZB7Iexp$@U>0}S%KwrWGDT< z(}RrcJ>0oE+hss-&%%94+or2NkSLwGpCa$O!bhDK`UN+~wTYZ9Ozu1see|EHmmP)&)=qBxH*wxORtGv^C2U`vOG%0S5>H`UTcf{jugpW=` zdIopK%}v@$JJ<1Ap{gnE&A3i`Gs?X#h%N=Y2UFgdn3Q{Aw1pOXH^<0k?p&2S-!=Hg zlf9A(FIIgZ(SdfQ%%NQ=Z#Nb`uKuq}@LK6NlUglN2~<_l*XwW4&X@782qN~c&cRme z&7>nAM_XtSdu19>Byryt-MJdo^_}3(kDf^?zfARkL<`!%Q}Xm|<2CtJlIMD~4_5u> zcH+JjDuF6{|BufQxoX(-t>DLdHzvk@8f~Ga5A8%M{LW&dt?tfM&x|&~HQ^%?$HuEZ zkZAmrrB9{ZPUVQ!w7bJv2V-8%nYf5nKkyE!D&8x#K2i{#<16@LC6BLsCV$s5reJqD zB3rRIJq0Z|3d3(v(h1uh1gbbqv4goL(x~sa!8>xFskki#ElA+ED7^_(ahl##%kNt5 zZ$3hnqd=4QQ_zA0ev4Amya-fr+Gp~2Et^&xCw;VA@I(q)kic(I(zmBQ2vl*}XYzL~ z$Mh8ATsn8D#kiaiX(ib{B2vl*}XYzL~FH`F&d=%U{EQl5)@XL~PI*bQ_Do*=M z{;uWo+IZ>X^P%^HXh8zMMM*oPJqT2B+Gp~2EzgeT69mq`Gdu+?NZ_|9>AM*o1gbdg zGwZc3M^Dt!`U7P-zRj^I1uaP6ww(f5gw=j+wutpalv17A3_Pco3-K zw9n-4TE<^{OO|8q**q3nkic(I(v04NKozHbCV$s*Vf`rS0|P%?Jcw*fnS!Slcqcf zRB@W#E=_1k^(wXC*D2x|%sH;Fg%%|6Ta?}esyOX4`MZ{1J{K!}{4jrng%%|6%aWSr zMWBk)6cr}FYdQFMHtFN?<#85Tkif6nX_^;-Do*=M{;uVY?=Q=!$x3JF4D8VtsYhW8 z68Kd+8t-}#sNyu8Od-Fimo)H@T%o^nA=*L<68IfF`XYh{fhtb>O#Y_c^h>-8`^XQ` z7Fv+N@8D^g7lA5H`%M0(-sqI&NuplWzaMR(1qmEWP(-5#fhtb>O#Y_c?2)erg^wbi z+v5_pAVKw27pDmFxFpZGRzZF8mtj5Es06A$h`01|XIC00eJk*A!3P-xTAk!q4^&9*CmJq-*C<=ZJMZrJyn!6ksWx5CBf1K#QwLr}k z60Il#|1w432bv2X8}IiBuJO7(*;lZH_{9eEr~RnOrgCQVxFnys!QCEV78Y3_^VGm_LUsKU_5y|kBT&`f*1#P-qk@rl7{ z6<}U3GI(+NvlRQhMN%^{8O)< zxQ+<4h;=5h`$()nsU@HILTqqU%oB-2L+e-U1BvOomZt=1&sV%$@mf?WHu&`q#S`OP z1gd72+?cYK_L4286*fBW_27iy@RGR`!)P52Eo*4C?mF#J6RUMEl5ZqhjLPCLY z_DT`w3W=DJMXhIOe_R8(I{5sbF~L>&zDmd!T2EvGRbp*X>`D@=k+hcIHYPZ3!_tJ> zv}TEx2BjKXg=s%uZd%z?bM;i8m|)XyRwm>n0xd}VoY>rIN_z=6%azm}v!a7N4vkD` z9$I_lT%oE}<{m|{a!Vu23*&=To3%^0K?GXD_l~#v(B4NY-JPoybH)V&N6I8L4Xq)w z4!*4L;HSz>cFtprvM^ z1y)JgCpv*v%<+oQUVs5(g5jG!+tHJrTC^Zx?>OZZ`iW=Ims06CQw|!QS9~F9I!q*Ck zJ+z;<7wzYrE8k{J88k9@F(Pey8yA5pdp9t@V;OvJd~p8GT|0iGJBXI?w7+^g?XRvw zZ(`J3MLs(sIDLBA?eizAB}bzA9n0!MyO(Fsdm~y;tT{3mxbn&Nd9GZkD(9^e#p(No z%dyWKIU{x~oD+TrrRFMk)sm9<@Ti(ABrs-%zK7~Tpb8^yWMh~4uNa!Sq|*pFBcA?i zqy;KQRWCHp5b2szDpHAO%Ct%>Ui2hcmP^YwD=J6bESi$3svI?DTT&JTotP4`?CDo2 zYQV%DQiZ>y!C#Dp79?h0sTj3=)|M=MAb~0_$Hpv(8HFoGjUGhbBBRnC{kK$9zRMFb zRiflvJ`MiFwQ?*-EMD|@)CW!8&!inhB~W#^+7nST$9|Xvajaky@-F_;4Si>|(ES+n zcePM%r8!3ao4#O&<-j|LIb^L(palu?8LA831gd&BD-|_tY>Xjts}ick`Q62fN>cfN zh+!_q!Wt*;VB`MN=r_ghIy7r-0xd|08k6h0tLv>6NG0cg&>s%A@oIB6QqudW9 zYBYb=qn6s2NeVO9B4s;)?4XXEjL27BufHSSl^s-i?5T4JLvS5kB53u^sN%@j};9)&;6DjFnd;; zLMtojMwK;1J=zkqAW^ZwKC0^G3&7pUiY^;?lyl~{j?#jG~TDopO^np?;sKsVMrx6 zB<)S0YVo3?QCZh^)q=k((xM)Sf1E!t>cii1RH7Vqd+g{%Em18FA<8u8^S_M;eIS7< zaSg5BT4v51FKXLPzZa?*Sl=A|gLT&-%KUJ`T(>@);;!8#$KOJg`rJ5PVk~UQ`WLAd zYTLQS2&LNxT97z2yjoP&Z95XE!f~mSCsA_jEt%kvH`Zg7KnoHghgsKlBv2);h}~AI zK16S6TSQ;${I0k+zAWxJ-)FWU!Tmg!N&1LkPxd^D2~>%@+3KZoS@=K;5~42HBM#LE z5~vcjv$05z*>R?x9zD} zlmiJ=iJl?rT%kquICjbLm%MX@gy`+;Yv@g&3ZEO5z}AvS0C{Cy!q!zK(1L{Mo#z}c zltoQM0##}~cD(SI!G3a(5Tk)AyGmr?1Aj|Zc|9L$9Tjs9zRy^DoIJT}JI_Cu5VM!8 z?>YV!s?^mM$BVjNB4&DaZ|O~-1qm^3x38h&L6idtRAFva0xd}JJONtKOiXPVP~{%` zh-c6K6TQA+aKyMh0x;$@TE4!eCIp{nc^Xg7iN$C*JIruZeEN4W{KAmPkdA4Z@`ToIn>xe2r&;mo`rMxY8? zCFk0T84Hf#unorYsf21tr>DqA{}`sTuI0`Z5~xz2V8=_0?!5C7{j2?6-kyI5rP~M2 z?!+w2uCLtBXGNd|31?l@?E?u^@$4n*mcf2&#j`tm{(-;blv~^nw20ZAO^9&`zoU2O zO10SUPak%z(1-Ib)iA}#DQh1{ph}%nIVDl=Akw1WwOdq2FG??KqmcyGnL*3LVYNhQ#NgqTy?J&`w|s+`)R5;#s2<2k#wd*2VV zAR$IFS@$?dpbE>U<_axH@W?5v=K~2;dDjwb4aB_7t|jSv7JK=)+mX zar;9bm=h$N6&<$^Bv9q7`?v{b4v?Pe%%g=$TtgrI<0jC8gfr8Bkg!*T(o>yPob*)Z zNplluLBd(lc^H8zXJ+XpFu%^4j8NJ05;uVsB%Iljn{Y+|>8Z||j8Hww)kVTtpK<%Z z-$Io$vwVEk`BV{LFV#ga zoK+lm$&o;ncbkY$r?ZOls4W8$&iafySJ;-I%2}&%6KFvKpMUjQA%QAqEyL{tTV&_W z#-sKINI0W&w-3A@sN(-GO5i52&2ZM1gz8bA48TT96Rs%iKwjDl?b)FIqud16A7^ceuXN^Heb@aE zK5PpT&Z?2y2NI~l=ie!}=xfn}gtN}%_JIVduvJoh;8>JvzE6(sF}EtATAUuhS!Z(R z3JFxHPq5>~9%YFCBYw-Clc%RT>oaa2&ia)YC)n#(cF$@5lK3zGVRS-zs zB%GBgcdn2?m9xg-Ca{FgI@6=(3JGVO$?XGkg(_#A$xYzZMcP?4a1+j~Iz81{DH5tj zX?KxuR*l>~@V8KfZN7cK#eZXTyzb6Q(W72nB%DU>ODuo zS!a4!u2j{d)OIACl_|FmtnH}6Cr!D!6c=vq88gxxA4VGglGwW_($1e9naLI;oU8C4 zVb5iaG-oDkq&c1g@mdSHSzzt=SVoSaJLVvKd2J- zCUdo(>s6@aXc6~3b5)*HkCH2uuvZNqmMf=4HPW26(oJCf5hc%j@A!yy7YT81GT$h2 z$un;wMwl9DsB&6VcdpQa1lCZsmLP#Dr$x>55xO6EO`KL+s2=5hs6^=fm#gIJZ#gP_ zZq#z97Kd;~HSTNWta$Jy2!~Q{)aOTl&ANX6S!ZJx8G3*KV4;pFCNMHQ!qqIIq zIAb4ouJE@|g<~SM0kgGe~5YVKU&Jx7(ZKIbM>i@mBQRQ4*~|4pPDq8)VB z2Hb>daeh~niFX4&j6jvM&fq4n-Nk!@wMV@ls>P`p&f1yV2NI}Kp904V?gli{oY~!@ zws1%|GfQ`_u!Tbvjv1XiiDyt)?4FDXvFF3imE9^ijNR_C1qqSE%qV86G0vY#pvrk4 zopm|bhv+lx9CBa6IdnXTa)`b!GYVSvwN6gN-OQ>STr=3>yyrC1oK>pKT*a^_d&a^9 zs+@HucRA34gs44sndGmBd?0};XZ^~ZE3_cttTVcErCxVCir`W2xf6H5JvF~kbo;=5 zQ1s5W%6Tj2Cd4?J_r9q!Ix&8z)${REbe0@AGo!3TvDg``Gmg z%ctfFEl7xQmt8}>2~>%>p?yVE0xe<|W?vultrBQKLd?9gE;$ma>QSC3B)A_;H9{lg z%&e(T6sklonsu(wB6?@L*)nIKNKl_hwItPeuw_63Rn$LvhXLafhw#Eu3W)2p%DP&-MQ*2fmas^8V!WnN^b&HG-e20 z5tYE_nMULx6<%qTKnoHyBKOD@5~%XNgIG(b=M2>h^_QG{sjVmyG}eYI?M0vp@2sO2 zEj3z@pgDs_$&o-6)=ys|?ODimCnd>lOf0Rc{jTR(m9Gu1{G`UAINT7U)hkM{$L+`7L1g*At))MEpRF(Mu zhP+Q%`CtnY!k<0X@+MFv?xwv{Qzg)Xgt&&zNY-IubkUyMqY3fcIpY%1?q`dUb znz}#!C}fI4#tez{R!X<|R?pe@s+8dpDJe}vY0x0*t!@{Y5~VVPG*BW#-AdhC_u2Pe z8A66sW**`dB7_k7ueJBtXZ_C8e)_wgkN3a+t@S;>efBBURMv%WiXUNg8pi2Wu`pa%(FuejcvoxmuYy-Zho_gcQL?6)Sl zZ8ufeZ%zK&s{{!iwe7bi_jQ$E6keh6^RT_hmX~|2oUOD|oWS-#f=3Kj)7c4(!YeeB zkTnC(?QT5J-sb2*f>+4?ks673)W11%BeX(ek$XDj+QtKlQq<5o3};Qt$zswiRpinQ$Ym~X3x*K1l8 ze$=_r#xNy+MH)S_&y-d&`s|CqC>gsl30arKOCl?dOaeVvLRoQS5;A|JmCQIC#jVMI znFM-}kg;T61V+h7lu7W&VE0JUO7>1%Eu2cNnn}n$Oj=3Ku`j~bk3AL=lD%YVAc0Ym zA!QP>JHY4R^0Ty(Y$=mK4-%5~g+!5Q9NJ69>qllzcjmqp#47^{nYA-Zg#<=rzpfiYt!NSA(O!NKtfhaAyH(@X1?nj9SfsmCd$-64-&FE+ZPd!a%;v+!j_%)6YSaA zJ(9FyJ^wdM(Sv=3OKbP6GtV6Bo!i{56Ww*i^^;jDY(XSs?|okcM#)}(CL#9n-9(e7>qyEhr4hh*0$kd>o6s-p_3fGV3oTD?BT^v4^+qp@ry+$}& zRdkiaJwospob@Zs(P)WLIJ$<1H~+^x`$6YnXJOgDN-Nnf%RF=R$etWWagF%qbMzp= zYu~Kj*^Z8dQM|r(>)`l#poiPQ-V^+{r9#5CW;ve^{U?9%y22NWcjDsf>o|dZ8wt7dmwDz$V3gd)$s{nBkv$oXl715}6?%}6{h&+@ zBrrE~j^VNoWAiqI_=<$==Sm3C@cAy%vdhl)IOjc^)`M+4i?1PJFDCa%GO9GDdOB`hRZ% zkA+e35gaw*{lMJ~{kMHk?u@1tuLk^eg?$jCunwh6nWGO9ysB}nnVpD7xu+H~+e7YW zrxoYU_E{x2pZjJ5EH4tAx7+8IGBuFEC|qmD&I6wDN|!@lDTg%?+46_ac%{o>|Em0v zjr}TZ+}>|zx*cKj#U!_q;djy98m?Rvs6A*0FS;`L`&X{6${}OTAh0B`^4>?Ou)Ijf zvsjtufdod`e>W|dQL4Bn$_@CPdbc{yAkYIjPIw;wp9T`p<{27TDvW|FCWFA1g6xi> zq-7KE$1NxxBp{p2&_DvCAbZUqV8_c`yI}@d4)c5lfgZlv9Ra%^`yenX`<2LN8}@BF zRx}!v!zhuV0i!eZ3HJmQefdpRXBh-);Bm8;3Oz``XqTaZL_A9RW&-}`o0-s4VePYz zUW*z?z*=h`rNSs|Stt~ZC0JK{9f#{^I(UGY+ZI;j6cx?8 z83cNefK~rK2#kWvB7?vY0A`$jIr<<0vt5P;jy@O#tC|b~J+NB(m!(1i+bIEmMM1n& zcxC*X_Q2z2Z*y!xjKV$-g`#U0XJptlp!$)~HBO)h30M;mEr0Qm8l!M@m3W?=(Sro* zh5MJ~*$IroF*r`Z&Od)E%0VI1^aUu1bSen;9r&s3D|SU z(7;l~qoRF{eGsryNKw&VUj~65B;dZtK8Sc!bT7n9C`DI2&1%v87XI3s+auctfl=I= z;qOmo5a>aI>oCj*GYH55&C1d~^}s8=DBI2;&;$7=MMXQ1`yeoiXHk1se_tz09_=K` zJq?pd;1~}3OyPO>)`>X!AOU%z_dM*eFbXog3<5n!;5D6qKlAN2ms`eq5oC}V8t921 zH(USUei!~`ZMp5i<+MIEUogvZmEiS*1dkHouhC|d3JHwDD-=$gMp2%T!yRn?3KX>Y zzqt~T;I)K(k|XmfL64nfiWHwYUeobXp$7?`ulyQFU=-{?lb-yUueU~L%WF|N?!P(n zIKeZuJ15k@QrX$rM%j6uBQxtN?vdm2`aw#F8c1MNyayuzcfiYewd6)0Jd(uoT#Ftg zc%>HJ$1BfHV3f`D%-z=v0`}p^6Wysa{n0;);?<4>&sX6uDQ9RPfl=5ul}kCdHfiSRdzGfIU7M#ZmCyF=u(-1vz&&jBYw@&L*X+30{cjC-bZ=@}MMH)Rw$SxI^Q2y}lYg|Ldl}rLX zs3D_ICLyzd`L;-Sy>e7KEKMeX9+`1eh4hbo5f~-CE0d626;&bmfU5;wePj~$Y^?_g z$t?CoV3cGpnS|^on78|>&F3jDiR3<+1bX7fb-7w5A$xD;3r%5O<2mypd!@v$M41g7 z!BKl@!1aoR%tZSlFe>|XB^d-COL~;7`ZG1+9w98PRCFFid`{Hg;fXD$VWVW#pQ#b| zxIV8cWJR_w0;6O-mr2O(kgAYqj0nnmG}xkavV37aAal+;+Z2MyN3HB zFbdmA%EaR?9#{4+>`WcLn~~8Tcw8i8CnU2}NMMxgwqz2r3g3Hn_K$F~@{SX{8uEp8oae~LL@ZHyp>k3C1jKWbVUc0hK#u{n*&(37B z`^En*e?>a(5kmH|G6~e+^{#yXNN7>u9)%@ALhk8gY9N78+#dGngiHcGwgt2j=PjY0Q2ObNfaNQNJU0k=z{lR#jj}y37M?&sLW|j&G zjFS7GnFMA(vNOR^>F^57B+!F|Wa0ZFFiP_1OaeVf;OZk@S4d!#*bpy2Op`@-#$dsc>Y#C@gKfROms1*IlkPvlH&O4I59^IgZ-CU6W)$D(gb-HX&P3{_ypGZs?{!D82 zp(FJJ*Kcl(9wfG0RyFwfgbk|RolG=*{E5`n*N)QFzw5smqrQLWpX3>I+_94i^5aC) zVb7#Ck;b0Uw>L!(5}QMf>kA7=Khj8W=LSvnms{KcHerna4c(7|IeSP zFNmnId;W6tAW=$0iin-VS)*?2!*%zMyXhZKekev@RC7Hzs9)=4_0KTY=>O+QdgF*L zy0q&#ZPA0oNoqv!)yS7r_n}NQZ*#bQ?4xeF#)?EKdXP9EH8|)<8kb+qrMjojX?nzW z9rfMoj%tGhMqRn-#^9`%)~TniV~zc*oUEG->7s8w`M45{dN&vmd`~4=KA<2!P8`|y zG+mW6_$o$^k2t75m+HycP4xl&TJJ?TnxjtYeQyx7C|8H{=Tc23q8<@n_4#W#dXU)G z>)xP%h_O9bA{;_F&-FoZ!&5*#T{~kRvcu$TJm0;A9RFbEtB(*Or$d417Nu!uFdN*5Aj2J90 zpuTR-*3^P`iem&u6<1jny!T+Sy89w7RWT9o6Vdg5|5POK)4e$Nd~b@}$*<>)~oJ#bBsM;gB>K99qykJsJ$bxtK; zuGJg~jLNT77QA)YVl|-)pT`e}jn_{O=$!iToJVuelS#Zu#HmK(v37;J{x3Vq8lBQM zMlkK7rZ3XL&Mz0JW}R7MIuYAHgV&V$)AaNTJr+l?QeU#+$X#B+_J@EKlYs~sYCv^$P5oVKnQ&3oBgc)` z+rgbC>MstfmE?Fl4_9y8&d#=1$w9Y{(|wK}XbAK;n~95xR|mDW&QKTTbM5|o%Q(HY z*1+U|bI)1fqWD-Cbp{bXeKA8le?DI&XUrI_w?8x|+2qkfo1+JbmDC?w-9IhtwTBUL z^Xxgv7H|BTg9Jvg-I549GF01dfc|IvkI9K^XO?Ih$$r{%hvJcJck;QQ-FtVdA1)q{ z-~0Awf|)y}s4F`2d5nH?sGg`^OjhgpOdIqd5!YCnbFJ?3!AHq1)t)Ow0;B2&&jsB` zukc*fSWgk2*2=Hqsw_LxrX@kUoZk0;K)Rv+}mN6Dq9jmdRU zd@PK@wn-$u8rDd6YTZ8QdB+naC(x?s!7(=~UW@F0<*uON=@V7&s|Mu%x5^#C5vlR2 zQ7=C8!fHu9GXq8&{@ldl$of_J_#vK*(4UYbDq*^k9 z>uMihj*4Efl*tNeS_UwN2)5N&wr}kh1J54wCU|RJvJ?r7YCw8_klq`GMP-;67TOQdFBQWaMRa=sW5;0>kmug9?xv6IgMhE4WzTFHxNKB_XtVMNbGssU{ z&P}~ZME(VPijlx5to1}+@=PNy0)x+b`O z;Kp1eFbdlykvRH_<5N3oPYmjn)s3BbZi~ERvlsiR6*CL+vECAiUhix#>)W|7SiikW zDSD82Vr!k`=Xdr~FWk>{)#mc!Q;Cx%2K^iKX@dkto!B}r*@pD4p2O#HsJguDp(iE< zw>Npc1U*P>YtUpxBGFIPn#UT)6m2gX-lZ@&drFnINMO{c&+8;VrBYozmo z()eXwx2EVpqGj8|nzP30r2R%q!*88>;U&m)IV~uekabNGb%aFjRf{<8J z${L%yc1RYe@j)rzJK!j(s98Rix-uk2Z=K`EKMCd zYk(?#flJk>TZd#*()jX*WE&(fs!omhsoP2KtQ42(u+kaH{Byut^jO6|KV}chx{c;(4keDB8 z{QVje^Lv#f?_4lE*l~A_V)P&}@bM${*iP4~TVLW*_3B-cyqbuv-CkIZ1V)|n#F2VB z5u4s*jV-|!$u^4y22a#%+8jMd=skhHo#w8;-)4==)fdU*i5N6;=`tiRDisoEe#jb| zU#}7r*61DVNxZQPqt58vSx-MXJs^z9+Xq0;5`x-b~VK`!Sd5rRB#4OIj2JTff^~f*vF~Z@N*>r`1Qr zr>s$9XSHDKx0eUiXXmy>0;5*+xkxXfQvLo3YYbg^Y;aTag5cKq+nb^Xi7uhW3tyX3 zEjTkM{%>9|cWsp%^dNCql_GuE=&`E$=Ul2kh`5c2ofqxD90`mXKtv7^yS`zKksr4T zKB|)w>P~x<@H&*+0!?xtG+A9j}t$i(K%>4=ak^UPv@*g4-!KLJ*X?j-=dz|&ZU}=-!WL& zkTg#EwKWnLb>5M)HvdZ;P||QOVNYGJDnEkKPbzn@(XKJHs~BY z_P{B@v(>I>iv&ispi(WPQuY6pHJ%|2b@&m%hxPg{M-LKg|4ACt{$gU+o<6~=qjx7~ zpWI66=Pn(26pz9e?tfZzbYmB6!t@1V%agvZ_}RQTFVJV9QO<83H}d=Hs6G&Ztv%%8wJ(NMqDPi<85ez0wRlNc5#r9k61W8e-04)N><( z9iyL1-dbf*Ya}oVOPff1_|K$Z;}bL5F5R!NEoJnYcRAiW=&JmK{?WSTjJawH*?06U z(-$A}kUF1An@HS#;H2Q_JBr&^ym9{u^dK>uh=xQwRE=x*_JRq)TNj;`Og&IH2MLVA z8ljy6BJwUdD_Q&OJBrbhNwlCk9Ah+g)fgLG@ymqd&I?|O5lp)%tT$Tw)an-8*Y613 z^4)%=XCMBct~I|*-Aui6I*kSo(Vi}k2Ak<>KY(^QZI7yRTF2n+u66bEi>I_j4-)fc z%+fusO%cJ@?o_I)A14>LFBvkZ1kar7syfx~^u$FJCACg-)SgMfcZ+9GTkxNFe8hc* zE~OT%uHINf;YCO|o1>cirFFg8^VDW)%|xPvh^=?OvF4ebHJZgeR*#8BL<}Hen$g(! zZDH_q{k3Jk*4(uM35=T7xJ=J&x>((8+9O58(k5%mE@+t796d-B60wSiX6CvYaMpz2 z&kN2@U9-DwF%lTnky`V0+8wlQ9uRTH#b>AZ%+cc`xThr&hyQX@aM|j@y$DBhR7$VZ zqsBe2em6bpC?ft@RhW9E(QV7ogT#6w1`{#M^z&Y$M+Q63csf<*e?>V+U{t}N75bE6 zOI0_caW@g4o&I#HL1}~K=s{u#5r+}+y&2)YdV5e%^P5enr+U?Djs!;ivGPgXw$Cc1 z%qV)wJA;Cwwrxt?^z2k?!c=6oe$74^`yS^B|8po2iXU@`pUXxPi(wYHBiA3Vk z+8u+nJ?rWpN@wSw2Z?FnNMu(s$NslfQ16Z$z4^FlF#@CBdZkb=`{qUUv{@~^Ma1CS zbM${cZm|+QNaVg&sD}`t)7(GKY<*_%*_J%ru==^pk-(@+!@9DozP4@741U_2r!T&) zN)CFEz&fOCyXe?pP_F|0Nx}A}NMO|R)dl)SYNxl%T6FV*YQa$__0;z)O14E067lw^ zbK{I;_Y249%g?VYol$FP>gm;Qs)s4Vx`;A5zR%4W-BXmY{6crCZC3Q$B^{ERgYmj< z)1htAgT&u!=cPW}@usS4GOw8XRq8no) zV;7WQo8SA=yi^&r+M*Tl_NRCLPU(<*C4ao`b?sNnu$__MOrNh9yK9hodRzOIJqq;& zN8K4CFzUN=A1|B#!&~aR=XeD$ZRNK1_Ykq{r}I~$2Z{5pdA#fqBD$L0k8$sO&~DSV zN%}t>Z*Pu7Jc>rl#M|KxOV6J_Xt#j~9!2@zoySMmeV^`~A1~|Q#1IyUj%8^Rb@~m- z^;f;6>ORcpF^|q_01@3b+`T*z^9V7u?hVP;h!{DY$C7tCHAvlm{RBO2!;vupqeh3% zo$%fw?Jad~kSZi%TcdNEq6Z0lQYDc%u*SI5&-4t7UVLASh(&eTk-VIqXF2_D)~I>s z6R8{CLsk3O$45tWsHBn!v& z)dLSYCkH)9{2me)cV>-a>K`5)@pU)-VAVb`0;8(jH&{P#{LAXWj;ztSR0Z!(s;}!$ zIA-}Qnpqy8HSW&b6Dl7F?bq5juAH{>9(~9q2T_tlD+pQq}HwTF@oYNq^b!#8MUsL00}p769wZ)HRiu~9c~N~F zu*T<$n+NapYoXsPIJ7kq7=^W-NK8CzK=Ad&KPF$Tn{4wwWhQ@79{z0W#+Bn9ct&sD zHAVf=vT@}t4W7~mUT~NCUvt(d=zMK(bKytH+uvDTf*vH!>-wCo`}y6fh-lgaSUfm5 zrO7+VAq_f~B7spaQMR2&*>+`9*4R)yG#GL4i^B?c6bX!Kc;Z_9M*j!YLrwTRR!$igTzl`;$%1N+wLuROE*Bl0!x}Tkj}N9# z4wBP4t!at`Msc3N`RBz(WAphFgKvi)oxDxg%|QtC=70D{9XI; z>kcVJ0;6^;*ZPTWbJWbnd>)hTD-3?@@_zfiJJyz<2Z_FQw0`CKN7NTh`8?+TZ&GmT zXItB?+jCSd67eXT8%{79_LLt<_-FH+vfA`93MPBGMV~*eX1!Q3!_dsd#xTd`6)HS zwE2})#|Je|>ymnA!IQ1ggT&XDtA?ZGPSC8-qdP?n+JictZ&i7*$WN(AAnQ zRZC3&IHDolxBK(DRMp|Xm7)iU*9MmAHMcBLO-=u(^XiCT=vU9CZhviaE)p2UeN)qO zOSYf4|LTU|*#F$0+Fe+y8G4YYAfkc@+t1&=d}vT}?Yh*X!)`MD+#L&}^4319-yXg~ z&2Prn?j;ut56-H!CUw%MHA>Ng#C6{;)g2ZUtJhobwR?JcK=8_0-=|t8&do&vqdumw zvI_0uEN{UY1?>k0Tfg3#I%eC_V)P*K5fN31;L$aac;$^Ng8Toszi!j+ml%Oj*St4h z_k6cRZEwjMkB;gURNqupFFW9_)#yQD(EAJYgTv@4y*8|I-2mFpzwuc8b*&z4kiaOM zwP}uex<^p|`-AmaPo1^~JxEMnI8QI=QmW3*WsTfhFASP2JWiM1bZTq`fKfQN)6-P- z&I)=?YZoM5?b&8B&5+N~9R;2t5C7yYeNdB$Dn~W0{PeIp^&9yU)VJ;V%%|2$1|N)T z7`)Ju86bR~(7No7>w3Gs_zV)hEx)K?0-r{FvbN3ax#9IxpD&u-d_U zV;;*v4-(14=ji9Jnyl)zWsT!^cMfiuesb{siBGmc0;8s=hxJ)QZdLoWVT~8p^#}^r z9UR=e;j4h!yo^X+0JFp96Ye`waWSK^yb_6^q5{v%nt>M7>B zavmgb4o)OKow_l3+!cd^dY>Fw`oV8i_3Q5sR4-g~Lgh&n4R!ar*QsU~Hm>}h@C?4d7CpJ#GKg)b}R_I|m(=iv&h(nO!BB=-E&0>CYNnn}4$Qc)CY_ z%_VP_pa+R(R?l0>clF!#V~twpH7;AYZc=dNgR2@Nfl(8$ook4>eOTkY=X!5bINMO`}gI1T-ZPZUS=*=26UfbS& zJUwNx{G#tm(1XOgi}O+^uj{9p_hOBWx9@1*CRrF1_uCyKFzR{Q1L#9-)2#<gT#*^@q1U+m^1nL?DH6!~&ud ziN^}}q)z|f%3#gbb}<5@h6h2grF^IwWHgpE{36wK$-v;{Yg@NQ4-$hX9~pEy=UTO5 z7;F5m-lwVO7G4w7ZTmh?prYl^}spI6fv4d;U024^Pw%if0^C^6Uw7g4%;7tE0x9P&v1FRxonG z&8lc@IS0^E^mq+BpxMV7!d_T(;BXNpeGM(5KO)H zKRHNX)P8;L4nEm6QN42`YaF`1m43fPPHed z+HPB4f&@lQqbEa@KLdXSiN{6)dc`q!%wqxd|2f4Q1oc3{t7O0O?Vk-#YI zkMyKd)v>zAn-h~??)PD9%DjS>lvRH+fz~@8uMDa_I$bp&dqKSyf^8e8tMA71nLqsS zNIj*~Q^{3Z9$JMSB;LJkMUeC4G*yjgdWv=JNIm@4#mV&(*1v!RMp5n)@b1T2qcL;- z2>oTLeR2RjKH>nQQGM5S`o`dO^Q-|9&gQ5i1}_P|?K?%4|Ci4r|B%7@s_)-T?z*y3 zE_#soq}Jl#uQ%>grT^vgsBGC^4;j8QdEC^`RwIE?pV2eviNu|%fzkNm+deucwL3ZN z^yiAvgG4$c?l2l3ywO9yx9Z^FpIM7z1V&*`qbIhScGLT}JR&%=akE_XAknf@ z{lLplDM1esS8dZly;~ns-x!Ve{wbsfEL* zIQF!~>T^@Omo}fEpMJJU>b3LsD@6|yT+^@7E)I_v^sMtG6ZKtdkK#Mk3H0~~+vbn| zb(5ZyW1bv{5sv1lYu{cOG#&Q5s&6y~?jEOmt?r$gIAwhIL4zZs-c<2R-Lm~u@n5*T&!YflDMFI%OG&B!o) z%hh_stzV^9_n1_I9wcm^UmcD;X;DSD6?*nVa(_|261z^oabt#-WL-sVDmz$r7@JaqG=!J#!?ReMIBQ2Fbp1;L;Z zuc{$5_wk&__a^M@ykY9Gy4xiMdhELG%g}=a&)Q7b**X8#GxhHK^YnlZs}v)FQFknw z6ny{oiz+#W&pa>hOntyxdHRd_=dVH!5{tGL29NyjMfHYR0c`xZmAst1w63wBg59=s|*4HM8ihlU*&{ep*MJcS&76^tU5gB7sq#JUT0Ad38!n zH0{ypgL8G$zfaLiwq3Ov35>#aqU>(){M4?WM(O7!OwB!N&?m|Bf7_sL8+=0LmHA7P z`_aATXK2Ox5v_Omjdi=;&6z$Ubz7G)`qfnpi_wF`ry*h2)JLDSE_K_DL-lR%4~!8Q zRrN`uXXLO3;JElq#Kr>3_VczA<^!`~}tY9rPr}Igia-jRZ#Fm7hpF zRexi0>4?F4%Sor_;JwtJ!n?1Wnc|&Tdi(6sXOh>{7^$C_aiGak-91_)Hk|)Y>b>(e zs2eWf*sd|?+=s{xq z&L2|8Kej=2zmzq~dbLc}-!@)fa$K9XNMO_g+BN7(&l=c$hKkK&lMh`wR`=5PEkh3y z3q!*0Gc>&K;N&;YPSh{fs}mzIs@sz_Q}bSZORcr#pyB<8$2 zIu%^~mipN2WlWu&-~PLmlk|yqtt^b+sf|ys6!razlWY2n3)Jp<9~Oa7*W*r z4E}e!w{+*6`^&aoJV}r2)MNn?35a@YW8dU^6R57P=JUAxln>X=rzarVJ#xUBm4I>*W(^5D@6|yxs&H5=luAl`qgB@ zuT1He`h%W&`RMa=VgyFv*hNoA7Z$glbKoRe2U3PKyH-BkkW(~=^6$!owyL17L*>gC zt&u>FpWttc{BY~!!Dq|68Vw}GRu%N+rhNC6?l^%SKfxLo9?&9qc>fkg0|~KJ z1%2NsU%usy1bX}gYs{o`7)j^CZH|Q4s)D{>MD6ds{*45B`~+)MQd`{H|9z7cAtAQ; z+FQPSFB}Q_vQgym6RdIUxi7h1K#nLEmVMJbr>T7Es^Fn^HIiBO}A=0Vm7=Rtccq0Lt|qtY6Uh@h_%Mjk&A)>Vq;L8F0$*ycN+ zQLUT0iU|6iVdU`>tU)c9qIuA0AR#u_)v?jl6DQE)Cs>27L>*qcR9A8=vCY@5qh1gv z=$pHd$4{^Z&4HSFl{pV2#8wsbz2B%e#|iZK3D#)4qN^_2e5BDpLTpt*U%I91%8ge@ zpvO%xRg1$Q#dHe)x&^)MV9^`R1frQwqg1$%_%@T0}J$`~U zZl%7Fcc+=75=e+`zKln8HBZ?-hy;D-F7o&Zr_t|DJJ%v1wmlD-&soC}d|c=86Hr%4 zt}7(Ow(TM7lCX9S!S&-jeu6b-GqNZ59^9zVev;guNhc_1OS?H{sE zM1rqZ=kXJ)5%xi&frQw$pUZj|3GR2!<0n{y*3{aqsgV%dj#sj7M}o%>=kXJ)5sr!G zJdhCEj=Pe7Ai?9H^Y{tYpjnMaYNLUK*mnMqJPHXO&z;9lum;V8JmVM*B*b>}V3CUE z!HBT)lJ)qBP@}!mpt}gvYu&M&tt#j%l2K`+xz>~_?(q>}T}AmI5@M?g`nF|M>(QFQ zXrRYWutvC&*^3aGqv}OhPn6KqFxXu;vQELBv=EpJ0!$b74!|; zs5i$6^!N$Z!0ZkQu~h|q^_H#$H(nuu9zVevnB5^Ew)yReXmpJe^qt+v<0n`H^FbuU zHos{R%@T2fzW5$_`~+)YK8S?a9L04tFYJRzpvO-*4VT>^A+|jam-X3FIf9QX9#;}1 zpsq}=hJ@I*JzUlo)s-Q*ew@coum)y#NQmvOE4RKv!nU*Z_zBj)d=Lq-ZU1mtU!36U z)p`5`YhZSVgxI#%x~wlwaKCdNKfxN9-60`1N7aLMI}+&e6HJF=qNXK75fWnCao1&i zae~J|@wk#8!5Wy|AtAP%KU~%qCwM$}9zVevm=7W$Hb?R7Q!eu$&uZbBi^ord8a#6{ zL4QJsO>3WJ^`p{8v$G-M9!Db))>V|T zFuOxSY>sL~bu~}zoe!eNPdE*i-60{iJr9@l*-|-zk1HNm5+tCmOm>Ha*tR`f))&>T zA-H~=$4{^ZW_L)4?XD}gzCyybv-S81*1+rz39)Vea9LlR;Oo_S`~+)Yc87%6w%59> zFHUg3a~?mz8kpT7AvQ-ffOR_(=$1K$!Q-HKd<1J?c87%6 zb~bQXU!36a+Zt;&mLXH&cA z@e^q(S-57{ix4`kcz4*=I%^<-9zVev;o8S&AR%^I@h-RBO<)Zq(Bmgq1M@*7#7-;T zt+%~^HIP7$pI{Bl2aymvt@y5k?ai!#1bX}gYhZSVgxG0i@1F3e#2QGT$4{^Z=7UIx zomOyHjx>-!kDp)-%mCU4X&`|fKjAc7c87%6 z_B?FX$LGNsj^N`ukDq|LGT9vxV%zqxSs&DuA-H~=$4{^ZW_L)4?XD|cU$F)fwwZUY*BJum-m% zT}1?X`~+)I3wrJksyv~&uG~Gnu+1X^J$`~UFdsxh?6l(Dde;l$1bX}gYhXTzgxG1t zcO6`BjuYtd6Rd&R9TH-vmA!l7#w#Sy<0n`H^FbuUPAk3(8kpT7A$D5v z-7Ggt#0m8H3D&@T5DBsQx^i~``MN>^J$}Mzxa^Y{tY!0ZkQvE6m$)>lZ_cD5cr!5WwkA|bZzAF@tFg0ENS z@e{0p`5+Qv+kP(VT_m{QIgg)U4b1M45ZjJdvTjF$#}DW66RZ)Ai6%EdLTo$kO8$Wa zkAu$RCs>1KH6E#r1`=Z1`9tz3BzQb`9zVevnB5^EwwniwC_0=6c~%S0JbL0Y&rgIJ zQ9dXcBp)lvGZpWuy3$5-t&5=NlpKuy3yF)^3dmb{MV?M~o6^|QtryF)^3+a9tm32WC7TtCj^ zCs+fsJ0!$**OgmeAz|Cudi(@yV0MRu*tUPjIuQxJUY*BJum)y#NQiBFt*m#E;C|;k zeu6bHyF)^3j*9Ne(RGCcdi(^_;RvS_vHOEOF1h2{aaZyWBzPPYkB?vt%*1QgXrRYWum-hYl-(gAHb+Hw<*2TZK#!kb8uLLU#7-;Tt#`d3PQ*Q~ zBuKCZ=7UIxomPC;!S&`ifgV4>8kpT7A$D5XyC-hELIOR0f;BK7L_+Me;=4d@bd3|} z@e{0p`5+QvrxoALl34-?^!N$Z!0ZkQu{kQbD@WHA66o<0PQ&GcNQiCEL*{eL2l=?- zaV0?l>dItyNQiCQL)Il>T^WMw$9en&YhZSVgxK!7a_cK3Y&%#--|qcf;DKy3EUiogxKc2396BKVO=3X z`;?K#PdJV6-Hak6#J1;Q=W{*})^G$L*LnN|)RoEZkPzFphh3LIT^WMw$9en&YhZSV zgxK!7;`J44AYt3tdi(@ygjb?Y&_IQR*tUPzbs}pZ!Pl$v_zBhsdz8^YLTua5?Ru9r zkl=pjJbr>TFuOxSY&%}Lw*=z^j~~wCCs-pK6U})bA+{ZNZT`XMfdr3(&f_Oo1G76M z#J2N?&H7ja2_Da#$4{^ZW_L)4ZQh%po>s1+_a=B&3(uTqHS6&cp+=Ms+L_D}Vk>@+ zJ}PZAJF`XtJ$@prt0*5tLTvLsXH@IaD#K{d{nN}1SOfDxB*ZrFZAYVPoS^3TXa`bYPXKtgQW&t<)f1ou1V@e{0p*&PyM+wn@)?MU$W;XHnVHNr8`oCgwO+i_R&4<$UB&GXbzFNhPge*qp>5+qmyvpXcjHqV7ey*Wx<`ud|dIkk{|(fWwJXY#J26>vc9OU48ir| zJbr>TFuOxSYO zo%8q!*1&ua39&h+q@BSznys@!Wa*1Z!Y+hlJQ1 z<+3o|dqo00ej?O}@Ea55>>Dx_aX`EnGX1M!5Dd8sahUO+-<=%k7>vjuYq++B~`Ju0+znd=Lq- z&GXb@FW~b)g7@)l|KQqnB|(Dg3iClE#7^^j6Jc*=4J6RxCs+fsJ0!$5&$n0Fe2_Je zu=iDXyi$37f;DJ_i=G!nLTvM#emJ_a1`>RK$d0=z&rh%h=7UIxZQdRTX9?Cog70(L z`9tOT3D&^u4hgZ%dlOVw^GuDz3AkUE=O>(o%LkDV+n$Hb`uIHj_Xo{;6Jbe^V2$w1 zO?Jm6amNzdwujC7psozT_2WE#f;BL^LqcqKUGe&gHIT6FY(0L0H83AULTuYVY}Usb zNbvRQJbr>TFdsxhY};#X*2fx1aKCdNKfxN94&4c9>Vcvs`N*m3!eCBX}FdGrpRg@3%4y`+LvCaFO zQLUT0iU{5}cJ1LOSR-8fm{K7jws|i#x_aUS?|-}N%1^Kc=7UIxZQieqdO@7veSFtH z`~+)YK8S?a<~`x4H^&LSAL07BpI{Bl?vN1Myzg9T^Fh9@kg)ev?0DrTSOfDxB*ZrF zZAYVPoZ$OIZrt?~tby4b5@MV8&!aIvPVjv$Hyii~*1+rz39-2ky8DA%S4g18PdE*i z-60{iJr6f)$MZoxuJiZ_s4J7*AtAPH54ZY=>dFvYKhEPPSc6tF(f37>5Zhf>b`=#T zY&%pJ0t}C9@YHG)F~u<>>s7K#!kb8nZhj#5T`UN4+3U@IJolAAW*0 zFuOxSZ1Y@r)SKf3-;Z$p+)uCuW_L)4ZJuwh^yh>2zKR{M`~+)Yc87%6<~jXnbd3{y zf5?ryeu6bHyF)^3^Y%bAOT-Dj&*kP1KfxN94G_bC(tQ3D&^u4hgY2D!MC2 zr9}cgej?O}@*s!gH88tFLTvNCbEQ8YwD(o)c;zQp1M@*7#5V73N26<;;QK>v-1QTzf%za3Vw<O6je zH83AULTua5WmSs=_dDnD6Rd&R9TH-5RCHI4t}7(a<0qI7$HX9E{_t4NHt*3#Sw@`T zanR)-qK5=)V0MRu*mgGX=Yw#+F3(S}24;6ih|N(h3(L$0(c>qW=C99Gn`D1iCXslx zg7QlGSN1qtvVqnOV_NCjld|eSz{ahZr`r(_lnRXw#pkeXG6uH zhIfS;*$9jhn>BXQ`-AkKrm9MyM{Je1YR20YcRkxI)W}9)l-R8CJH0zdB{Lf65u590 zQ^hZ@ZlF<+?QBFm$`PzlK)*fscKAD362%@DrSj&#_Fl!4=d=kmvJn_1HXmt+{as6Q z9_SHU<(;_sql#yr%cb8Br4zH5_sDke8p3 zC_WZOvCV({@BSXeckf*vOqWYv;pYId5f~*lAIaaNRE0#P%cZZdMm7SY#AXeDk5Uy9 zl`faQ!W!8Kj1rqQ{5?ulNL0F9`U-1gBQQ#A*6{ZzRUuL7a_K9qk&VD8v0204qf~`N z@o`;WVLKZUk8%WS_k@gam!04q<)Xx9jdy7tJSY6!SM-SO`pQ9}MmECsC>td`^qw*?G`L*}m-v?kn|QIy%(IMqrfKMuX1b zyYTmf(IYmu!KRAU_Z{yvvJmkoN3h0~)D|14P53+{iajpM_LZMcI4RV~MsSaEQDXCv zXl)hkx1&dFRl$Abl8&c@8rcYp5}P%Sr+IKL^$|J=(+BObY~PmSa*sMS)W}BIKIozx z!5aQP$n&e~gJ~sw#m$_1_gcGRwS5o?K9au=#tG>wtdWhtD6v_?-=pjr*Y?`9lD@(k z*$9jhn>GAB%B^v^*QOQpDALGAV3gRb;qOs)jT`nyC4Gg@BO8HHVjB%_kFslA+qe0+ zuCEx4EJQrY5v<|wQS5P1X(fGyHL?*HB{m<)-=pjr*Y?`9f*wU0*$9jhn>GAB%C2$4 z{z%7-dKB5&hnFsU2e6S)rK|M8!5}S`iD@#ph@AAPg z%B*oCf_hY5m=BUhHUgu>W(`_dYRCt}W0^H>bX@9DbWSE8B#mqYMv2WDoI^oA7#_>4 zaiil>kID=4LDI-ZV3gRbK|M1@Qq>+uFeiucF%^I|_)Lb&wK#$mp zj=L!@%m>NNM#Q5W!5Xx(OhG;v9*aFL%FKg#VLnJ2*$C=)QIyzxBwATUPg9{sY%>q$ zh4~<9WFx5GMNwk22CXd1ARi2)%sdzo)L-%_A6#VDaE{n?#w%yUkA+ce^B-$)AB0(r zJUk|G8*m?F+xC@khT8|h{mw;+%}1hHO~YC=jIw>(5!|D~`HD2M5f~*lYtXEwVJ#XS z%dByuo!++Y!`9 z^6Xla>na-&k8%WS_~$`I$8__cSy{TdOJyfu?&H;~o8jn4{#nheMWf@wtVSBy2#gY& zOY5K2%v#jViM$r2NS+6IY{^Dol-R7{pViD-G&(N#6*~{IMm7SY#AXfutY+4t(Q#$I zVvTGBMv2WD{#nheMZ=kskL%_uwzCoOC`Yh{e^z6Ui!y7`aE4=zYy|fxJ6j^bNAk~V zW-S^KFcXnRHUgu>W(_y1CFl=5VsqKk6v^`-+m49OgM2KEVw?Z?-~IC-AIr^ywy)Uv zYF`A*eS9~=&53j*|Ey;FwmUA&YE-Ih1V)L?rS;EhX(dsvub8=uG_nye_wn5fie!Q{ z{PUp6Gs7s`SHis$`nPO^%xXxmhJRKwd1g3s+P-4vD{hZ$1k8PWH^a?|tl^#2(wt|y zIgyU*<}0I-g@{Kvg3rT0tFgyL*}f9)wvb*nLS{82_(=YF(Dqb!T<$A&zT)%9MqrfK dtl^*4Or8nHP1CVYrTbvqGfyQh;g09* zeGElHA{25(L{b!){hqa+z0dxveed!2`k&Y9oBh4d=e?gb?X}ik`&oMr>i_OLZ+QYo zx1arf-;vEP)O=yj*{vJ4?(_Wr{>~QAw0zh5#A@`bI4eQdv?Zpdc|z0rRoceKnkJ5` zEm%W;*R;>y6n~FIpo)(@AtqMuC@+1i*`1)H1&Kwk)Cy_Z%~fSOKSw?y5vby0Pl$=n zH-4NU(m3o|f{qp>zMn9fe2|wfg^x%Cs`%IwV&YcyKctV_XA*R@AhCPrQjw4H$DbEv z6^TFqi8-NVG9PU#3m=gPRPnJV#6+$EQ)GRl^+?dsf<*Mi zWLY0228gnXM4*a~Js~C03|dPyHwANtXU z79_rmxhH)T)AN&$NCc|**b`!+{QHBXk5kP*^PvTas!=)V+?sZ-)ot<>i9i(}dqPa) z>N#Bcc;>%WKC~cFzkVL+W6#o)4HKa#=N6c|3p?BxcRbE%TviapWTsfhs=skXjID|4T4LS-p6` zpK+&?R#%L*!otVG5*OM#M*LmV&dhwvA^dIvRebCTF>(0^_R;S|(EwVI_~H6P(nrDg z5c#kOznef6AA3Sf^xDHd@)j%?KnoHFe##+zY$+!C6pQe?2~_d1C&a{|zuCutmy^6` zL1JGb`}m`6^FN6Y%yJ^oTGT9BwchRdpa-G|9XBmz}@>q@6`E|4)aj5V$@}X(Fe=R{iA`z(KV^4^QlC5>=<4%!EI$DsJHT!Rw zkL@?aI2egQ6(4&-Ok53?ls@_#Zlt3HiMbcg%Y4jPP=*DxI|NPMz%hxD;9x0okJB2dN0o)8lseR4b?%IXC5zi2_?7o~@09lje_u?{(SpSP z&UBVOE>)>aJ|YpQ;$u&UiE*FKkUmyjP0-PT1l_mAiTkLDn9mvn8<&H$J*$xQUho~ z;j8T=Ff7eEUV)jHjgKJMK+NhJ`8KouW*LQJ$C zwLsQK^?$`!#iiKu(x|$8tZCx7`@zAo&bO8of42y~n?MyG)7(cA>te2Qhx!EPrOnAo5`mem8+CKBhUGB!=}U zBFCu9^IkX5g2ZFXuE?@lGx|O9VG({efhs=sgqW!HSWW3;!_687T98;@Nz55E?PBV? z)ILE_0ja?`mr?djJ$(7zVp zcN3`MV^4^Q^7cEG%pU6JOFRo5LA`z(KV;VmsQGF!) z_~M5#v1maeu?d&eik79wM(<5XjS0DShOHfI*+LHo2zD4yg}DVBmz}@ z>4XK1Zo1pZ@eUL2H!)PQM`F&j98HMHX4~^f@ zRRYh2v$J2OKOu?EvnQJ>ffgii-W8cZRpeBm1qqyYsXmZE6_$ufw9orDm7XW`gkF1AyBn^kyuCcglf$Y^LF%s79`d$`c@L7XMK1d z0#)g!_eo;>1~G3(A80{h+N~3kSh8aLeF#*IEq_!J&+icPcJzT3B%*g*l*C7)#@>fO z)wpB7NTU65F>gm7XhC9gg&UH%dp+Sk1ge_V{!J2diu836Xh9->MZVMDxyfCFNTBNJ z$rsqihF&foXhFi?AkQ|@N?v)*UAjo13j2Jutk8l)ldIy1k0;bDwvQ`SNT3Qw2Gs|S z0E@2jm@%$)tGba#1GFG9f8Ap;RTutk;7Sz|sQRwff3kF!>s}Xu79<{S!amNnct8iI*yIDb(0o{5}M#e){_#nU57;6>t$~L1Irq_HlP)p8F7}nz#O{ z^zp&L3-M|Vq6LY^YjRmFkL5L3L2JT5~#xU zAk_z2kSH|hNjkSDw6~FavO6Pv>;LP(j(GG zpQItKvO)q?xX!5hKnoHp_J~y+Pw3t5?pZhzsKWJ9)dyOT7*$-XOn5?{eLKdL4%OWF><6*Girgon1qtjcRUZl=S8n*86Yr^10xjx!m&A#ji@Uza1l_lVRd`RO5~{@^ zY?_~oFvGoQc7#x!^u5@|Ln?t5ByippnNU^S zD*0I|Gu+xS4gjCmzn|+5ne*XGqqeC&(1OI#4}OwF&ekz50xd}3vwPJC5~ymme24V$ zO`TYm540eG&+b(pNTBNFHS460*01|qJ}~FYDu`!Lp3s*?YHq_aRDGZYiObc+%C;vI zd#$R=2NI~lm=M(mT97C+DxdVx?5=p?&OfemBv6I1Eh>Q)B#a{uOCNSUi84LE`ws?Bn<^vt2%rKo$1jYCh0{M67jJ+;M+- zmk%URh5fwhLyg%Cub79_ejanKS{x$svmzu^)si^TUu7LX>@iAMkmy))k0c6zr@LAr z5~#w+AvNb{L891mQHG|Hq2%vO)q?xXVNJffgii?}<`caU&C`QhOz4tXYPPO7~Dn#)XjZKUs`= z1W#z*@Wy0|M4$@e-c5yX<208KBv6I%`>GGLAW^q<3F+hPz9g3qBv6I> z5L6#%L83xm&c~4W?_EBSKo#z%P<@~UiQn%$CG&B7)Mb|sBv6I>LR24ULE>qH;{g79 zE)V(QAGZ=DP=)(jR01tXtlq*a+sT>YU-W?ls&Jo(%H5~#v`Y^o2mATjNubJS)jW_xulmk%URh5PYTA80`$f72t9W z11(78X!^DE@%b39%Lfvu!m&NzlsV;iWgV9bOh(1HXfz@vBx4Bm#jM$J}=)b3FTAw zAygInQ0@n1s`zeO)5IGO_)b{U#63BW=b9$&?q!<%cFvJN70(Pbjo)h^8LPFU1qq%% z&>JS~Sw`3g5~$)Cj;8T@4bTT#kl1qq&=Xdv!Lv+F3(sD|K9E2azOg{{ffgiqwybI4S$Nn75~#vA7N|bZf&|a{H7$HM z5%z%us_=~kst>dv!FMmzm)LhjVIN4K3g1|u`ala3d>5u^;k&!A4A~11(74TaMIx zAb~1gjima(HB0FOElAiSYSwWO2~_bar=}_USfmft;*78AxQk`Q&p9y+oLkd)S3Kqe zElBWlb=tLs&*-HOBv8fACTOgc`{>aJT9Dx9>YAoJqnAFAKovh1q47iRqemZTL4u#2 z(7t7SMlXFJfhyeZuGR-ykWhE86XUn%C8*+OMYJ!So?Gxduc4er^wO=5~#wr z(Xa>G2U?Ker`DRLJPnsVkU$l_jYjo>79{xTyQV2m^`#FaP=#-!QGK8V363J5vcl*D z=>rK=;oE3bA80{>qakRXh*1{O2NI~_2oJGZTEx}2qXh|$>d-VLT15Il0#zKTLNiPG zmK)9qw|2B3!OrK=;oE4`vO)_I9A%?vO7xEOfdr~>L{)vD1qqH8qE#G> zLXtj^KoyR=st;UGz;y=Rr$KL2!~Gx92U?Keog|v3>@mqgpo;ft(8?X||BwV)kl>vp zw33Q@OtKKD;(Z#l!h-uhB!LzrcwdO7DSJ$^5UApv9rQ*6-2Wj7v>?IzLTK#+_l#yC zP{lh&=#2)n`&6w#v>>5Abzp|C4`PXCpalthE)tnQ74HV7H(%j?XPI-f zAi;ZvX&nZ@EDqNT5nx{XzmQNbrtqq0BT{ zZ;w$(pbAHAl|Ty;@YKoW0|`{&*sl6O3lba|A++v%Ab~25l&3fQ*!zn7cFxg)1n%@# zQ-uVoIG$e9#2zD+z&FC+8)!JrTGPTY+u>B91qqJ+ra3i6lFN3579=?0ThsX6JDe`Q z29ZD&zUxQo!>QtEe(|@sc-|Kvjx*z6Ht5PZT9AO+B$|GHyFQRmRXlqQNA_nSgarxp zNuzM$_8|yVWyyJ%KnoHa@lS7t!`%b2K9E2amby$**ax;HEUU=v3M~pD_i2c;TTgiX zcFvK&+T@*Rw4R7N++;q`f&{+NLwIs(5D8TAPBfZ@;|@3J11(7K&Noft_m`j#Bv8dW z(KJoj;U;~c1qpn^ikc53P{ljZsGZ^tH|YZ{NZ^}dR3Av7ig%)EnzF-9`ala3_{JO6 z2NI~_ooF=Q#T{vzCVij< z3Eufe@7I)XXd*9u`}#lvRlF08=DWDVP5M9!68J_aH6KWzig%)EnzF-9`ala3_+~5B z2NI~_ooJe->~NDl(1HZMp-c6F1gdzi481iPceqI(XhDK^zERI0-$zDX{C0gHfhyjo zLu&xIgGc&63lhAWhu#?}-^7MKkU$mh9?~>rCzAAm79?<-SIY_sRPin-O$+a+3g;Xx zNZ`ys(~brzh$=wzYr4E9YsaMaDq2nwZ_yk6 zR&|;XeDi~@=7>S83V3@s#Ow9e@`~_;FN+8MPMW@X)%WyHq_`4mXx+wKLGL5tl_GvO z(eNvyg1@!dZ{DIa(HwSbsX*D9GgF@1mtdd;2{lz4J)XdGUyMsRw^t=lwTx2Ry#9Wf zT21Q?`9KR2;@B<)P3u3kNT7N5;O1Wssrjg}xxBA;@_uvUI5kh2)^gipfuz5Cq%1y? zU|`yj7~E-suLY&5#zc|x2ERQVxIXJ-O6{Li0##GjEc1EK?=zz(3!=+!!Hhy>lQJGT znP8OuteAfCuRZ3^Gxcp45ue#Qr+$TMHglRF&TX!rvE=Di>8Ecd7-&HPQ>$q)zvl{E zXu2kK)CrY9Rfn>deC?O*H5*P9K9YXQ7fAnKlhk*PB^YQyLe0n4w~{h;Rh*a6{x>xr zZQIA_4bJX1&&*NtL|+mZw>o3>@{cpV{yo9Kv?Fo-p020P*liB_RHW+J#Y-}F)f$tb z|Dh77`fFf&{r0qP%)#>o(f*IbjPIknWaRrR!9Yv-f*(F4m;?5oBexm6)@8Ag;o_}g&H2p^O^*o!)3cLQhzs*9fJUvsMWoJI1xm z=<~+!=^L)A1gcIpSfxLtrI?o_aj?;=8Q=W5EB$MFryg2btk|fJskOkE)bFjCXD*>*>DwQ(me<=q`tWFasbcw~XSxVg zWl~SR#JobZrWI*dB4bm#SJJoKPB74W{U-wYp4My39<~pPNo5}w|9vE5R*gr~yWdgs zfy9vgLEUJ*(oB^;n%}*getLh;w5pUUEGt!osjBh)V;L_Wej=tR`M}%?AGJRJ)Jau1 z=jCn`&*=X{!BWrVyFQ8ej0m*sq{ep=K;l^UFZH3_J~lh7 z5%sa{Ow)`vP92QtMJ*A}g{n+yyP7u1YP*Z-w9WW*!?~C()Y{RqsMJdR*D({#uc(FN zndrTPPxQ*Db2G2EvVBEasX{_rU45S&Bd8$J zm)H4$55{MBI#u^hp`HOP7n4Tl&m{~oJAUR))xPJaW_;1SiT9S>`&g+$Vk-4M>pvK5 z^**zA%+C1slWyK!^yWoO6{_wWYN;pv+27nZPn7PLCzodIEI!V=|3ZR+mfxwbopStL z+1KKk=-uiWpJzNjVY+uZy%iBHNX*WBLEqoAx2ew-K1>>;HeDVcljN#%RPk71KNBwh z-o1<;`{%CX$+SmKwjgmTv4CD{=-cN0>B2`w|D1u&zU|TaFDikmb2M_6__l{Na*nx> zJ8<~m?C5L96AZKrnfIe_F}I^&xNY1PuKUou&0Z;W4y>mp{0cb`yT(YR-Yde479}OU*;{Fql?*n zv^!P%ixv&+FgDhB`=FXCBzDbuehbYm-1f&5~z}q z5p<<-l*O2;4Fc01FYo-^Y?T^Tpy?2)OpWWm>5vxl|bpHk9mi!PcZOYNbLQ- zn-M*Epn0gBNL6gr*8)GS`zvPqI+Z}x;6sCr&*?gE+*%N!-c17?{@54u?iUFLTJp7+ zVElMtxM?(Zr|S8yUk}`f|1#$6TGa;Yf%FwhcPYPs?A`VY+?8@N-oV@2!0vT5yN`ma)bAn|j9 zRmPor6V282g^y03vQQzP)NI5XAZRztU)BUKfT2;9-VF$BAR0F|85`1dFo`HLM{STv&W|y z3l=7tIemg?+^S<>>d_^2{#=@1pylN!0!B?5&-2B)Q&qTfr@)BUhSaG;1f~j!!xsWZ zj(_HwTfM?Z+fUyJG+y*?bnYc8p{h*d-o3@a1Dl2^?LJmfm3y#Oz%u} zF3ZZYATfF8dSl?pugsycm9$Q76ByPyHhr<(t}FsoG?y?mnjv#bY}>j`Am)*V>F0?+ z%giGyjVmvvmQu@7k^1@_|Iul7&Y7?dhiP6_NAy`CA5FZ9g@= zjeQMT1ga*{RXd;V6Zop#T)TPTc=grk^XNK9%k_bijqT$?X5H7_sj9KBX<&KH-RUn- zUxMjHVhZ&>;vR>4pJ#t~Ezq&++4Q&U{>n-fsxDj|U>NmxniboKd{pn)IFRtj?ey3$ z6AZLm$ko=kzT+G7YzKF$&NXQiIQ-5N87J&s)bfFZ=uy+?eo*wm6nRH|d+NYuX?^T# z&>~PJM z5vanI7wX%OjG{I}i!#Z%e7Jj+pRw_qnelm>rfpftM2E2jd}u*JJ_V!^ho2~-4@ z5vGv{RB`MmefdPjq_&vFK0f)jPXH}Q$cR?*!I82S;dc|L;uu&@h>1guxjypuFA_ux z5;8KE<|Q2QYY~1ofhvyWr7tha7~u{F`AbdLQ{M}s1qm5pO!?r*WsC5;2~=@RGJQo! z#yaoMJ5aX7%Li5k(Sn4GlqMe>fo&0fH-RdSt@ebN2>sDh`slXnXb>$($cS(9!I9(^ z;dc|L;uvxIqK=F`e{5EJ>0{S#c?`55AtTq5URui$@fP8C6R6@?cTb3kalQu9#}hY7 z8)!j7M&MIEII`a&{B8nO9JB8UF|o1J3)07&H@pT~kdQkG$OrFGun51KKo##j@PwG? zUHcK~9U~Uu zcN3`My&#?t6F*-bFMU*s8e*UY3Asas>YR7JScKnApo;gj(3fK6UYXm+3P>L-myI&e zf`r^@L;2txJQm@16R6_7Is8Ts`YyoDU*%VOj+{*}(1L`FNhcrt77vT?y9rcr6uT$H zMCG{!V#SCvjP6p=f`p7Pr#k0o^+*J&I40c_V#4#;I+>3_)W@R*37n(S{%t1wZUR*} z`yk?x&f?jGw(T=@UV;RzEx_!x`tNTB?zE0i`PD_B3TL&NR=4<}baLTeO6zc>((P41 zT-T7tG|ux{-^^#$c}1!wQ_j(XgpB^B8svA@L?Ted@xu07ZgxF-SNa%Es~>1VLdGYP z4~~wGM4*Zznmr*VeEm~oE7@{&w1E~RWHdJU;3)4%1gbcG+Y@4<|AN{+QC7eIG{Qg& z5;Cfsu3C;(k3^t~+Ctw$M7%TH_(EFjE<*#aMXPy0#zJO?+G#SdY_-9 zk3~Cs8fZa6M)}hf#k&V05vbyQ0sMA3`Yz}BN2&GEJwlIG23nAiQInJpexqC@0#zJm zX}^Q+&3Z3NA5YJ#W1s~I8Kp@+IF>UKfhvycr1zf7=+FP&Yb`~l63lcJR)YEt^ z$D~FgP{q-vo)8nwu6B_=a&-AOh!!Md3@qh?V{0Q3sN$$unpw(d+}~@xCw;t_V`C64 zNXS@T^1(5}kqA_A^sgtxL}2wW>EplY-GXRALdGPM4~}(?M4*bJm}y2Pqoe1v=I`BI z@|_Q$1qm5jO+GkgI}(8^j>e|htBmq4e3`#@*Zjxz8E8R5#)y*-jy;b=po*i)Js~D4 z(f8ZM^|AcJ3bANGLdLq&HOMjakqA_Abi60TM4RpGV`}xPv1ma;#_W?1-U|?kKov*% zQ(4K~1HJxcAHQwfk%geWTP$}~JJxoK4yF;o> zt{YRvF!ByuVD_eCO?zR+%icEM?T&6p1X|8)4jRSZn{U2FD)mgcm%r?7esphi1D6jZ z#LAR-V%Avtc&AbWZ}aDi)T!aTh)Z=O`=#!WTnNQ`K;-Z=j2$7WxmDaNgIV{fnXpVs-qMWE`9x$BI**FQ2_ zNMh&F#@@}#m)FT80xk6HmP&V$dF6R`s?K+B;+?!SP-mCR2NEL+E;2^EHQww=G`*`} zP&4n;8K>&3auKLnK&w&WDcQctf>=|x$!ujYvA;UZ9#Iij4A5%-RHwu10+ zqjPKTy_*$c>QJiC`@=0e8?(<1FgHBs&bdCIowsYR1~Ip8sI3Hv8?@pzm7Y4JR}?;S zcwX^#I99ICBd)fKDoi0o4&)u`eX8lJQKKjyXhC9^Z0};WCR)>) zyy5p=8G`0DvdZv?d}MU> zdx!PYHj8|q#d~6juVU$LW>ZqBsrvfUvEF8dchz3!@_|H^wMo7_v$~m&N*{@-W4xYX z-D~f15vcl$o{T<2&)7DW6sc-dewz1q!&`Mu(zkva7Hp;$snFl7Ut)4y5yO&1SJB;K zlle{Qf45l6vCd~sjrBI}@krEi@`302Z%iRQPraUIO**fdk3+Y|dS_mIB5JWKRY=^X zXVBBAwTH;Jru`W+%R9I8Z_&LdRd_B`$=K>}s^+(w>W%ALFy;yoXhC9D)kga7h5MPK zrH^fkrh30AQXuA{i$E2Y2u0FYo9@lM?YlY@y`y9KTsIQ*gWZRko3oVFn+v9U{~nN5 zC)MQx2|J45gQrE#7yLQHTf6+YIx}4as-lw;^({-sm>neXTh$rfhksgHXAKc(xfAuN zp7`!qvnr{uL?~YN$P91$^B>kpbooHSj-{yilt|U!Ni)5J%(it#y9iVbEWAelZOkM#hD2*x-)^(K zcMlb<)6JDCRE3Uh(O+CJ-K;8!`MDFl=f3|T`ZXfZLNfpvS+n&?cdAmJO!UrA+#UUj z%LfvtS_JgrIp><2h^F_q{FmqreO5ZUl8ZpqyLSxz#j%Uc36jVNh+199ixwng#6Qio zdG|mh0#&?6z!PF(cMkS3{@7QsXhA|o{8K)7_dp~9RlG-l?u6xjgIm)^$h*5sKgRmd zf`p9trlt%>XhA|o{8K)7_dp~9RlG;Q{-Vy?)p|)E zofjSPp#=#U@lQT@_dp~9RlG-lR#@bIgTz{Gq>r)BKdhq#2^sNEK6v*)Bmz~uN5B(e zBI7%+^s)H#^Ez6PkP-jngLe-^B2dM91ne*BJdy7i>EqQZuj*()LPq?P58gcxi9i+a z5wO3gGr!DrxpLRw&(1npkdP7o+k(2#^onJrIdN74IsbuV)_;UvRm5-Xnc{b6}*7 z79`|;1M+vM(p-XhA~mi6bApt1%LRD&9p$&j;l`$l@!v z$<_0OKNEDcAfe8EA`z&P$Mh6{=esu(XG5{2>aQDuoR_vLh6Jia-N{3D&}sYH>O3g)aP72koYk=pf@VL#@sAt z8Nn$ty@d)lOAF88tbCwK%xXmJkC+G17q0)F`K+BW^Tl9ACZjf^-HB~#i z&+>j>p=eroMrQdyqT=w)`p;dGtU28Nzi4LJD=JOQ6Y*TAs`K4y-P!&}bu z7Q5avZ2}Q!;kjsvDQ2vACffUZV21a-D-+XZyL=$AzWk?pgLwh7nw(R&$~n_pWlcib zG#7!Y%*Ba%fdRm&x2NILc zkJkVBZM&I9cNUs+6j7E^9S4WpMajjn9R|@28vUIo{i4Hk9{KOBamymTtT}rMHVfRlEF+^#9%1W%?!Y zbi1+Mj&H6?-b@5q#J!r>^C9j5)l_|4d7QWJPZd+Pc^eUE8QC<+cPM$ESulKmZkKM8bien>#JH`$ zyL=$gYvK~$%)j@U&E)<0@E`o%4=aq>`kRYDl~@}PyPbH|puuXtx4*B%)<1|qOT(ti zW0zdoZ&nMhW!S0uesO}g#l~J6^IW&@o!Nqf|B?A}HY!lDxAvPUa)qUPzXWf`9J6cXCju>$Lb+4RS@*G1^+xnaZ?7LJCVO2zkeGGmQn2S| zd(97NO-|EJ#}D;R{r&_+zx^TDl-Ybv2 zo_>zj`cQS7*7rnf7wdZ}@qAiaum5p9y@0*SNxi5z7ZRPvzhmqv_O*G3))r|`gTIaU zlgD35FY6*uRsLLmWAE^tW)-y_ zU1HR4oMtYvSGKJZp=YV1n|O=&H`2a#`9PxFfn`R*d#Pqnu52%;+{D}a&(yT@Cu4VcIz&(DKmPB;(YYO=hC~6d;_c^Jic2RxC0;?XJrQ65@$~ z*dHaHA>U-aMC{J3n%LfuP&dcaueqwT{@yp(;>r+!3y9iWeE;WoNuP-wP z%2Z{IXymv@ewT?SB%&DAh{n15IX?0Db30?vf&{;9#S`K;w?raPC6DP&n2D(eICk(- zm141IL4w~i;|cK_Xd)4)lE*ZAWui9iixN*Q$6T-PMGF$@x0fRksFKIzgWtW=mUfp4 zAM3t&I2J8P;J2PBE<6H(DtSyk_#HwETCoo;cVaABkiaic)0$-j0#)*u?&$elNGB*N zTIA!ysjXwtf&_j^Thk&DsFKH&4}Pc9tM{Z2|EgJY)6s$iei2;LA`z&P$K-?GO_lT& z`-ojoKY$h_@XO}3zcvDaDtSyk_&wXt{mVWA$qO>jf&_k{UDF~FsFKHYeenCj?@&a) zsE?e(JH?^}3H;JLMfOJ^P$iEkAN=0)!5#QIpLhOTELxD@H>i6;{BHF~1ghjQ`CuYG zbA-&t`NwMe(1HZN*WDB1cf>~`P$iGa2NRpGzt3g0HqnO`B>4UGw2Bkkhx+zN1ghjQ z)dv%85BHKj^aF={XhDMC%DJNqLMsFKH&4<>fhZ!3K){-}VC79{u!1D+6ndms{l zDtSykmFTmN{ZkF-J!b+jPCUwrU{_*)Q> z2vo^q>aUo1=%^-r%&zr@jus^N%N4X*yJ9@mc_ac=@|g0$#IB=(ptuI>nSFJ%Ai-bY z@Pzo=9FYiA$z#d~6XlMNmOet4hv;ZQg1;o<3Gp{ZA`z&P$CM8yPEUJE`j}a6l#Ui8 z_=_l>5PvHr5`ijtOg^lyt4#Yu#*5bNPEXu@tarZ@9(t@y+t$T~Yk*zMJLwoq&-DRPnJV#Kg0m*~i|urv=c0 z1ipii-slj4KouW*Li{$w`c_off;TDz(1HZNOYvrTen(>@0#$tM2{B>P%8ID-T$$6o zXh8zs2}x^p5eQWAu_wfDr+hJkeZ2K*omjLW!SA-bS)RYm5s5$*AA3Sfd~ZD~+OR)& z23nBdZ-ET2z~2~&M4*a~Js~DeE#_#$zj7W5palv1rU}L3L?BSb$DR;>kL97KIBK%7 z{%#O0NbuKOhF9RP#6%)c#mAly6T@!2E9?ArQYeTPB>1Z|H_P+aZXyw=;$u&UiFG+T zN*^0P$z`Ag3I4hc`6$wt#*at@s`!|ENTT+|deX;3Uzan`f&_jgh`u`&fj|`>dqVuZ zqEDAqkUoAM9&exp3I5vA&GP&erAP#-_}CL-V%Efb(#KDqv@_6x1b(%Nb^}HrP{qfd z5Pv`F*6(}d^N$uk^fu6f1b=;Mcm@8dRU`scd`xRK@;g{>%$_KHbUi-UKnoK16)jDR zM4*a~slUoSl3K~T2Z~7_s~#O?palv38raS9{FSjt1giMh6Jlb}fDh$!oaF=Qy-`*8 ztFyv_1b)?w-n12gKouW*Li~NTtEY?0aWMa#1OqKd@YmUHmgld&MIune$DR-qCAIPy zqHkYL??^!l5+XL0o_mz%uh&_G-%Y40L3l#p@7)O(^z-Y_lsXzeaq3Ew-^F;8-j6Ai z@(X!!g5YD4T0g&jI`dqZ7&ZP}{GrRAn?l8JU(Aj`3lg9Gd6xVoN!mWY_}8x^fvV%4 zv+>C@HfKZ7`@Q2wY)zMzS;u~k?>{cZQZ0$gJ|C3Rumy={PyQ6qheOc2&0J-r(a(CH zr8uOYpLz&Eh@Y@Hgedjl1Lm9eCr~wR#L@WYADx{IftGHCej-29EfxBvBv?N+RY-`O zH|qDXdH+gL5N*M} z9#tRM+EJxm{|;l9uJ}t_ytwA=_KIcb=-pQ>613ln>c;L@9LDxx_Zf}~`xr+rd|(gI zuiS6p>-@n|g#^9NG2COQKGbtLDs0CpAuI(hjWI=8F)i$I@uE$CFw!soF8*Tw{5o2Y z;C7rHp~oIiQdQy#&MxOzx}w(XeBha^1j&EYR3Rbi|9<@y=L1!uy=C7gqJ_sO?sp$7RY-_2 zG5fw9&xI=W>f)NSO91-}Y#ID_`~B3SuI(RM+=Qlu3B%U&wMT4=}~;Z#DkoC(=;6g-nks1}EyRvB_;H4dYu3RToX zL)p)k&H47a@)h-9 zsX{{JJo~E_&xI;cZrS$?Sc>d}M`tWUH6Lg}LgX*|(HRL;Vcn=c)a%aO+U*h5VPxNK zIx}I15Z8@e|BhbN2VR}1qWMFFe4vHqB~*jqnGE=Lyr@2qpgB>5wu`Ak6^)M(t`F66 zJbVq}nVdAab50{?n4mE+!gY@4LKW7m>H{rE(3lwRi6RrK%IU{cLT%M&LiWhXzJ>OF z*Ex-xVM6p{+0Pm9T&NQLWA-xukz40nPVX%8ls%zZ90Gl-IY&ZOiL&yWS#!>#0b7uG z(0m*Zmld~#>`GU)ID}}S+4nw3ph~p-?0Y!0@D;_qD4t0zE3_aXu4a4OjZC0Q9fKXl zZ#X?!W}MT*WybM$Y(#&R8RzJ!h76}S$c%IPmCQK)hDLS-)s!{o6z9r}=X%bJ!*5Th zK2(cCQ0sv+IgH;xVlM4I+eo|5MB4Go9*$n*11(5U3zU1wvgRBKRQ+S^iBkx_@IimE zT6Jce(_Zb;73p!8E`C1<3FivFAEB!3UIGX!RgT5!i5@gnNH`-k_@G?*4a^6soY{bz zz`CWL$hs4H&{l%PBJ2ITSxXmN398ik7xh9vzsLus*O>=BXjviQ%&*)z$Ff3IQ1wnnHbw`&O zx7dnF%~~I5L4x{9>+a5-4Ax1mC$8q~W0#!J!sP%#4k~43A(6U0pxo2>v3d;&rYCSpW@*8R?ihkad z^^9k7^iH2>*R4Z{IZ^iYf#*UMmZ9ncEl4;sS$EEnP*wK)+D+hiC$2}aOI@^ZK9fj~ zn?MT^-|lYttk_e3e*#rR%WsclC9pT3wnTlGm|tbaMeZ5Uf&|TKtaTrEK9E2a&9AI= zSU2I!!ZPEyg>$N~L_~?%KXqP$gt%6CX6g2U=R%dZ9(nfaCPZ1;SEuN^?4F3vWVcW| zO``2$Pj*VaLti|{QTusE@9ssB5IeGi6uF$W2C)}KmA!jNA^gGzj{43@YGxdc?P{u2 zi@o-GzkDEpDdap&$|fIZLBigPuH=J~Cr2EpDf|B8L9Zy$Yx5msW}LW!`5w+)=h#Y6 z#eIw@B{zW|6{tC|}QpGERJOku=PIszA&TR{gwc&mj&m>Y{|LoEg|35Ph2^x1J z%=++LsG`w1Jj=AtFaGr#YM)_RYi9Sm&hbj6_7x_?nZ#S5vX(9qsET}@)5s~mwI$9a zMl!KeOB`d%7wNZu_GrK@5eXcLY_<58XRmgDF8V}X*?v$TNQmAw`C)rn!rj1y<#=LYU}g?$F9@M?DQE&39)AVK*H zk9Ls>RAoD!`-KltKK6W&OP6Psq73<|4CF%+s1mhl-(hDW$686(9w+|$oXTq6rk*^Qc;+$9bv*#$382th8PFMvGwx{A5?nu7cmo#3yBp3>$!^M zLnwiu|3~Aw^v)I}sGql=);K=05UR>v_XQt*PL*S!@yfavv2)J8#eeOenkpn{OthbW z+$UA2;`JGESL{v|T10(V&paNmtdJ0^oYu4L`=kn0k?R~SNH}Y+kPj*_yR1CqSy=3~ z*SL_NttY&$REZMh*^40T)j_*H>@(T5k=2Joi2Ao8AY48$AE**-%!;^h5#m16ijxS@ z+!s=qO>37q$LjzIu}Wb@KxFaZoC{UF5+deTqC}h@_U&;Yr}q&m=S+^CTf1XX3Aq_ zPQHS<*08Zb z2cAn+IqgmLf$a(jvD%XTRf~kGa;{C)hgwtiO3{P15@&5GE+qU}@d2(n$5w(WE)kI) z;m`TmbuRv*o>!EDJtjJOr#_faRibYErtL$FvG$M4eOkXtG=5_ph+}%swER2w2uRqL ztVGy{ZtLm1aeORGl#V@=8v9t&7XMJ0e3OqX1X~1+gePPZg5qb8;-1`!5E1>Zwc_FU zuu~-o0g0!U@m7qFn8{dk^|;WTPFh{ZpQZN;0?$j=xwQ^+KOdNLBzUIp8qZ~_kU$mn zW7Z0i@aO#GRcqb93X8b!_nRWOoDZRN6RO1_sKvmU&<7H#3TqY#%m)(G@~!)GcdC$3 zRZh)@J@`d^V42WpV6DT6^FBzbRKmWSykDxEJ4oAyhkRvE*cRu!!e90?8BQ+~s1o_J zV(!R~^OG}Vs%O&_-o^Tb-PdN@b_w(wXhDKzHP-r-J0D1>DtiUVP2g2T^R{qq@k~xG z+^IssS-ExlP|szr);@S^cL?Dx`}r>W5Gj@O&#+45&z@ha`9KTzD|~I^nN$KTNYF?P z{ffibH7NcP7eW<{=g`|Bf$fL;5_@ilJt`8|5|I#nSN5|EBv2*#N@sSCK2(dn_A2W6 zK~m+cy~;5$Lfgf2iN3_1C#bClQ-u~JMBim!U5?(}c2$+V_UdlC&f05SNYt8LKIl8L z4z)Yr}|LakG+!m;8&DGh+ZQ5xeupG_>BvpO7uk8&Sb<+J?m~X)1<4* zUX3s_4&>Oz>CZIzU;Z!e?Xy-n$YNjTnPzk!F`kQ`n{djyfTlF{(XiyFxe z)QjopDLXpN8Ny{keOI`2VNKsfpalu)yCPhJNT7;(xCqy|YO(L)Gp$}UyXymei2HNv znWsr(dxZW92~=TQP|FG}NYHE`+&@MpR8=OGv`HoFu5+~yw`Ud)dJWR~;_dS~a}>7^ z>={snC8Fj7El4;sC$|qIRFypgbQAQ1M}9?x%Oo6cZaTACH=$Y_LR^p5lTj*R=jYdj z4=Wniq^G^|t+2u$rqjN!Fu+i`z7;uOI(p#)2~`!TKCsTkIB3PHDfJ)O2NGi3&AxBPRG~_Y z^VyFdIC|lzmbFcD+SKa<37YxaQRS|(QqSe6@Y+;!u8v;zQ@IBnIjOAdNI+A}QL}F) zIM$*{%zd-3b1X#~ovGjD@f=HC%?DbL5Hm7+W)PV`m6*>t_dX8e*Rk&ta}@D4IdK)? zwdv@s8GyCwlxZSC5e2k9E8{@u49-u^8Nvjr=t;aTzTubks->$aT<&-U)3p+zbkTwY z){~Pakq;zPl^ARN*`$in8MYu1xy~^kVwPcFwU|ORRjS1y#0)31ViJ4ROSFMQN zfO-zkGC3wByBb6bwTv(UaXD08&QG>0JKBgW;V7j0+}EOtu5CM->OKVK90@UUWRe0BhuTK%=LVUkI8*k0 zI})hEx>0?g1qsSugb@b`R8d<9k8r9F?DfUfWyKdg;E00+-MP@UvxG|4-AY7CoVs;X zoT{X32-V^c)OM|vRJRYTTkaqE+Qzn^<{T|Zh+fp`R~$yY+eVd$>uM3qu zrV4-dJV6k4NjrM0hYMSfp!yH5utp|SRXB#tR0*mn!>%cnu%kNMrHceax0#W1u3DV) z3V-%0o|-BoP=)oBg$R!Z*lR~_iK@lv=f$0j6i zh)GrMQfq83@9Uks-`qG(r#10sudNEscxa$LU`y_enRH)!g?5={PSdw_D0|7*e%W5L z;Z%Ja^{CJ&)2j{Z`BW;tUf|-dpC6>T96n_L<@@YuQ5^hc&DB$BKo?|XKh3a5_-Z4y+$a-oV7}%>hf33jSD{(()DLLrl180oX^pF zQa|iubj+1QU*CH`5)!DQFM{jh%O{tlk4E41Fdkod%GV^%o+@ZTqQ#1h`j}dq%&Kce zs=m$H%jntlsIP08{V8ZcLX5%Ah_g1-&&Zvg;@h(Nn4!FcVIKWlq>6e4W`s!{kG$90mZ1?y=_!!fDlyUUe$97Oz36~M^CZ<8rdHE-^dD~2YSAhvMntq^M{s@gy))8iH={%r!ls1^ z^F;3+Sofas+sO67O@|&!!&KRXeHSKXINTDgb|rm?wq#qfBY2*eUiMw1N7~LTgiQ<8 zvF=~$L%V%!c330Y)lRyiM$?E;r^@50XhDLnF8kj3=;CgMUiMP(-wnQvNT7LZ_xh=AA2Q5^tJXX`NgCW`f~|G%#NSw+mP0@ zeg|tBQ)<>QrshshMhgFz;FU+a z8l8sct~NXK1$}?d-ljfV-}XC=OH*hU6^~2K`o5-BU6;p5+uGh3Uu1eUF{)X6txP2D z9BQd2{n_8#H&4|0pH#AcQ3;!SbEP7IDl8FAODyxWaqQV9#ycM*ZbShHs(_3}K zIIn5>s+2csrq?wpcC4!qsKRm!&##ODYYL=_*^<4=F=XD4zLmSXn`@@<9M0N_Ml(zE z=x4zyZw@lnw7s!j%wB8@66fgeC1~%Omvs4AxnHErb8uY&J= z-rwjJ`%oH|6%wZs3+T0mzHRQGE_}?I`F-$%wnG|?mHiFR2b(Ui)t z6TNwXXO`!d_Y78lW0*0rP>E`IE>vN;Y1*#~kETzfzPD0|ylI#!q<77Fev5cN!-`QN z=QBoc3VcSRPLh=602?sL4y3j8rlDTdd^ql{gKA(X5EvJK-DUX7%@orpqai;^u149Xta@9NqDvHA{~pi zRP-HLAK+u-KcD*^YBs>=xjSbXo)?MoFWn3VygkfkdJ7+A;{3jKhldy!mw%Cj1gc!A zqS=_ZYDYDDauc;gdrzf!;vQZj8%)Qa(>2(*wea!Uf6wUi2fbo=mTgHz%iiz18PSsm znupp6m2)OdYq9@-`hY=gj1T9`7JW(B2NLJ$%YvdOI`yWY>5B4+D{B0dX-P<+3d>N_ z4ln!9x2RwjqmA)fDq4^z`Swf3>5_fS0$qiVj1~KRGqv8viN}{DA%Q9^X-%W?Ll@(R zwx!}G8Z+qroJX&p>G;mQiRSA1vTqNs6l+?+B^~v8lX4n=KJ!;9_0(Yt60xP08$YlA z(EPE1NY#%IHP>?-ENr~rVMq#EDjb|`%)2$lq)!!!@gsaDO{@7&eZ5HQGDdQV4q`M2 zTacJTfA2$Ml=+(QL1UCI#;9X;Ca*yPRapO;cDrhfUTkR<wI*85eRMJR`DV-08<9X2wjNDuUhZ8z zF?naO<EW2c4 zRXi7}u>QmC%Gc>yo@$~#?7KLVjC>B2~$KhU&dq4)N`ul`9!7|K7+jDvexY7N)j~XQDNL0weV!yb%fuiEKe4YRN*Q{`Pd!_lii>@~Un1eqR*OKNbU2sp#=%?#Zp>LlRc`Y?V)ugaetm`X*GpF71pe#%~{%AKT+?3 zFM07;*)!O6j>P1h>y3dYzcPo)E2;;5QK$39knh66kL6Ws6R5)amn%iOSSfm~;+U#p zjIy7lh!H1^-u5O&GSTxn&p-4~UcGyP_WDaNu9v;2Z9(EfuC~VY9p9K|JBZRfH1sLG z+=?dp^!IY6pyk5V0fte3r&+O$+sB`OmC+9ls;_r`qG>hsj>Hs7RYiKE9FOO;QlyKO zqPCU4R0vdwQNnILR3D|P=#AIL=)XKNLXK*-1&QkeCmY+xh0MCIi+rp+5UXoDE9<9* zUfGD}LKU{L@N7x%G5qxuF_W>^KgCRDS=YUCz9U9$`}voq<+%R2Pj5OvFEhNXn1zQe zNL;f1F6LTt&C(~Z+{hE54VrVqCwbsEA+J z#+EIapf@bkskCZwh~Za81%GR^-@GN~qO=wsD|+jNiAR!=Koyp{ruCotg70wSk$Pg$ zZ#JL>iDgzj@qG8L?)N1f9-=QRSy;|R?HWWC){Ul(Yqri;=J5ggh~KIt;n%G3yVy{( zahler>k8k;0|)B;yDY4Q79{Z7+fKWx`DouLBv1wUBOgzc{=xUwz<2bvjanLCo#}KJH@QnV^j92vQU$v}_1gh{m+;Y`f_9Y{dCq%(@9*1AgMq1N8 zPpGCB7#5`uC|5(=(c8VHLg3fBHEnc!8NFW426}~c4#;<3?NJKfGv7)V>c`d*G{M=o&(Sihity`{a%dz&t+_h0ipbASw(@OiB=pEKR zr59NEZB?`&f!`CSIo#Pey=aq)`raQO$MHN4RanxRb}hPx-tOvY-zyKFt%^Cv6yo>2 z@5r6WRgplIn8`Zd4WE1Zef`&$X8SVh{PZGP zkif5lJ9D^l8&aasf`mN}qL~b(YI22P`d3kXd0hrluW_$)I)FFWdv{0bP%cged$sNcA>XW=6*Y>cv1;#{c06jGhn z8m-@$eAzwg%a-8ppGQ43LjU!(SKKp8`IZy$1YD@pobTHFu72p=w&402e&Iqa`og=Y8?ibpzVeDe7*(O4fyoY@>SioZACd`spd->lJk+rvi!J@!1T5U5gH&)A|q{mUVhjUpG~ zHXc1W*%)4Rlv%g(Xq$nmXtm!Exh6z)W54y zd}eD}HE;-2si_(}>}g-H_$XuP?&3+qr^N>^Z0};WE;qUEr`GD}SvnRoGHW%O+U|zV zy?hN?3^QtE_Q6%oI3yn4a5$K9u)A5lyewU7?e+WFTchw?s1ma?yF_T-USqM(*KCmS za+!lw(Sn4%I(S<8xY~E8FXg3ojY<3b3V|vtH%;rY_G0X{Mx%||{VGLa&M}3v`j!qB zo7Ba8f=WTIh0As7S4yTup#=$8v!=4DFu84Pjg<+;jL;|RkwDd=>q}n}>+OfiSY;(5 zQjGs5e<;>P?dKnHe_6*HOUnANpQMnFl#MfkV_*Kjs9Z&hrj&#&NK{#y=0mSh}0plvH>o>JzKH9L!U9gz-h^+2Z~q>;s8~*55Ov z5Bs^nL%-)$2vlJy&^p|V^MRhNMjI=({vCxDB>uUxGWJ~AE@l;3RzG(;kx}sX1mn~B zk5@qgRj$&to{}YvJoF-6+xGLpI1$g1ME%FzVxoM)&x)vYhc7H@>~GN2Xg&TraShr} z;uNA`!Df1q3jNLcB?SFPD6erne|sar=v5mnv#K`Ie=pq694%GOnds}MfgDDGr#l(T zgSlixirvc~L3bI_cSzFqGq1Ew$HWSKI8~^^)}v{qD*YOq`9%-oo|z$fpK!ZE;=eJ4 z^gQ)?nl-77(WqZPHF$DWKjWjPGnAHyDr{qN9F$LZuLpFoQbbWJgzR{sxStF{>t|YV|VLz|^K>DzsBKP<{Ss_q`tw+-ud{f)lSi8EB z>&T=iv>s?=7QK6ijoyZPGS?fi#pgpO^| zUtBQVtXgz(-O}SX>v>j9GaJ$|jq@_1fM>`{mb_%HTrLRCYeR4{^<_#{F}yr?YDwo4S!T=C8)ys zr#t!_Lyb;HMg?0pd?gBVZu=0qr8%RFRN4BZ@PSblXvvP?vf5jJq>)&xiap;ApUb9& z>Qsw>K0N1KbCdKj^PkbiiOQ+5Z$A^L{bO`MZ&Z4XxtT0Q?-+XOgeB$#sS3x*P+yYo zUV<^U$)*@lx-{RVvRYz_^JYgdO>=4y?<4Pukg$)13R9?QWywd%+12UGw{4A9E$mMa z?@|h19J|;`;Tv~H8@2ju2{e0iNNprgrRMx_jgf}7>_y+TmVs!@xt%JzKE(YF*N2r4 zaUbOuJ{*fv3ijW*KBDdnG5S6?THHq|1gfSS*rK<4cZ0kNG_C2!1B}q3wZ4xpt%*hp z5*3GU)_?AjB(IflEAhP){ZCD_AR$_ewHh6#X*nLzL4vQe6xn(-?eS+@8CM%U zrU&~TQ3zD6FaN3DU|ztiCVMzL5^&ewhhz_Dts%#W{z@E+eh_I*TUxfhasKtP`t5R? zqtSvy=Hf)XardCvN&3)_H#CObD5ZBFJVPN+rKW1us=P+Q;_dbPZx4xXm%owzzZ<(u zKaF?4pKhw>cyE{4kd8%P>Ab!5wW&poI?bEv=N5MptLI@05_YUAkL`A3=FFe-D+H>< zC}Ed~rme15!MO5WydH{O9*q_xCY>Lx|MS~+GfnpG%g5I?nvJZk-)f(xlrE~U-01t^ z8*&)=OLx+XJ+)fNIp#@>)T#7jgJ%GCr0k8(ABh#numuS*Gk~|yjy)ATeW-^X`%IET zpz4=VkL$ z{hxZlGcS+OKPoam8ZAilnz+O_^Y49TGwI`*8C`JCiRH>;NyJx5`w$)I5 za<9M!T+JpQ^680vA7!Uj)0$PP^$CW&L4~i9h@KKXCW`@Bf9 zJOApv5B|uPzG(kbPq}MVf{bF>#P8m=Q%L0|@K$4t73~ejcToY^0j9B6-+8@)r zK^i1%^Q(n=UQ2>+PRAqWl)+nxJP+h<@ZRKKl5sI8!7I61L+D zn5(xlNvu72CnTit!8pI7|D-^|_HuLm799zC=7cnUJ<{+Yo%e}961JC{e1mUI&@(5b z@lce-w?~;sgM{t+jpuwTX-)9$qd6fB&P7SsuHUfrJ8>lV_R*Y>#;aqVcz9u*Cz7zO zD8FO0Cg_Fjvw{Qc<9>;q5eEQb3z(zjJiaaR@6oOcZxJfg9JTuLiD@i z44Iy@M0vy?ua$QF!hGKCn$Uay_RI)rL|*BnY|$WLyL|HwxlTggmdNs$6ViwhydL9V z(I8=4QU1o-nxJP+i2jAx(|^QkOWlpU;l1e*Z1dL(>~roz!gkiHmq%HsJV?}XuAVs| zjaCznN(TwswSD-zA0$*?(=#We(b{0qAYr?5JJzozl2ha;vVe#)I)}DSRATE|ZXDI0)VVl3aDDB9rzJk;| zp_a#Tm=n@yGnt}6!nUINDl9Ze&@(4Qb9G0;cKzMo+6t5o5}LQ!lXpTw8quOA>%rw< z`eM;6v$kewkf3KyNMpVpTn?uBYpc>AQRmU>ueJzj%-4g8VNBF2Cp1MhR(<(7L9MAIo7*NMpVpTn?rc)mLGmL4uw+ks7(WBVoIyqkSX3 zX(WO5S$OhJNFc8?XE-NeyOu{?^&zhcq5MhDoR9`rcO-0Qz0&+j8YHkjE9KGFpY3;l zMM#6II})~Q`>3-)X^_DBtkuMNUH`i@T8rB6BCqVJwY|+U^$YE7Rx1q>^q8*gyv>6{ zW4<1&?c7m)6&4yK)Z?_@5-L5zWkTs_JzPl#3EQ>bZQno-4HD`H?MXcn(r7(((I8>_ zqKpQ0wWPcvq5eEQb3z(i-I1`ZD2+a+Q>|Ad=$R9u=j%b;Z(jFe(I}dCyC&A28PW1; zvL0LxrY{!F2Au1WSDm0|PDmq4aIzj;4yF~=*KM`TJ3-H!5ItWHDzEao7mH?RwN~oi zNvu6HLK@McChNiFVESUwEYt0r1U+*?8eH9xuw8y(_h$Pom`DeSI*+bB*_@CDS9c_A zmtP0&z3ZCLdLaAVIUxW+l%tXD5T)&7b^ zE$8Z)6Vl-7j)d*nK0Hq(q57JhIU$YKqRO0_gzehSJ*y?5c9)(xA&vQZu(tC`E2^); zqGU6M8v43e%d3mHMy@T>uD>gktJk8@iMZ~;o*A*+>@$F(LBe)fZ6CY} zZ*zvs-R_wa(r7c8OGM;uqZQ?^DX$57=7i{|iO1Z_AYr@ynoFz4r!^7v^LdyJt>FgR46dw#)9|!MlbeqCfARIUxs48Wg$9XQ&eby~ zq|xf`eit1T3EQ=OO&@(4Qb9G0;cI|ibsneQJKWI@Fa@mgt@=bZg+*F>x{;h7OFulnkagl+zk zS<9U^w9E7J-U`-4?3chZBc#!0 zmZdyM*e>S)dTU-2u@BQdb3z)iQ?!qBGDU-g?Q)*s5aal%)+-XR1JylqLK<8TlCWLQ zW%S;4O~g)G_sj`tv=xhb>KzH&<+KP!2@)MldLIQbJR(B+9*YfbZq~%p1lt1a26Vl-7j)d*3S6cO{os+2LTs?C_ z8m%TCRpumY*Y=UK!8M`!nw~i!jn)Q>1_|4>oqJYGLhUX+b3z*N#AKgm?nu~Hlz+`- zP0%wZM6cI_yjI$^-}U-~g!(~yW`s1jx+7t`jvrnvkx+l0o;e|nHb#~5AYofk8hy@N zy&^%+oDkhc&Z1#riEH-jYG1V7t^S?F+A|~C+WCfNm#VuYY?sw`uG>PR%^3=zc|xww z=Y%xc+~*QuT2Xx!78)eznG>St>p|s7UbpO*v{s;hC!u*;Z68~NG}>IWq=SU*vhUMc zv#vx!^UvJ(nG@2OuLqZd>9T(n*H*724H9)8T|IL`8uRtwaxh)?;acx14H8-pE4`b1P;g@pzQdaS4GCXpJsy0b_3 z>nN+>P#eRS4xzdgg>QxVj@@JL}bJPM4n#Vtsa)6VjNk z2eV%3y0v}yxd92R&st3!32C$zwckZvk+5Ccxu1WKP`gXdoR9`rcO+~ps;|PL%t_EQ zCq%a%uB3y6?b`49c@zn(&q6)#goHF&PhB)f*e?5`ZMCF2O+x*7K5?59(%|Zjgl$D# z#I;YSTCYgZGbcpP*Mqv>yl#2U+3$8uXnf6d%!!s)eRW5|c6s{RR(&n6I-z+&meib( zMwDQG+DF2+qWUT<(no@xIU#z!9@PEjb<5N6-U`-)=55(N=7cn&MfK-{By5*+0BzML zZ4#P)W)CnYq`}o43ESm7LtH!iD-v}cT|IL`8uRsFIVaPuTh3+l-gQlAJ&^sb^+-sg ztyt7kV?9_-z2s_g(ds3i0du~89&I(L zQ!jCsFF##=K1h%0tcfC&j`?~p>s5_Xt<2frnxMyewMDgcVraA$Rpz23Y}a<~SuF{* zyY$QnrDMJxEazl$H5pNT6&86$f*$MXx=F}xJzPnLJ+;4TzuUK{x64(=npk^$UH`i@ zVpLO4T{P@j4z}y~QCEHF+Y6!oJUw$l8eH9xu&tr9pz8IU)L2&mVa3m2F=% zz7+DqyWP_s+Qr3eUo5YB?j!eK{H9MS|Gp;ZnG@1@QOwyt)ZUvQVf$kF;Fr8)|KR7O z1_^rRgfxCM-c@^jdvAh-ZAG2-U-Q?V+R{OSo;e{JGqN2C+ZW3#-}1lqpLf?&ng)rr zC+~!WG(P^3pMHFEdvAh-?Th7mZ~6G;hhF#Ora^+9IU$YqdlUOe#EyjRi{)27=gx?{ zvuTi^XHH0?{nADmqe$4kSpNOhVp3L@np)nG@2;-%61N3EQ=O{N>MmY||j2 z`kJ0OA&s}iGy0E-b|?)Jwri_>-OvBYra?mOEB9pMKsMG#Czxy#w zg9JTuLiDeF`7ho0jrLA83EQ>bz2~QIX&NNd589J=LP8qPyZ7E3?`Y#73EOr2__3#_ z1_|}&>6sJKczV3Qt6i2|{E@JI5#!aHpS0Vh1_^rRMANuCHAvVl={V-ymb>aiT(^7X zM9Zt|nO7uim)t!%*CVew5&6?Sb3z(Xg4eUmN!V7@>F9bzf}S}cI%?uR>n;h~rF|T; z6|9M2o%n0OFnKO{EUCYDsl9pFF z%Q&THPDrDb`6WWRTj{J zMM>DMt=98h5^8tpnG@288FGIYnS^acosOQjlb~l#h>n^5^;{c}uwDCIuRlnrAG9a$ zgoHF=#d1B@I3#S>@x$vV66(*>Gbf}GYqh&`twzGO#zC*))&xCsLK@Hd`p?+^`17Ap z>Q#J&ZTZn3_{fKLrH-b3cKC=t|1-(iv~Tm z&kn!)h&M0y{@agh8e0UTY)j*%H~!}S(f7Qev_X1opB-NIqIWNMf34#rxZT@>@#}N005Z!xw+> zx0nC(-CBQ0V~b#vZE5`R`(CvFz$@QgRulBtK0Dm@^8c~?&j+8>G`0vv*_OsbpZIt7 z?|`8n=J-SMC4rQ{GiH=&^lvI6dpE}m@$7g0#r;>l;4x(`N{{Wc!xJC(y5(R0qh~dZErL`8lU{OZ@K=V7uS6_dTgH^zWzIZ zaQ_A0es|N@A{b>`8qc`vHFrPqQFZ-6kL|O=OF!Xp|6;eh-ZZudM%iu}52gk^wo5vW zPDf}=iMXpCWm_7N@*9~~^w=)tadLTV5s|w+%C177?|iN7@8v)m4r0n*-04#Whv^5Z@X^^<7E5nrtJ9M`IGCv zH{v}0zxbmk=_LLzNZF%?uO&L8WdFg->fGltk)DwdJxhnLm4u=)<;tru9nQrWA^P?x zkDq=1Gg^MFQ=9pwviUF1{IQ7Mowf-^*;Zb)T2eIVvAsK~jy>*Q{@13lMKH>?G+q|% z-~TGiA`gRV3ciXv|hBVKj^W&JE;%;x!-?w)7T;y zWm_6IWBmBtcYfRT$Oo+r+O^JZ+TNWsmi*&4eO}YpA{b>`8n?zc_{X05uA)JY?Kn&n zqv%_|>Um9Li(r&(X?#YE=g)h=WA;i1J+^lzjqN}E)URn8TLhzQOXIg=Uh>ShKf7qq zV|#bf9OdcX_svaXi(r&(Y5Y{oub%dfFDe@J*xsEq*ZQTW+}kv^2u9hKMw|5&4SHGr>J@160> z!%bt0V3h5qq4h`6pvQJe$KL5^>yJxB+*OaV-SSH7s7yzTI=ktpQXY%TBl2oWMDF$| z+tP><)OxUJ&||yQtHt$di-=m%qijnfYT`cYE|mPYh&`|K0xv0eJz#r^IU5xr=S zvMr71srT8p(__1gAB)G2Eh0vP9%Wk^G2&?ds*F+e*e>JX;&E_`h*7Oa*_K9(ockPW z>9JkL^Tp%&77?R!kFqU|m;vl_&OndtGA~&?FWDkumeHeZOCx47`<(mGW4p|+7SFG? zh?p()DBIGA8JYHXj~WN*vAsLRd~WePaf@J-ZE3_@bf0rkdTeV>b^ns{(rscLm4q~6 zhFtn8S&ot?qpF7I@FQW*NMJRw(jb9#!czae&GaWkncYWJUiW_4@kG4M^sgdXRPOK3 zH24(2*G)ni^K)d^4u0xzc8I4A?Ht*)fuLtjNQ0-sNZ39*#M6^@j!YUP=$RAJ;HfYY zwiT79x1>RWo;e|!r@~0sK0CzItagq}8YI@9yb}`A;HfYYw$BdnRIZ&PlLiTT=7coj ziK2ehs?;qKw$BdnbTMk8o@Ppe1U+*?8tsHonYWX$eRhbar0pD;G)T}hC#2C%Iu#8P zw$Bdnw6~ojlLiTT=7cnODvX3}MJeSiU(+)uq`^~RBy87KThGZzgM`{$dgg>Qcq)v9ZAInjEoqRTXHJObsW1|@Yrk91 zElGof`ayg0PDn_Dr@~0suH#2Ned(_NC#1nsVI*vy#dwwH$fQAno;lGp`l&Dy zwo5wNX|bl!iMVd}%!!s){ZtqU+a-6~X|a}9orwJDo;e{6o(dyjTTyv>OBy8TnG>St z=g4%eyl!b9?X;NwokY}EcxHq&=I6++X?$&TY3J?imo!L3yX&4gA&ux6Cg;emX?$&T z>90=p9GNsoME}t}b3z)?!%fbSUDNp5=+f`D(_+#f5&dBI%n51mR2T`{Wi)7~#iT(Z z`t$CY6VjNUBfF;Ywb6=NB25?vC+Env2xye`;QCs5-I|ViT1@GfpCglJMj)@soI&@V z*Roy9qn`IdUKK+5lb$&tjaGt}2-8`w?({gQT2hEw&eby~q|s_(nZuE=UE4=JEv9sk zP<>6$oR9`jg^{pb+j%`LCJhp5cj=iE(%`8u61EkUr?;d*f}S}cny11@*slF`FnS}_#Q zxVj@@TT#pYj^}(-(;z|5oDj{`9SPgJlYYJMZ+)+x6>0y0#M+a0LP8q(>yEqlBVl`Y z(r-Av?iC-~G)T}hC!`TQ1J;ASmg(K8{zB$0O@jnIb3z(zrr&xv{i<%gmg(I|zX$sL zKlceug9JTuLK6cKS@YW|Z4HERs32AV3N5ZzE^c%2he=2hl^vnrpwDlmb zm3B?Xd!Bm7TBEH8AKcqBBal}&cJZe>Ny2t5k1zZ5PhRI$A(TJqnG@1@W4y!ih3&WK zNZ8JL^|YozqLy>@%n50{H|p;HZr{u#VY{}E&war&ng$8g*YwN@X|xt~jI4_HicHw9 zt@fXM#iuq65^8tpnG@3Z{YZoEOd2F?D{9&Q@_+iYra^+9IU)MbMOpl}{$3HUm3HlS zzwtgj6IR_Np?=Vw86l0ckxAGt<#BYbM_zRz@~3;|gfyZA zuV`O@4F8x*1iR`aPME}t}b3z)?!|k(ABw@SsyT|NZ*F^M#-7_bo z!POlJ+hzPXW}m+%qCfARIU$X<^2!mX6Q&h)iX6c>i1na7a{?M|J!rz$t?BT1-tMXp zx~@G*lR#dTc?k*IwLCm8X}MbnS9x+7t`_Pbtx zkWfEpPu>X$X|$fYtK==7co-cYYiQ ztO0qZkc6MOp4|+MPDGlpx@*LFJK1>ribwxS%stL-zW%;Dj(5DP+Hs|J##8eW|D7LS z_=J1*uXx9=Cb0+6o+6I~?a;<2PRNO&3LbO~hRtUvS6!@~)2W zxc2@Qb^poFip`uyPic=*Zen-*zV{`)MZ~}NDBaZy@BQt`T}4z+VMJZ`z2|f8tMZD( zTi$rr_1kVAQhr|Z%GY8P%ipOGK@W*fz3WjihZ{5kT@&l5ty;oTBN2KxE~TSrkYLny znJa&g?|YZp{mZ<}pL^>!@4xJOeyx<$1K)ABf7xfhCu_;WsJkTI_7l&Ge&D}P%iQI` zD7Kq*c_@XM4yF9v7g?8FL)QfBE{RXQ>%Q1Q`oR3IPMIg`sI9yTjh>4nLhrio(DzkZ zR3{iUlv77U?0TuGXK)*|b`K9@twBP$o9%y_U{o!e-~^Ia|K8-C_DThzlTa}sLJa}Czrb(GuYrIhy`U`?DyJKsooCnE29 zlxXL)Rg^b5dpW!5S%yXcm!{*hJhEnx@cdyiew>nE6z39ajkw=lQmQd1k5kr#HNi3` zQS0=qMUh~X>h!$Tu4gQ{TU+u9x$gU_Jwv8Ea=Py{$Gj9f!dnERd^T>(U3y5w{2DvL z)F8nqpYa-&BeQ2}b!W@2Ei!3FVu2Ca6Jz zQ9hGAYS2TXmVfTBP=f@ce71VjpofI&v3H87L4r{}BR*=-LqhG*J6_Zv!6=_~A2sM9 zp?<|Xchn%kD4*FMHP#+qS3RG1AgMuuQGWMe)S!oiRsh~fr3MK``5lT;gB}vzhrNnm zRA{$%Oh$qp5*pzyr6ZDaek8%D$iw!o%&0*RiO9FU@7r>!{Gan92}VU-Xz%=t8uXCR z%-~YJD(N7>sHoHJ-K9}u?eTS^9%J9vDLFrqU{tit_72vlK@W*&kA2_Q3Mvm0jEX*{ zy-PM~&_g2nm6%Bl{Z+{;5{!zzvb_^GYS2R>`p3TSyG{oQMn#|B-^W`M^pJ>tzVG60 z6O4+ntG%N*rh^_5-nqSsU{s93?On@}SbI)U26d-ddfxYSO3sfY7!`Ag_Ri?2K@SP# zTkiW>LG_9Rqhe0f-hCZ4=pj+d|Cagus$YvyF}G{)@QxbvkWf9&ecyFDNUWnC&f0*4 z+GFnft~I#MSVwtXvLg0zHm03P)mat4#}MaP+Bs7FyZ_GjYmbRof5hIBzB@P)s(tk< zdpwPqQ6IQ@nb3)ydQz5WM6V+19oB2MNuzxjZusnvS zUSrl8>;B4T=;KQ53vHL%IXx!gbYpv~;3|SqTIu^M9=@;hJv}7ilxBN7V$>kPD6RDU zH4x+NBp9WYzP}Db4SGn#>EHI&&8R_w zQCjKyD>u}jheXV;Bd_xNa9aeUw9@z2dPuB2zOMA@8R#(`Bp9WYzP~y|4SGl@-|DI9 zQG*1dw9@z2lc+%tiCX@5PR4T*jM7TqUxA_qJtS0*>#6B69V8f~mA=1bMGbmLs6EzG z)1w9nMroz*uX0g?9uhG#Xy4NxHApZ@D}8@mj2df?udAM~o|+ytNH9t(eSam58uXCR z+^(LQ9yLfXieF{3f<^;+NYp6(w!)}Ef>B!OZ>D4L)az;nxS5VlFiI=^&GP6T5|MB1 z6#JMCUW-v$>2KDn?jfNWXZ_ymsIk75qqNfBY#;ELhs(VO8zjCVY*Nz&z7NfM%-|Tn0heY&`?QNA&gV$n|_69b`kM1E6 z{d{|eX4K%d7^S^|&2g}MNW=&id9^VPc7jn_>2Hqb@c6pYt8dYc>EN{(rIr5Xyrg?b zDBtQ^w4(;E#VG9!Y|gK`heR!Zy+u1}@LG)0N`G^n*gYgvkLz2sqXw_Fj(Rw&I}&P- z^)1>_gKL9zl-KRGKd%3KzF)5z`ZM9OHu&%>mKYskZ>c(_D?i&EyF0TebySoDlX6dDCNtCUqQyTIuYxgJSTPeuKKkY6>F+Imo*_W zuj)#y=Waef9|&EmJ(oR5qn*nr>F|}D_PP>I&zk5bJO+(nO_t|C@MiH?6S)tgylUrt zv}R*SHU_1W81V$@4{n2Cub_;#zbocS%G&&a(y+ zjVzCKl*+1>zZFy~6xB{s9Hi0C0mOA5?p-BObD^9AxZ)o-^u!)=dq%6MQ>0vb)|Ux;MAY5v{~wJcbhmY%`m%=amr=1h9Cvlg^saK} zmnVtK7lH8QNTyt)L4GU9JHkBcJl>U_3D&cBtCC^l;xtkt6?W?C|^SU1~ zPsfr(y-r5me_H>0^%jl6QwcqlTk9o3kDjY#nxd8rS4x7OHIaManWh;LbDwr1T2U^i z8cQN;A_?!k&oq)?6iaih!TJ+X?G#G6tB27(NQ7QHCo{RLeyw#>8Pz^aEm;$JE@!6U z+TbYG&{@j$9B}=GH>IhbH5fJM(Jn=P6HdDc{sx^@&i5o3r8L#E2BQW&B($60Z|PBk z#5yX^1dJL{m)a?W^*8#oo8WH(QiBAel)Lq;!KgtG3GF8M+lJI2!6@|-^%?!BK@SP- zCiokT)F5#=N^hTy8kMe|HSq^``dgFKAQ7{_9;H5JGac}l(9XnWIy%9q$isHlU`z)+ zB($5bSswjb>!>^vFlwles;3av-xSqu!e+hd1f!x(x3dPL20bLSo3PnF`n4DpZL^&< z7&Yi2q1}YdcHXbWsQT=-_A#y_nk~^oLc0msuWS>H(lh9K#%oLmJtVZ7;BQS@<$OQs@;#|M=pmuq1b=JN z%$i`7@^C(fqlbic6a1}7YLH-5tv$0@A3Y?ro8WIvQiBAeI2&}l@+$7C_&jw{7n zbfdPzZjEXz#U&C~~?uwpBdH*iw!@DaIQ8xX{p=%9Zi&0Ty`u9xN z1U*rA`o_v8(cP*(= z^D6I`QB2=Jv=bXjxe4v>`wq7VMrpS`)93h_yGvYKd#t-9_AJ}8P3heq|K;6=xBZp! zSkglxb|c%C$_4+DVF#k_u06c>+{+m6Y9#93$!_@VWojr#>r+-;%hy$JSNC^E4HAq} z&sTSyL7c0Wtm{wiw-!CrP~KJC2|Omea|?|C*X^89affX;dL-x};r-;R2u5kVx|H&A zSM-qZzWAs?f>9bp>vMyVpoc`1Q+sZ36~QRY2I}*Vk)Ve})VKEh<0^ttn$^_jI3qz1 ziD)+`w;R?H5{%O9tUiw#HP#+qS9F~g~KRR4Q^!_R+=f9ubRFwWkLY@_I zs<}Y!HY3t*}^^?{*|$^I2+Wv~PtK0?$uxZV;ituR4-|9Z~(+ zZD^37XM+g(L-FmlUypA`DIM{b&w=Aw-R4v4_;(U`I=w}N#s}luSMgubAOTzFp7SYr zT!{od8$@WlCB8p*%P-d71t0{hSJ*@nm~ z61AMGXM+fhk9qAE9#8E%kR)K2_Tg_?kWhV1&jt}1twkNx$VtF1?c86#Afa}bo(&>2 z&La(<8EKIQ3D^)#zXOCjndO$oGG$MknamAVQ;k`K#m=3E0Zr zd=n`&NYJxEghrI$_1Cv=f0BS5QT@%Q&>%t21`%}B-F?V-yM45v7@D zj)NrV*&u?Bk#nD8EeY5q9sc$X30>EoekUYCqow@1>Jo!mU(>Teghp#od*u}g*rnC_>sch! z?$WbCghtGe_c^B~0Xw4n&AT;0&jt~6>)}c|NWd=rZhi}GO{gEVr{4*Q&}cn%(I5f4 zj354j84300>DeGcgWrK90XxP)eu<3)JsX5_y8r2mi$A;nnmeBKP<)$j@gBg%^7{LJ zaR1BKv}bv-^zbmwkMxl6F2z;EIx61je&0+Zbh>9v z$J*oTde>;wAi=1&yz$?}iQkz9JtVyQHENJxRLnSjIDSock`8)E)Kb$f9yHEXf+QFf z+EGI{(lL1IbwjW1a*i6j7Na5$kDKMuJtQLE+S^W}2Cub_imys;)vNAV6S+G)YAC;a zEk{KwIBvENcuYh+ZoB8B2Cv1aXq(4uo3)(k|CUzUJtU$%wxs9rTsO7Jd1EU77#VFP3SG;3J&_hD? zxW4T)YLH-*+U6badfeo$=pmu@Sl@OUHAt+Z&X0ff(K8L@S9;b&K7AiGNJOP!{)Qj3;bG>&AQQq{Bh!|a6)*dUUhQxo} zvnKMK%&0*^^Q-z*ojOn4Y#*^lmbKbM)Z=z~XVi%H(FsOH+l(E(jdtEWB%(dG^F^Zu zuf?e7V`5&v(O-2BiRf3BdeUjs;I$YPeP!&h4*hQF6X_ul{bM_SHENJxRP_0=Q#_0x zMS~s^(a*ONVxtC$Au3X?^JOCuLfx|_mj3S%)BnmixcFL*lJ@3!4vz`x)zcyuaYg@? zk+TzwQXX#3OS*@I@~xg088vtRXrqX`Oj8GycVNWr#I(`-9tk4xSkdn z(y{lo%5P`3sB5v8q4uG>EpNH?>^$SfcHRvIse9PaKwt~hE5{#;KLH+KiK@W*q{u&LgA{ga9e9p3 zMuHv^9S=DuPkbn%jDCBuz6N_I*ZT?J*&}I#0ZcV3cyb&J#z19ums8I#0Zc zU{tL=8}qBECDlWsmj9jeaj+ANQY)zQ#PP1^A)$Jlzbzdl(ErXgPwdxXlv;D$7acX| zA))q|zb)Mb!Z_cPSV!fa?5Lsss_xd-UzhiFb0799Lj6@edweaP{Nz6MNUS|3)Ia*S zrJa)VJqbo>l&JgdqXs=B)X(Q{OItyCMdEUlo*RrBm9HKW@eTAJjyLs8oY%-Q7Y(x# zj0)}c{A1LhheYVLQ^i*ijEX#L&v8bA9ukpn?Nsqq#5yXUI*o*KIP2A#$md2^5t?6R zy^1>Bo~w<-+G8SWemhls6~U-zn{CxM67-OW_Sjc?{bbEv<<4hCwy(u=&MfnbWlhjC zCv;cwWb}rfx=VwE?a~JE?2d%X{9>6C(r720iUtYWipr8zI!MqnCq(n~CkfkS?$gR# z8YEoi^5mV6kcQ64=&5^TRh*N_`om|m*Ww&NmbtD(f*#W(q`}jlBy4jJKpG_KT1{ir z#WE+P(M|%EGZQ3ia}PioBx0=XdopuE8d0Z?aZaY4%P?X3TAUW)-VzCV=7cnO`jdoh zMeXALbB~M!J##`dPk)lIUDM&cJ`%dFJ$WZ2kXJY2nsH9XgzZ`$-m`3ZRS4xzdgg>Q zS_xhvOlQ5yy;l;ooU3O}NQ0+8N!YHn-FwI+RA19GC#2C@)KPgw!gg)7-ti`(c9)(x zA&u5E6b%x#6_tAcY9A!%nG>R4^5t<(?Gb;YXppd7`&~bqAfbNHp1czh(r7(((I8>F zjvs!;LPGs{dgg>Q9{iRE9(+anO>Yvmuj!l&o)wXxXHGPYyHkUN?UIhR2cYr@jZVaM zyJt?cyz0LKPQrGbi#pdMuR0O=)1TeV328(LUe7WoVOvqT(pNf2&@(4QM@`fjudG-7 zsikS|0kpc?iKwr5%9?jVLK+$a)vBTiY8>o@?b6QM9)L7RM7!&rIUx<6{v=_$^jC2Y z*~&^IU$YKmlO>WwiT5teU&*0dgg@a^?6ZVEA86v`m7oW^@H}z2x+vQx}<}I?K*z= d%pD2!=joXf(%|V&61FuC^6Vf9dgg>Q{vRf}_HY0I literal 0 HcmV?d00001 diff --git "a/yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-6-\351\232\217\345\212\250\346\256\265.STL" "b/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-6-\351\232\217\345\212\250\346\256\265.STL" similarity index 100% rename from "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-6-\351\232\217\345\212\250\346\256\265.STL" rename to "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-6-\351\232\217\345\212\250\346\256\265.STL" diff --git "a/yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-7-\351\232\217\345\212\250\346\256\265.STL" "b/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-7-\351\232\217\345\212\250\346\256\265.STL" similarity index 100% rename from "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-7-\351\232\217\345\212\250\346\256\265.STL" rename to "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-7-\351\232\217\345\212\250\346\256\265.STL" diff --git "a/yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-8-\351\232\217\345\212\250\346\256\265.STL" "b/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-8-\351\232\217\345\212\250\346\256\265.STL" similarity index 100% rename from "yard/EWei/STL/\346\210\252\351\235\242\345\275\242\347\212\266-8-\351\232\217\345\212\250\346\256\265.STL" rename to "assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-8-\351\232\217\345\212\250\346\256\265.STL" diff --git "a/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-9-\351\232\217\345\212\250\346\256\265.STL" "b/assets/EWei_STL/\346\210\252\351\235\242\345\275\242\347\212\266-9-\351\232\217\345\212\250\346\256\265.STL" new file mode 100644 index 0000000000000000000000000000000000000000..844d12c311bb143dd31ca2803390897250366f0f GIT binary patch literal 131184 zcmbT93A{~J`^R@lNfAOqImTNuWp<~1u8^U@+(e{7NL^_#-(#K&DM~WLHI>Z69nRh- zWR?;V>6TJ&8bm0P|MRT1_gTNS?VbDipU>yb^WNwA?%$f%+I#Jx{|nFcdMcFr<)-6% z_Z(bPvq{aJ$Jc$dZcpg{`%5is7=rG7W?6yzrbZ z1q1HQ4KDAb}o#f;Fg3S-*`OB{Yywc3!x7sg&>! z)pt1>NTA1`U=8XU*3Mz8QaB$-D4V0g^uKM61`_D;CqN^YHIPuY%tyKXn{*99@Nt#L zO$idL;p9BZ3P>nh*2laZmR?qZ;PP=j{se36r8;j%{g5?~P`2ByavTjLWIaodKfxM5 zQQQ5C`XOr|p={Yd)=%5uXduDu)%Exjtl{)1p@D?5Wv_j1_F6{+3GR2U$Dd%0bCd^8 z8Rr8DWpk8mR%x`_(Le${{shx4sV+XJI$;eYlr6{Iu`jN4G?3tNPu9_qTn(LjR7bJycfu!b{72@NEa%~9v88HTIj5~2NvX;xDnBzA1yS5*>@Mhf>_ zA}S++QAAsAYDKC9K}E~+VBF(RIAxW}{m@G&T9mG(N}b9oPEh&8J^lo1Pz|QKb&iCx zIm)(FyFvmz{shz15>2=5BB5;2KP8`1fP&P-|mRh$XfgXQ?Xih!<9tV}jO$idL;f&OxtdLN)m@UdS$LNV#V<1#^WO#tE6t&F1FrhzuumzSn{!MB}m8Mq*F`1<>C>gKRJ1M)BYImuK^T z^?dMOq=%yv(ebv)VRF#lfQU#9{u>`_uC1b&<{!5)Ajn3KPDmQsZiHEX!fD6xR!JIS zta6C3{8zMavbn{e?Pz!ijuOZ95Tl&GU#`I(gQDj;gs4H6P9xuCsdA6y5^k#8Bl#1k z;S!u$F7+!DqHe;@NJRf$PQ=?1L~#n;`oElTJ#IeoC^~N22K~JCaT!5TbHl2|cnRgf z(M-6lZ*EwPW8R!Ak4`wf%cr&L1g9!YQSlV|5Kh`5$|b1S z1no_gPPkE0qu1U}P5Ce0mKcgj4@dD&X~@4<=$~k9?o-=Yo48|?sPp&;SLnVRduN?x zVZv?02qG{_*?gqDk2_hbkK8CU(4%a_{_~oB_N^c6b~J(rj8ZmhOpNxnu4=YRoU5Tn z*@iuF*fIO~_|uL?5P?z3W{o0S2UypR?k6N#g7dJ<2xh$@TK=H$H3aXao@$rEJzH-}4#ky6WEu4fH76ud!kGK?FuAn>BvFtDaToP(z`C z9%UPLk9TI;wcZ=zXao@$rEJ#NP@}k2<8XVSfgWWWc9~jz?Jw^fH=$C`H7B35P?z3 zW{ui+ugEP}M4k_#N7>xBc^xsy(Qt|O^OsjrQG6^FRpIeb4&i8|u*RFMw$9f*il8Hz zDj%dF2pU-oBrrQScK2hpQ!(a*!Gp9c}tYvWPMW(^t{ zOm{3nkFv#h6;|U_5J96)JWAQDK_i^$j)~||witKAYTOMXXcUb{DVsHDq&D5L9X-kx z^G8_CA3+4o2Jt9mvj)vLraMQWN7-T?46AuCh@e?59;Iy7pqbNj=UVhATg>NSHJ=9& zG&{$ml+7Bn0x;b*1A3G#)+J%JE(s!Nl@X6pHfzvI#&p*{=ux&(_O=%N7;r=>$$L6Ck7E1rEJ!qm8I#fMbV>d9(Uby9JYf9J<26mqt?(>x$~WC zeYB&rkgnyW@tKLT4SP^!O8;DrYB7%(X};+pte}DnPq{*9&c(K#xDc z8hDol63XVNFzs{R;AkL$9)E&qyvqU!WgGU)FJ7TtSzhmQ=^~+f+>{`}8qN-{C@UnC zZP>F*zG1GLR?N{r0zLi&Yv5fLNGRK|zip98X(;JvAb}o#f;I3i3nY|n*jxInG3V{L z#nC_lJ^lo1@E)hSFGC$m(T3f;RIXWWe>q133H10AtigM=>b?whEJbsaO=T5wG>|}# zKLHxz90v(y%Y6J$y^5|O2tKazxG6yb%1WH8A)#zpAKe<C!HsTOZEeom;wbk3Yd0 zc$Wp0Xq-?sM}=vh(`{EspvRwJTE8y?kLB8;f6%V1+dq(?_6i<9f;Ff|!F?HuP_*dh zmfM?kg8E(D<4>>#-erM=vc-5srSFbcNYMBZ_xKa6q2HIG2t|u=*K$W!ouF|r?(rvB z1MjjxLfK+Au+%Jp1dZo$k3Yd0&K(f$j1wmm%~3X$2+V_UUxxDd6QCik!|BIzX_*f- zpF61%1Rqy<{0Jy3ag7WKWy|_d>k_A|1i|Iwdi)92z`HDvP`2By-1QX_vYw^KpI{BV z%K`~y%l@I(iAZpJbv^zBYdC$-H0XzfvSmM4>s=(c-?<)tf;I3i3nY}yQDM4|%w4x5 zfgXQ?X}rq<31!Q1SDk+#!Q-IvxG6z`HJp)Jlob-n7V}_Kokt2d)l%GZ zH6)bH^PoD1(+TwW6Rc65&N;XCsV(xsXN|a5sm%N&g$0;8188e{1iK#69%M6X4UveVP}dceT%);JnL1V$;F zHHy-;j5DM92@UipJ3WoBYwZ3x>SzQJ7^Q61aIUb35e_}dPEX_OGv^v@cQk?sj8Zmh zI9H0q*p41$r>F6CrXL3Hb2Neoj8Zmh*mRBT!q=0c2K~^Z?DRCgUbg+&uN{pb0;818 z8WreT-^Dw>5gO=Gc6u6L_v^FzxT6t7V3e|1qaj_he6nvTi}QgVWv8d{^~)}$es?s2 z2#iuTYn-8LuhkDV6dLGJc6u6Lhb{BqSw|y?z$j(2#v;0g+~{z7p@AM{r>F7tcdv`5kyew#-o(Y8dQV4=jGOi6J>-|lxSDB zYF9x7wUT(0vRQ*#qUE+-^e9{O4_oz*Ac9(ZJWAQDK|RWH`yhIhE&92w`gssRy*3`D zY}TNW!E(nE^e9`5SGF3jf(ROY;!(&m9#ZR6)sSpy05 z_!F#wyBSC*o1@&PL0JO{^!O7@<8B5L%1%$CyW{EVCqI|U8c66KHzi20hI1uVlob-n zPEVt|{GI1gSpy05_!F#wyBSC*J3Wn_R-hL6MNH-c3H10Atbw~3NGLl!jh?!2o=fF? zAb}o#f;DhA0|{lPr_s|R&U2}(fdqQ|3D&^f3?!7zQDG{pZ82F^NTA1`01Yv=BcW`W z5BXdX=flwu1Rqy<+>{^zWhKrHkWjX)5BYo)l$9X3d|Zz|!5X-mfrPT%cE!(mu?7;d zo~6g1U=7^OKtkEFf5_+6SOW=eudc_RU=627i8UM&%9g!WK6l3&NN~S%J^lo1;BE#I z%H}BdX;9Wc0zLi&)3}>~gtFzhE1!d84J3FRR30}aNU(-8Qj4-eLfLZukk50n1`<4; zyB>dnHQe0{o}-XZb~?>h?o+0$fdqQ|2}dLTlqnL*7Wr_VK6NzW1RXc-@h6?G-$3 zN|0a;>QS)&p$J8be(pSd${I*ezl(eP3D&^f3?!5-#w%Msm&zJQ(D)Je_!F$5?|&#l z(PG?no+V`sBxoFrd;AI3z}*Zalr3fh=UGzLK!V2exW}Jh4QHppopIuXqB$x|B?9vx z?0+baKLHxz{6jyMOUr!7r%yQ_PO1dK$5kFb0?I1YpdS*-mh~Z@K83Op1ecHN@h4aV zcQcSsw%e}0h{<^n30cq5<4>>#?q(pNY}r5L)2EydB)Gl09)E&0oE|0CqDUxP_FA>x zMS}aC>+vU819vl!P&P-|&U2}p4+7 zwT;PpBj(!FR)zh=-n*lTsqWvA&^?N%dv_7KJHbOl=;;(|Xt`!q)%BgkaSyKUO6!P+ zFVj;BE^)YJZxNL}xr((u?KvPuIksXVbWBc(^yq|Pr5x^i1%i$gkKz)!Q0N68LeHVf zIh9CiU|E4j5xncZR#4btm2+H!R6K} z+QBF1NMID!tgg|e{1EG&tv$rCR=u8X{XF1lNY#~U5DD30o()WuJQhZAs@&G2r%IN) zB)CMOp3Tczi6~ucubisVV;_Zl#LF-)mI1#mb;3=deSwpA8?=lBjsVHPA!-+*G3h=1DQShE5o!8i|4k`g=Tz>*KN!jsjT2i1$v`fY~5? z zjBP{xj9W>bEp0wrp51YAYx?-ptt#X41jFNUJCW&uPN{t`SeUyV9B+QO2g$C(` z>5XCm1V%|)q?U->JEn?Ne$B^NOU{<@w=GcG*{-ztgiWR~Zqe-@2NM`2?NCe-?_OI+ ztny#3GsHv>60M%OPUPc%$8IByAOfSL9g0cfod#2dMxmiEo9IEJ>Rn}p#==N>(g-3j zO4^~ABzEP=_W|B`yr+pCByQ=RAT*viQ2#k_;C?<)z!)~H_FpLscbu`g~M2TW` zg~p53ZY7N%0;8lIibvUTxN0XdF0xHWfWcJl*krp)sjQG13SkFiP5? zm?S<+>nAiSq%KQE4-%!f@;civN|!B68bJg`Njnsi#D$)Ng~m&_r=_9?iE?HaQ6H(x z`F?{S0;8lIib>+HHgYVPvuZ{PdXP9)q?^dc;g?U+zd-~>Njnsi#6N#ajh26Q%|Q>V3f2&F-bhQQEH5?o0^LrB-XB$ZI`aukVX)JQPSqI zor(AN4YRmi4*hCV?%l1Lr^z`g9FsPC!m*S$AEdvZ&#W@zO+`e!1V%|a6q7{b8>Pn1 ze*fg62Z@Uh@N?nkGoL!Ri!>Y};w3Oj+M$>v>fDfT^MoBvqlf=?WvaDKVpG`pz5(B1* zXXuT4PhUsw@7=ENUX#^1%CGAj561yurBs3;$DQuz#i5EY+mo(029to8qjUWP} zq#cS$qQ%@4p%J-omx&%ECOu+`e5Ai}3uy!q7$xmcOcJNZ-Yzr_UDe7&4-zr)%!FY? zC-QtAL|~M(LorF1@1Kiu+aFP^yNMno$|l??%Bp-qInoFsFiP5?m?VDqdAZOyJTu)y z4-)UDmlkF9(pS8`3L-E{+M$>vP9AM4G#+U`*hCK!;r+jd=^a9gDt6+vXb^!>(hkKW z@l@muajkt%rwkK4NXRP|?%QvI2t8^prOJIT&fcSPEP1}u)wyHdPoy%Dt8Hm>P3478 zg_A^CHGX^}kq!~@5*Q`zP)rh?ewP~GS{riEgT!weQiMi>8#-p5ifyJ(hkKW(dg@!MgRD9!~hFDNOZoxg3#!e*O@dNBH|@5 zO4^~AB);vtU1-#QtdE5rBt9CRAj;~4OZ+Y*hlqFyjFNUJCW&ru7Zzh;^W=vt^dRx~ zC$)q|p)Wd;hC@WW1V%|a6q7^&>n@>D{9uZO9who#X+Rq1s||gU-wEju5ifyJ(hkKW zQR;XLp;76siWYj1NI%2<-!N{S*^V?EBH|@5O4^~AB#N}@A~eePy4pey5|8wjeXvIB z2T8*rB3=Tcq#cS$V%0lxJ|Fzkt|)qtnDTrxk&o9e-bWe^5%CfjCGAj55>vXpBJ%Nb zsfkhaAaQ$Ven-*yYCAr@moywA;w3Oj+M$>vM&BUUSDW7ZCl@_P{5ALik&p6yOww?O zh?l@9Y12F?i03ZJG4a>UoK?%EJSCd8%fl<sNvp+D+!; zsQG#ddXSiuQ(x5i>Z1qg-yi~`q#cS$;;-MNMq+MOGJ25s|L)ILpY; z2#h+^b#&?j%|Eq6DNGz3{$cL$4KorSDw$!Tr$u6e)EY}awU0LNrs{!Z^K(ZO{wHx? z9bE$nu5Vgb+5Hn(qy5btbAM@bGO1IhPGHmn;UhFcg<`#rKSM;I6pJ)$&|)cE8>B4c9SI@?6{83Xk5D zTy1fNiJnY)`tS_ZdG~_eRK4B#p4{*M`8#RMYFz_~SzSX`!t9;)fJ9A9`=MyHJ!~R#&$xmHYLU zX-V7m=^99^z2*rk`G-&JA%C*QUr%10TlS6~Nlzcu35*&>&yrT(ve_Q^2NU(aI+@e| z^QK8p9Lq4#^Jl}M*0-fL+lxlQ~w4W=rhvM6aD~?8z?Q?Ug2LXm6s5PTDj93D zZ!PselYfao4-yyGS=Ol8^X(Nv%mjl_Ii;mbh zlQeFqkzio& ztX-U1ALfa67CVg3ssHALtk_wnbR7*OB5mKb)`mveqkiUA(r@j8oFy}?tdCA*nCO{B zy{K>1;i4CLG)k|^8G7RDtUk0`h8`qV?wxA=v?XHq5Ph)x#{D_5>SeM={ZA(_YATH- zAHDpFGnU-{_Su|vhudWT^KFKSo{mRfw(2*1#eSPc9Mm?9M<(Bp+x?!5?3WJd8b}l$ z*3z;oJa4!8i*vs2stUQC^D?vT-8z9$%V^vkdE_}~+$}V=R&LJ$TeF*O$}rJ0^jvxC zQjcftiiR^A#9PU#cbetC^328T$SPd}iGDPfl-TjKm`muY$-5nLE1W2i^W{RFz^K>u z{xACeYfsq|3h^8@a{b)go9-=~Z8gX+e=69n5$*Sjd3)>U1ylQX?QZ{dx3dDERLOP8 zw878hHv6z<&Y`}Dxv7gyhxlN-@fg+%J3qoZwKenQOD zv|23DF}K9lA~_2@`M@Z#CW@!(OoK_e$=TzwmptvPG8_*Q55F@Yw_?fe_TEaI^W=MH z=H5`<%zm)7PGA(42;E`&-m=_>8fRv`aBGH%`8UEfShy>`|Uc3LW@>ZatZ+$S1+vvI&lXVvHA1EUh_olE_$+|%~{c1*NiuqpS+ zk#}!w^~Ep~J*8-!7^0RDUs=Y>>cT%e#PyQQL`7N>i!15=eDi9GpF)hQp1h<Tt}+^m;Y z=k&XIn28=FTD|+2`H9)jt~8Ky-ZJ4*?)eUH=X`!EEZ5kPpM>BEN3s*>2I^f(oTh< zJFah^Q(?7EVAN20XVsH5KBmlKqDZ^K(N0!M&Y$y#n&`P{jXyiFTTWlJUrgERxok+V6o_D z7mb{2`wTVF^KW>i`Sj$;c7cuFRCWBfM0DA!UuWA7=^98Zr?-yPrCBXChc%k_DH$~n zZOQ()wN7Bv^G~fe|K2{;Zeua=$*|JVRrfE*9@}WBiJtG5WScb)ziF@ATF?+Zp+I>M-99)`%FQdz^HdOTjuQxX50U6W#WgN+oQco z&rQtvaR{Bk*=7M+e=!?=;=qH`bH3np=@s(pHOGUe=ycx^M#l{j?U4qOn8ZVw(M}`k7H>&1(BYk z6MS4ZO1mmzWUjj_k2z5 zjFPrtNaBIN-VqvqTS{ej;KjT;U=ZJ`H=Cswx; z8Y@oTMH)c_MoF8#iztX?w~05ZM4m6*)wS5^KN($fl<qvEUVjxXR$^Afl5oI;A-*DCl zATUbUq#=pS)lwsIN%Iu+AhEv5YeM6JeYeuTK?Fugd(dJ@ESL3R%-YsA89hi$?>$*) zy!6QdYJ))pMoF8-T|vBlPUfTft0R-qgTxQrWgndK=dQ3}1Q8e|Y$_{B{JBPIWSqSx z1wBYu4~`f4_+`Q~X@(I*V3e>)LlPf2cR;-V?$s&iL1OT>u|ngqn(vcF5P?y`CJjjp zboxh!y&ZGVgTyaSjT0KP8-Gq3K?Ft#n=~YG!vIlMk!^=Y=As9Q)y*afjiFoqC5<2g zql7(o(qc*cIZ}=#H>DiOMGq2(m&yLouS=PxR38BZMhTnpA&Cp$OO08fXfAq?*zxdm zk&iYdYLG?{fl<;HmSeoU5C-`yv3(1XNR)#O-mIM#$Tf(VR~_MpX*czl>_yEW`c z3VM)exa$p(kIuuJkwy@KQNpIOlEj4@`A!tWc&J9bRP-P*=xaACj1ULhkAhdueAXdXT93o9rJYyYL+; zK?FugoA#9iG4%dNL_TsmU1y>PiQ|Vxi24|j(uFjF2#k_8-Onb7r90DvMwR9XCVG&# zy~nFUBkjrVq!C15l(cErP7wQ^ts*pDNNi@J2Z^7SJ|i^VI`$-K1Q8e|ZNrenjty4{ zjhj|?G0}s>;cq$!jR~22eK&}}C}|H`ED7_)kHs~zA3l4|L=O@d2Q?QO*`a4iBZ$B# zX%AW~iG~|8gvN|xubSvVV#mljLSyS7z77{eV3f4!Oi&QDQa6cnwGsP=ndm{H^UN|r zPq*@$XBt?<|fbJxGY12Fi!r+YTZy zO5dB9|H4~YoR2f^o)?uB9}5Y7>Rau3Wj1;>+dgw@!*~yYQTh(nV;#ySRvmS9)&)A- zo#12yKHDzTq+-^b+>aYwBtrMtCZ}W? z5eF+-=Dhy1>?vf^o7mbk%-VA#sWG3?qi5~fsClH{JNE0BX}ofEi>!zL&S=c3LJcHn zhtA}^yNN=h>6!*vGuk#18c1N&mdzW??x&~OBLxwCIyvi}?>Y+tJ+!Z8^6uN<%TiVQ zelyERd-^gBB);#w+`Q}iiFUfsC^)Wo*0%X|*LlkdqvpNyfqCxl3HI}X7+Sqr*6`oA zh|)z5z1NvacbxsqWvSZzeu1oQW3Bc7dddokb~n#9hdw>Z?kY4U^;xhnjQ}|uODl! zjSaTD2#ws6FEzQR*9RNDslq61p>#jom|C%^*Ze|tiCK&(~W(J z1-g&R`qq}v29LYM6TJ4J`?QGEpM_7}S%3Z3T zUD-om)SJ%U)P!2x2OExDnRL_eXS3)2n_;1+^XjzJdYil3=P620RhjCaBz^GK$m|wG zpa+SEGb*Mw9@pKjU7Ix~*Z3~!`6V;6vo7icM&T7bI*)33BI%_Q)3O&4fgU8<-c@8R z?@jio!y2KPMU!7`-Y2_^hrp=t=7qU?DtEVUy_<=jKC7O5-?F>18~u}Ep=Tw%rJMKe z&eW~2HPV3DTDYc~9q)#`$tDkKW;m>XRX>S4cCk2UU3YMGqcJumBO4}no@rmu+h znbyNTD~NO5Iwh}}{b5!QI-f$%Ioj3bR#Lg4H&uO0KAHSig`rs={;j79iBqqZu>MKw zY5z&IVayu%e6smi-K-ltgdP>PxUWoX!bHa3uO`3!?%x}S{KYGN<>`{p(u$OL-o7r; zo2rq^2POaf&*6<7h`>@rVvO;iHKoc6b~@39ap?X?^1a*M-FSx1x{<)BH)&UY1tyBO97{2#gxJbh>qR&TzYWn29z`#wEA@tl5T>XEQAHtgSo4n%aAW9ib@9AHC_e z*!bjgbv|3aj|lW2kte=GG0q;VPj!XXXP^k^ydkBmgS9Gzpbo)5l7DSQPCnT>u zcc9^1BG5x~l(?s)Z!>SI#&;W^eAS)()^GP{Ao1pxYppM5PO;x3+Avx-nV5X=_bH9W z6M-K0o|#$Ay&82N9-I7QwL3Qy^^`6Wjoal~1+SWEzfUyv+JY043;oi&(G*XrFsl7U z%laT=j%~DHqW#X1$p@RQ*f5$jbdOviaTJz1UFE%cLNc$fR(mwu)l!_GH5~6i(Dkc; zy$Nw#Ckl5RXl1=*Wb&B{s~eA}RN-;!Qrer1q$j`KRK+zOE-*3q+Pr7i$8+v@kQkAa zYkhh9VtcMAt0ng6?f9VaBOxc2&Wi-|zbO`k2YinU*F zZ=m+7Yy7X-_~g5bf6!=`M*|7j@;5mBV@%oc$^B~XX!N;uYINU z*yIbpz1g@Jl@)p($eeCOa8aumjNl)n_!K1_*w4*4;k~!-}Cok@N zvT<_{fl(v=8fLZrev{pY#xC0H+A=b^&yPt>xb32cN4o^t6XbDFPgT}Kk>qZr-fi-y zM+1q-pAT5epWkM`AjaMF>4TE@Hu$sO6>T2@~N8j5{tMqj-$bIiA$WEQr!Bs_b&TKF-L9O-y?a#o?(eA zJOoDZ4EG1!HOq6NVf1;qQ}T@+KTLdrW={098?YkUVErEZ49%~4s!mjBnOt;#Ug9r1(n4Nfi>2bLsR}`Mu8C=QUbi9k^#^QntJH zacdBw#7d3+F3;8W-|@%f?OQs=z4+a51guQdm^N-BQ$#l)!|0;5je z{cmcoHoNUUg2-DRPI~l@KN4pVfu2*erskFrUsK0(UT;A0r1tyPCT{g;AaV2ghGxrp zJM1lD-Jbroop|F@LlTdB2t6unay#ZT3wrx^laYxnhc-?;O$4>@xTo*1US`*FpV%)^ zlwMYgJ}I0yW7^p!d?t(@Bt{;6!CW?Yi*r7>_>)sjN`Lr6llU2=lS7Q6Z{?UgO7M9* z&1(IMG?~2hjV62^g`S)1zh<@x+v1E4wdwh&vJE#5`r-B_e0GN(Bxvk1d4!YagY(vH z*w}pMg2wT4H78XV_0oHD%}4Ibvb&2^6<&97V}r~Kjrc4TJtcR~H!Hlj(e80sS+$>C zJZt@wu?@XBM?#+CZV+e1^rT|Zs#%A6Zd~srFsj+H6=r1VDp5C7XT4izO{wtO2ENXK z9$NdDd_Q&k8bG{Vt$Q^ot8dHp8@x4$M3Wv_=0jta*<(b`-}$*kR*Tsqg$9-`MvZEl zZI+p^)E*~@Yll|Px~6kMp@ANnsZE~4`HBY~iJsniBQfiZLib;mDkPqtXPH0zJ>Q-x zH2T!7kag`ZD=#Z6JxX2CF^qDXuji{#5w1a6$(Zi79+48~>X4qQdsb(O_0@TLS_nNz z{B&}2nAc#(kMeyPK?FugI~0>dfx(-_b+|R34YSaLM34T3()jw-dw=qM89@X_37hI% z5~Vt~7S|JxogQSN2Z@n)(v#k#G4Fvoq!C15l(0!d63ezO78=`E^s~@|#DuF_rg2$y zpIwtQf(VR~b|@x^{ryh~jr#^YVW9_!aTB@;jmiD1lSUAMQPK{@B=J<`a?~>Dy-V-6 zvCxCWt`_};#{Da+kwy@KQPK{@B(Xl)L})~-*RjxpM9v!{gvPJuE0RVKfl<LJtzd%1#h<{=b*`$@?Gzql8U$E{VsM_7oaVe{(2`9whA7rU;FqZ}Zz0 zf(VQfHfc!Wy)rKgjcX6Q5k(IYBMQ7J%4&B5zV{=Dz$j^lVv?xch3|bdjN!#KJh3VM*p{&Tu0t9L)jCXFBh zqof^*Ng}a`)X1#!PYQaFm|oyDp)nwLBxwW@7$xmcOcG~G$+GJ6>jx?5L87iTUTA#1 zxe{pv5f~-yP)rj0qEh40c@0z0gT(hwjTIUbAA8!S{lNeNqof^*N#fmKq{c7JwkD$o zi6ak=7InUN*0C_XB`tu!C}C5bOJXNI_rd*R%DCDo=s}`IFB-3C{!z^*E#4x;-PnCJ{lc7 zOd3H1MhTlVByn9Msd4t6xw+^;;_A+0L_Y4#EZEdAf(VQfHfc!W!o#wE3~cvPE_#sY zR(6umSpVbgq!C15l(0!d65kh>`S`fc@?7*F@zS-g3yt}gYLi9~flcA%#L}(L2#v{af1QdRBwl(~_Q9;akCH|ZflJh_rAjE z#m*txa}!ADPYJENyK=Nwt<K`4`VeSf-bcHP^B8 z!uYl>j^^KGg!BGH@m3Ai2+Jb{YvkGZ_C@{uS3<(k(4TOTX`i>B-%TVn zOkfmVLDC8IAc1eE4JI%OuY~CYdXNZi?MPr0UeVJv(1Qf_E}g*l4&wU(@eDvG(1Qe? zm*@n|gSNZMIQ?8RS}Vvmap@}@$;ed(dXT_pb94Woj?x~c(xQw zU=+ToR434b1in92Cvf$u-xrSSQpv>E)He4CUgIKxcdqLiZjWLDqxS8YFOJmmJ6Q#~I@U=*(5bpp!-%L>02pcCjp0-u8oCNK)Wd!Q5OK?0xW z4JI%Ozu%w}=s^OXOAaP53co|46X-z#pRW!kFbcn?p%dsq0-qBPCNK)W3!)R~K?0w5 z4<;}Qzi*-w=s^OX+Ycr%3cu5$6X-z#-#-vcU=)6DMkmmN1inWhn7}CfZjMf%2MK&1 zL@mR^dN!r zN-%*@__Y$9Ko1f)9_s|o`gn~rcm;qSB=G8|u7QLem7gnKNa)u^rAmC25$06}Up>Pp zT(9Vt=0+jAc1>G!30L(`?qxhJxJglQZRv0_#Sbc zKo1hQhZIa;6uu8#C(wgL@VOci7=`b3*EP_C1fCn}gu7azyZzGes*3)WX35C5iykEK z`i!oD1V-UIr9FgrbG3XAH4?aYA535rz8hO7(1Qf--3JpGh41**3G^U=d-uTvM&Y~4 zbpky|;NE>Ofl>I*b)7&D61aCCOkfm_V>*EzByjIOn7}9;?Q{aqm+(BQ$osd5^Qd-3 z_zM;CCtEvukiaLhg9(gk+JW!$3B?ZW^q#As2MK(#T-QJXqvo&RFa3pL%OYM4^dNyx z$m<$NU{s|`wS`98&3qq#{K>LH4-)vKe=vbjW8P~dG>WYCo;#xl34CLLu7LzbJ$qHE z(D?j?_MUv82MK)hg06uCM)fExudp@R(bl7Z9whJ$61oNw7!_XHTI8c#@&g_X^dNz6 z!q7F4z^K9xv=thQ3%2oSpa%(jqld161V;V(Rwtp+s74Eq26~XdH{-`oB{;nAF zXrKoPe3O!{fdocvEEpCVm9Bovqk$eI@QqNq1`-&B*WPskJxJi2t%3=R!fWqL)Sg85 z8knn2O}asxrP^OjcJ8tW%j2a}uKDVq{3fsb8xzt(&)l&5n;?X(UF#Es+!^CIE=`v} zJI|)O!rrV{jWrJc)+Irl57NCVe3uU1?}J~4GK^_QrU>G*UppnB2MN3*iQZ!V+1Uiv z*l^QRRgu6b{4x|Jc~b#;7LCek*SZAsAc1#QaW45M%L)mM!Y@O~c$YvA5_pFg-I+O} z>LMoAcCC_t1V-VPq3HhIgV)@_#HCf67oi6Uab`iKF7JoynlM?E)xKf(W+H)6_+=<9 z9}&0x$ZxgD7Q^)~uWN8D*SY-3veG?@kk>dkl3R@YF|nwI&N6@8;<0^ z|8s5>eVv{@T{HW^%DRU&Bq4XUn8*v$J1Pe}M#qVmW%qa0+7*8L3|lBY1JG-ssEHE&T^kR>zLtm4F^3+#W3N5E@YMA3=1hT|*-<3hxl3Z|eQLTM%txH4}7?92xky z;(7_SMEN%MB8A_oDswLCJnYt*tHJdw&se#HxCZ4_k3MPg?3E+Am7HsNtEi9E zA#1B)tH#!j-zcLyuqWLlh^}Y0R6`FEcz>#4jA>m-5Yw&68i7&xjWW91@YB|!1|MGj zR|0yF!24_slAU51q zAQK6U!f%ur#_eUdh#vL$n)Oxj88x>CdCt(kis{zivBr;6-E*xCB2B|4oBkKK>F=@! zlTZ92rXpOAM%b4V&R7yw9wy>6{hfc@O5`s-`h?~G*GC_jLiXqc|3$SvJxcyvyXVfG zYs1V*52uQMuAX7YJND+?Ut092X?s(sjPO{J;3&OE$>YfWfzOr5`()UgXXCRVB0l1d zKIlOLztu@^Rr#`NH6~u3v#=Tx7$vR&Q9qYYj1=x%TeK^q^3W>iK?1)yY8YS59lnS) zdd=^biR}uXwRB5Fu1j`Qe5W!K@Aj`nq%14;AR+c6dG#UQelhKqw*|32T_^M?S<-SZ zbP)y<)?dRHT?k13gH{-Cp-y z-l%~DM#(*I!zf+0FljXWd88=a5tlL((1V27wWj)z@AAGUEm06(9L%YT1V+id`}3Kp z%daAhr2|R`V!@_g7orCVvHMOM@?GA4>?tgWEk}oBB7srz9t8Rx$;&5WhLOGV20`SE zdNmV0NQk=#;_vdV{n#ynNJ=SC1qqCjJ8{&DmhB^rE|DJ{8TG} zb3Ui`swy}a;VKj7F2lI?Ye`J~?ssigLqcDRmOLtn1=pU`2#mrf9O(@L1)mkEx@Op< zO!OduU-zVU71w$~5IxsTsiG0^ZBcx}(J;zvsUe6do9?KF9y~67rPMI$)|c~n{RuM` zAc0Z%gd@GVeqt-3(friWh3G*7zqU$G_&wZG5Z}EwSR*hBpKzq7Wh?X$#C=6?$wUtl z_|;g$SoutMLELq2*Fq#P3ZHPKH<(qeFNnNuwX32B3H*Z%p7=;tHH&s>BAM&T2VVlIeqYiA2RNa!nl!T1mu zg-SYJIm>ck@SAR+D%rqM^frC>|Vkf_1YH&4n$0;A+p1$2es zNO98Gb#Dbhl->1aCVG&-_b3=f-#N2Iowxt4%_1Z)NgIfA`Gj($F)$@n)VY0PMOE}5f$tfiS$)uAQC2<5 z53Gg+M#-m#XifbUuaLL&ShI**`;f;*FG3Fz_`Vcc>2Fyt^6^Z;)*69P`q}o%5?iXW zhW*^1ndm_R-}^$Vti@TPm6R!Zk49h=o{{PG;huT%c_yAg>Q{=f2GN5Ap1o4r?RQYD zOG4$QEJOmMRPqmNcY4-#S@ zhvpCYb(QHQ`T9b{eEg$ARgu6b{fc+yk9>V0V%|~s+N$V50>7a`S0HEKCWuG&)vSgD zM#-J6L5t)rS(QD1iMIRW)x)Zw2MMv8Mfs3lSJ~0DpwO7zV%ncTzs)DHT?dw&L zz$m%%dp=X{BA*`nni#L%OscmCJxIviUia%N7q`ADW`pf7l*vQ_qvQ@Yy+u~+hCiS4 zv#9fCy{06f2MM`r?S5UQi6#4B(SPe#K?0-XPP}2rUH!8aQbo@1t64Y`JxGY%cPcCS zb(PN|H3U&7{iCW#V3fS0fWDP3?oLR%?hZjb^vE@t=s`l60c+pTr`%kdSw8xnEZ)b-IQiZX4KKBQQ$dkw)(?7k9T!ZQD@nhX35R zz#{Y@A@4$SzpgUqRHFo*aca-HrWz6$CGW*MpDFLsdvt11QC7e1E1!TKB*fix)Ia3c zRi-q&TC~JIWlC!VM#(z_Y1Jp5sHz=#O62^xp9&+b$XUZqThAzsj#yNjA{q_X(AR(U;bHA>V_0tkjx^LJ&YJ?s&*XH&ocYf*|mg~gP z$JNi(R^h8mltMxzV0QqY40&f1ik00N_= z9g4{{!_s5&9a~RLji#Un37oa*8gc-EQPK{@^ zhE0DC747Pk%2!3vg9Ognv@Q!EFiP6=?l!Sz=y2&3p>gERF;Vm&fwQ(@1Q8e|?NCgv z8OrqOEi`_M?T(@c37oa*YHa|4QPK{@^tYc{qf!X?2&i698N79t5Nh#`u}<1x1YO# z=J+YXcBA>tiJd&Ft{#Q>G60)!O^+7xqMseSCdvIJM z!W!s#_xd|ygXsH%Tnc!kI6;PG{C^%q?cpNJ|_yf2l%3wo3a7snVmkocwYwOHg`{;J)IfP|pW?xYw#NDnA-X@QC3* zChDnDQ9Kg4W3Zko^zaC$#`FB73JE#7%DF_>z*J!r&sXkDq!Z{VHs*S0OZiC^5(n6WXf{Enj>8fKJH$5781e0_H?pCtxPC zVNRqd&N=_`Z1IotpNNUag4sErsX_u)1|AK}2S&k)!$ZK_XTvN?Q9=1Y4-zm_do+;1 zC@ez*e!L^j>asqd&*!tOkbrT;lPWALjKbCfiK44TFay{ympG~7SZ|%+jKX@-3GAsbe$a9A)7p`Mk;s!OJeD36R3BJVNWl2$t0DUbMltQI89W5G446Nh zoXaB_@YDMs5-?wRG%z0+1@ohaKo88w6qTQ{LIUP?j|LtKqi~ck;1@Bmufa+-pZy#O zSS@=}h5Z1dU`6gB(8FVtbC#0NR3RZpy9gaW&!eHIDt?wiQCuJV^AhO6<8tY`DU_uA zuiLKVu`mi}B8_m)&-riRnCgS!nCi`8TA!#No}Y(fYP1W-@J&G~o>%(lK|;-o4SEUmAfaaJ{~|C-tp>aVdQ?5QoRd^2)8Trs2=RL5~o?`YZTD9EL9k#)9t)$?TEa`9N3Bcpn<^yKI>@Vmslq6=?(!1o zQR}w+rV0tQ0`zKNs`RM*%mzrXo;*MI*Wh*#j$ste)OstSF)B@7X%r(|n!IKicE0i; zkE9cnkFeWD>9}d~iicPMq{(aV-c;dzuhj3-R8!XDP+ANToN ziHO*j6S_wcs4WiS{3l`|fl<_hL0d6m{)l^!pb;ZpZYrKf25NorGNHDcCa*@hc?wb9 zygA3xMS}WGn!MumUj#-`e@v5C)w~4F0F)|O?lga-$t%MDRp*#nBxvqRlUJR+8c1Li zwzqg$MYyc6&S~_45>>SsC&&=H8DaUCa105~x!b0L35?=$yDT3O)<6%}hg(+IDuXqU zkZr-Qwd1icihGyaSK=BXRp_C9o~A~F{FD_EG_Fuv;1S4MgP1BkiZw!4XuC+To;(xw z*O14;C>&SfIVXdAt!mX==klsEA2&a#LW0|y|ICTU!YJ9M{c?^TB;*)l`;;yc7{#NH zf2z>KBaWMMJd$2k=s|+}p#R8#1V(WW_8)!F!y|(`!r_sEQ-y>amH2wQx0T?rFpB3A zclOaW&_k=fc=>&R^IB@Ts0sR9BjFNxnqxKA{HJCqi_~g@zg)~ zdb`tp^5_~e&z9W!+-F+2?dH+{S3hwr+!-zNY&BB51V?%a)j#rV)uUL??VDagJ|831 zF;#dZl_t&ydXP}P%d3F|Mqvtd4NR|^Ir+HmSn^*QNT`|mzX*&{D+4cqb)e?j|Edps z`UnX%&wDkHz$n$OyabQV&Yloo*>>h7j&f%lFM&~NR{JjkkA;MqMZFqGV3eA*y#$uK znq}Nn`SlNM4M=c__+Q^eLXQe6E6fKHY8Lh80||`6deU1v65K!BD}vY-bOJp{$o?3i zy7#6EJ!&1D-?oc{T2p&9FjW|(R+e4@TeTWR^P4Ip4#Z~zuLha+0L6P^r)HB&H0s5g@l@^y&9M*j8ZEDFM%Gl%E)i3kWi}{uLhfC^jo1b2b1kX6my+1^&pF6AZU*yc`Mq%$#@p8TEo}Y_5gxupg-)a;`3hM-q08aY} z!+1qe@mbA7pa%&UD?J3hDFS*|80HcW0X;Pg{ro@jff`7_7^5^ITvkZvQJnLDJ0Rj7 zB%nT&hQS)LtmLsU3hMkn2$-Yzjz(IY@%dn$hrn`&H3LQErv{OLHHt?AkA+dNCh`zi zx3J2{XAL3&D;$po)*wc~*sh2O*9Vq6^g)WsU!A*G3i86x|CNT}t#gdR+N41Fi!gz8 z%RNfn1DBsvA;G=bS$BmU1@VvG67{J3v=Ss>{ot!1=7}&y;TWT*3fm8?yy>|4Nfi>@ zyX2X0-hZSDqh#xmsnt`39wcO+x9!XOAQBh_^M@x@=z$r>_p7>`I(NL1=|uu&IFE*& zD)%ftFAOuPhd>X^&iPCg60jQZXke-^3RWK;0zI&j$!DsNIG|Q!9t}(tM#;Y$^z*hW z^dP}{{(TS$jKVpQmE0enZM)~l;WRbwiuWgmovUgzE2tlypNG@bm>BlFEffjW62ob# z?YacFH}xJ!<|3wiE0gpfq58^y5qgx{&%J~i0m5lWs6PK+1V&*Qs(f=kute27$j8l3 zs*q4~@PDNWqtwdDOJJ?3dC;v7&ViS}w`3uq=HUM#FiN#VFQI0caGIL0IEu@Pe_jGT zNT_-6zX*&{v#6JltuJD;x?1(+x2%v*D^9NlmM%uARfd;P<5f6Kjc{(NuGFKDP$Q~W z1N$IGsS(^uphwLa`AroPYWDGJV5%?*#~9IAod3|<($$_|np!9Dar4s$kx(lRZ>sQE zdQ^VeE)uNgTzjPysvn-Kg+)HxDC{>X-W`3MT_hTJ-Ib-AbB^`Thx8!9qn)!8`yZ*o zC~VVus?dW3kHO9!t49L~jKaRDYv3rO=0Ue5%KYgBY9OKJU2j<-fl>1BSL%aEu%5FY z<(qSPER4ebujhmMLCo2&Nu&PZJO$xCi|&^yd}195>W|J-5Z;_4fl<`|ou?qY1dTW` zXNNb9#uDe5A2(Hg^+BU^Jc`ElI88mxmO1unpgLo^MC@gioT}eWg zBK5&|8^aRO3G^UAy_RZ|&vCq|LIR_(P3syoTE^U-L*pRS0hg6uonuW=kBZZ%t!tnM z3F^U=57znbe5fdSBtE)7Aw76p)^o>s_PW1_iO0gI;C6+*h|5Z~zWlT+B)HW5Q-$qH zj|!>}Y*$FooET8LNMIDxZd-86iT@QVfOyN0rQr7M{GBqHAEPFp7JZvr|ny zSpCGgLEOW=*4Y84sQjb~2_7+=-FJ@$9t)$eKdLlwS>fo+BdWW8!1ksS=s|*K2IsC9 zPpXi>D4u=Xkx$n^503`!IsuQQ6X-!gjw=!SN`271znyz3*9ZT+y%s%qTrOQVg_4y2 z#rxaEIcGcy$9#=&uJ7{SoG%W+mxwyvHaRT+t{8b8PI)Npim=t+9U?+?E;N*9Zak{c zeL42dI?H@C(DUat`|Mjk*zH8k4XYzL8uX8@fyBgN$L!Bf(RQGX=;YQM9; z2-ORhi26mWEq&Hl^LE@KJm0p+q0~sT8VsZ=EAS`HTAJ9P1pTd~;4>5lb)Ku<7O;j})9L>eF$8%Fy($ zK|B^lQ7;Gw_K&y+32HH>f4jnCVHEY1ub5B-!aL42)Cnqrh^2efaar$&>Q!_?Xdr=6lk4S$-}tPxP6!S3Ai?FV(ih4-&HeYv_c~KmwyG-MTKkvHJ5mAvDl~1h?Z>eQWE4&_DvC zdb~3;T%i5LD(2u2}s7>2}{R2FTpmuCs)<1*>9t)$WZ`y(VJnlh) z`lEGOKNlK!ER3Qt#ts~>;vOVuT%i@9XS@;`cr1*fvCzG&QD(_;&E9o za6XT(=rM{*!FQEmp6)b~*3>Iww8o`zV{W+9y|aWpr%OTep{^^Ozq@Io+1b=RilCJx zjXr)vv)ew3UMTc}dn_yEa9_usYrA?%fi-kOMSZdN?&v46_>tleUB&4%l2+R?ACy8% zPdlG4aQ@Vf&mj3HJxB!S0||_xRHgc-iimh_vnN-v)~7vpg`86z#LEPUq2-!chgfq|G)DoZdA@ovIH0Dp*^1pgnVG6lbR%x`_M?*iBio$yGYVg$ozS5YU#`&na zp1fT+1TB7@Rr4li9k0LlvuC|KjmgphkQCx;f zTQLz6Q$_7Kwct57C8&o4_d8czCk%5_mG(Y4M}m$NkD{_N{maTzik3QVP|iJN5+}HC zsyun}VM9LRQNd+}>7_b1-8%Q=FD}9@QI!=E)Y{4S@D<7mqgK71Zk8U)-&yyL3^Gdg z9M(|%PK|c)B#{v@v9Hl_t)B-x?Y7EzZ`KJeU3ct5qD%Q9);(K$_@oL6Jt{vns1tk@ zse6EiTZ5FZcofq)jrqH0|5a98H;^Y&m4eE9#KdE9&Q%@cCm%@2QV*ze+sy|?;kcsG z#5G9Ajkg9$p{a7K+M7;bOVkN&r2(ZIc2mWgDoT~x;Pb>K^S|-YKmw!2-f}B_lj3S04fG&ESEe%QZeJe_BruAv zQU&HC?m>dj4FmHLCoqbyQU%sW+=B#_8(r}VsE;^-QGAsuuwBJHNbtE@V7rPF7{ynq z0{aJe)N!dD(-p6P{t+iIimy@y_Vc(03F?n_U_Xx&7{ynq0>`Vk2MHQiZ2H2VPrJfn zVH97b3LJOi9wcadv;)W8IDt`ol`3%lhtAKeh zPGA&Y@d}*J!K04LdV%wKoWLkreb|BPlDG#6F1NsSNu0naT1DA`>#Mj230eOE>#I0{ zQM4Mg1J{Xh4-(vt1J{XhLXT4Cq6YlLx;=iDiUjw^!1ZpN(4*8fAj8=3Myu4N7YCUo zS2tUE>X*gQ;`{d4wTks@dhcVSqn(<6YA-L@v*}9OX=q3GnY#68M#$avMs!Zum(7~n zuUfh0{OZ)bOZM1ZoA+#LbS_|?EW6v@)v;&OQ?!rs2iaX}GBL1n^=OHHL(B!sI&Pdr zyDxmK3AO5dy#2%esZTuhsr@0@GP8T_{t0v>WAtD1b8FVgFkAODE29UA$hmZyqxRZ8 z>M*?`xo67Y85w5d9oM~&1V+`ZS~I$Q<)`+qWm%(4=@)Zfn4Dq$)cLK(NVG_7kXmEu zr}ohXJ)2@`4deOlrJ`q=4mDe!TUHZ2NF3@qI`sj{Unqq&E^QhRUE6Vh`S*1d>LP(r zpC9@yb+P_&Fl}5Y|9P}+|6b;n5C5;S zbAi`tO8@x&XOfu4EgFQ=#r@W)bWYT}-g6{HZe_?Qx~K?=P^8nLB#gV{Ubz=TrOr8( z^R9iOgfT8dnhA55kkH>Ha`%6pb=l8v@78u_P_tekN=&N>VKC>1H^qTVCh3bikE8;OmqdwPOU(>v|+P3Z9b!b6?pWW`a z;`#U-Lk!uit$yvJW7UK4%u@9F?jM(_a`NhN&8W&W@lA^Z^}-=a?RmzH3($hZcGIV* z$2KpIAN~vHW3Nf2deX#l)#|*K>9q1})`FMcw9`@afKW7d9^`mBHLt1i+n9*7ns&LQF< zB6{A-8qKPX*M~p(NA=v7>lYw_UY9&DTb6_r*)%VMgPO^Ul!i8n;r%{Oy5Sv>;*M zJE)6C8e+n!m+9k9y&?DX-RIZ#JAIiNP(3dm{@kd_?!%U<)22NUPb070?_R7H%y>E; zSI>8K`UjWjRy}6qRzJ|Y3@u2|6D(C2JwKjkG|JDoNI&z`yxhX=nmvUCdMzg6B_eXq zn$qnvMjv+2vRp}ztxM5@M6dtMSJm?tx*m1^*XQfUUTMg6YI|@k66m$#vrnnV);$xC zt6`0I%SPyxKmRA!>ZXUw(1Jv|tgg6cxUN2HL+kc)FD|He=xmOgDShAb zTJ81l{qZj^u*T-wtMtn^zg_=B$7Qu>LE`Q9TFn`EZ+wfXk1n50*8Tqc;_i7{u_s_$RCH9k(W#tyT` z>E|l%FU(rMOBoXA#iK;UjGNu)^Xq*V>%B%kRCx8Nt_#qD#8X6cCc=(BU24wPUw*f| z@N~lgrAVOHx>KK02d%py9&7UP(bZ#g*I$+t8mr?nv>@?Iet{ZsTE}cZHUE z<~EBc4#%T9DX&$^&Ze4O8QOW*%I&=~&&T zMO%H!)qB++95-T9DX}h`Wj46<`#7`gU7A zZ@{toxSbv=MFPG4Gw>`mXZ=NSwaLf02lvozDv#4AfBt?AT9D{_-x+G9x+rdM*1K=q zx2^vD5vS>4FMQVx3H17vM!1`4gfo#vv|&I?J?ZxY_0X@oEC3J5uLMTi2ll2^@o?=x^W8Ewr0>k>382e%*JW z=%<86YL0%7=(0KY!5$;xw@w~aIfLTeGcO%#;@v2EukWTp{~w3wyEnD(j@RY*W5T7Q zO~is@KDDd%e=EGSVzfScM!Qn9Ac5LZ)U|w8;m#Ar>HnQreHaqx_0H1OxqaUp9xpTT z;G?6?DZF~}<@%rFpRPj-66t(={J?4T?H`$}?|84S?xcfSEvDzECJrAsxm~V&`jGgr z!@4a0*yY?t!jBKSs<2?ecs=K_c4b&T2mSko+}8IFjVp55vO4PEZiU-6Ow{$OTb80a z5^0S?ui33|{2r5Zo4ac|A%R|}K2wqF^8Aqa2eaqU?Dfy;hxMt_mu`N!7A;6%p6K1X z$C?+0zB);--uaVq^m^fq=DBf$hs58Nj;h2GiK40Zb*`V=Fj*h+NPQ_p+T0VLK66lqG{*n5>cNh}yR>~`x534@u`NSzz`kv!%sY44Ayoa0zbN9|ERPH-0-gU=Om7D2}PhN3!=+W_k1;3-?d$r?sz8y@0n2FuJw@k zwf1&zN$zU#(zQKnuc^`-w>z;j-Y*iUO)KPfy>bs%PSn3tR4qUPy|#U6cH!ZYVey^j zuD1VtNN&8oT+cbFx)v=+r1Nq1w^MSfPam&eUA1pHmeozKeNuSnrnBSgw@H^9?ZHla zBsV*Mv3~cGPMxrPkhq9SdM7IBAuDXjB7t7h zq7(Hk9WRW>8jbNY+o-BzPtdbQ)YPH{i5c{c@O+vFKkC7Eb={%6s8hE+N&o)XG2PJX zl=m*xT`Mn(@BVURWtzC`$c}2%kY4)IW%nJ179?&Zji*WDa-!)SscZLB7vEN)OTU|x zBG9Y%!pVBYkO}elo_ts8k6qQcFAmrHPyC@4El4bQ?N+^hMRh#vGuCMST$$RXM`yjE z(|%=0pck!)G_Rt*QLItj>nJtrFZ<}9T5Oz;79{R#6d?ZeM|>^{OMn$2=tmV z?+*R#tgGS!^Q>{+dB>{CC2jToH@#Ma79^@qx=$}InHo>s!1=iT(__@&kM`E<^3T*F zfnJL{&(yb$zB;Zp8vPGGMRm( zy(aAcsQ%|y*Ty@3GO{vF{Le>cs+V5({@5pl z_Sf~TMGF%1TR*M)^!rQPY(3}vkgd;E=l}YT!oN@KUXBEMt)RDxIV!rK7w4mJzy<1$ z&&TFWVYGyZs*hP?dh?6b{{Mb-3&PXvwav{nde8Q^#wQx$pVKZ<9c$+n7MC4eLiOZvi-0 zxhsCi+|}%#CaJauMTOjkSv6=u;=Hk1kNeYo@gk#f=+9MZ=39&FxB0cK90~O5|FhOl zPM#Gh2TwC`Ahrw*S|;vEHPjw<={o4Il4J$yJ?khpo$B7N1F^WzImuf1T^Sarg>zveo;xAikf zpw}JoBHg0X{P;36GOS&7nd;GDdTzJtW_Cjh5~mJ-R`>2TH~zr1#9ME^NKLqAZtknS z+b%&168g=>`j>N`c4Nu9$0w@immircY1q9x66l4!Ad24qWxSfQeN~Rz6Hl_*+y%>cEi%MR+ZXPcK}oqx60o%)&2>f<{;9a)JjlvaKF_EuAN zZLfx2v9uFfkhqK5^bBg#cCPJzU74yH-&u7Zy9e)OB&{92uKun{AG_|k_&l>_nDd{U z>VL<9s(1VPaX1M$Ug7Z5CA(T0IBZX~ z{rbLY5Ung1|8A)6@!`t&%1wMNdRjxz(s=z@MZ|$b*tO3AHOf)=WM>(kY=)~%PI1&MS% zwtsg!HF5N*>X^0Z}G<_nz-Ykx?JhXG3vBdU6-H*364wn zsXoVsv?ILn`rN@IE>qLq99)iX4&d7Y2ld%pxc{P8;_X^+WHI=FPje$j4p;fB{#B0G zy?1bl-tYdG;|afxH1Vfsw3)L!*L&6ZYWk47=A$|ikJ4RzLw9B4s8w@r%dP8usrqQ( zv{EF{>*NXZ3y0VKJ^seTgWvo(H>a<-NOgUrUw6D;%m>mGZU3QH?zW>Qs-2%HUxF4S z@=wezwE5!i@eHGJ>53t_1r3+0pN{^n4hi&1-&Nng?v(2?XcFy#?b;pRTfp}j@EwgP zI(*r`dOWy(vTC!k-4e7QQS z5++zxTK*m|~>Fu@wGB`VGb5|Xz4L%x571h-dj z2@|a0dX&*XLejRM%NMhd;C|;VVS+Wd|IwWp4J0IO$1C~X77{#ucuSaI4L8CW4J0IO z$6fg<7ZN-UdP|sK4L4F74J0IO=MVq2$27s?xwnJ~)^Ib9(Lh4dTvqtKJ|xf*CRpQ< zs)api9%PLO2}w8d2@J{IrU|r!30GD*>QzPq2}zsNDw0w+Wt9;4)ypu!8dQThng@*r z5|ZY!!f$3GftE1A8q^Y%Yr9ldaxF=lZ>uN0AWh&GFvA3EP>)jlkE$a=LehK`Yq*xE zIUh(!+V&53@}^zGacegOw^wfo6RhF-;1-0?wx9d2FQy6Zcis{vScBHo%CD)BkhC4I z2xszvgrx1bD_?a)g2zE`2@|Zr{f}2n5&e*mw4FcXi;GC`c zf;HS6Wi*hGw4VoU43{SCyksq5f;BL@6T+N|NPXMTaMFBZoF;gFwfQJUMw64@y0|{Oy*!pOU!vt$k4F=*tbAFVsO*$9Z$8fBH1X@IoPg3>-YlP!LbE2bf zl?}W)v%P>dkU$GwSN_f#Ze?l8N-T}Br1K5D%Cx^j<7!UStzbcckb^9>M%kp>cI2@|Zr{f}EpL_Z`XjpuuFK9JZU`Cf2i941(U zBQHPWAR%dPB|aWx4J6PKCcK7^?vRkQ&4-QpyoM+Ey515dpsaY!0P$dBEVQi;8}&h1 z8G_5lTfziuV04Fsq!1l_50B^O`s)A zu!f6Rc%+7SurU@o-@ws}pC!@+TEYZtV04Fsq`6)Bc#zu_5@-n%Uc=9|NJ!e|!$y5x z!xMa6ZwV7nR%XqBgrseK*r<;+Tn4^k;bP|kuf!wzAt7lz z#h0H)xiy0?-3lL{hY8kjE14|_DqTmLeTE9Zn~)}`o)b%$U=57!kdU-JbJFjMqzP)T z72XmiSc7_0@_Y~pNt=D23ctIPCaB*fmN3B@G%_UdAQF-``&U#CJSt_M57PLNSi%Hr zV04Fsq|H8Dh2L#U6EqGcmN3B@7~LTuX|tbL;dc$w1dZp3B}}jeMt4X^+U$!`iOhCo zg#^t@i6u;U4IkYhA!(Zr{}j;Pl_&VR-V!FDtW0!=grseK_@{tLSs8-M$6LY#YhZMT zgrt4D;`J4`Due$&XJI`c@H4z&1r)6VG>K2U=6oIHX2As+Pu#|ZNZOMNYH*# zVhIzhf$<;`k~Z&UB%^DZpnb8#5++y!<3S`OZQd_QW{EVh!?c!(B}}jeMt4X^n%fnh zF9h>o@ZwV8uk&Xw25ZaErKFUZFJPvwGm|zWz2a%Apoj)XwLW0M0 zZwV8u;pQk)A4o{r&x6&mod=PS_{^R(ZuO904UF!DF#Dp^x6O5VU)0@gBk3T47NJcf z?DN-rcP$6DBwxG%^I@ z!A9Q2@uLLqi&li6527VZutqo@H2b3Nx@I5Fjjo&zBsd=M`*5O%1Z#xjL9;LFM{V90 zb+ZI(Ab}RqGdqxeULg&P?vRkQ*%zfe&8F+K1`?~2c(5@J6Pynwd~}C|r0reF{w@-H zU2h2!P*$0E(B74cCV8LQtv;ZvGVx$Bf;BL@!)r;}?2A%a@%oB2kbwA%ceedH$hAbX zA|nmgc2$&$2YtJ;UJ!+m1`=oyJ=>#PoJbn3M;Q$yByD@GJpVv~`<=Ih2`;N}JZPSO z_|-B$$8k{~mlYCd5j{J?xj2zD!ttOTue=wJcH!rPXc0X-QoA^jG%&hDLeh3NkmqVh z@ObVmVS>vFqdO!dZFV^;ffmu@(oLd1 z(g??cTvp=6t25sV(ga$<1eX={sO0$|5|TFW0l27-`v(%d{`BtwgbCJgD`Zn2NJ!ee z&rl)b6%uwGZAY>&!5ZOsurU_eyq5vvE)pCM_$P;9f;GbNpn2;h8AW$UqCPGwB+w#y z=8Y5|Cz1xuI7xJegrvEZ_;`>tkU&eA;CwLQqdO!dZSTrI1xyosU2h2!P*$0E(7Y#; z%=!?8Nm&^JEuv>@(8YI-;Lge7oZ7 z+Wz5JgK2`>tG5V^1Z%h+Wi*hGw0Tbk*1Je>zq9e6dGjn;S<2s81EV{!H1hj!$*Pz~ z3BNi|6KDw&tl>sDlMf^$ZAVcbWuys+&&&wt;?D;8J8QU++GvQyj=L_J@rZ4rX6WWTN66oFp!MRRw8OO`+jeUqH-hQD>rUjNNqAwgdoccZ4p9FC2ER5FF9iq@AV+^y0o^&&|jZXhA|w z+G&bFFYbf({EsYw79`}Pou-Jimp{iQOYq2PPdJJ4NXSV$O%dqDBZfVXB}||q8kJ&uJ`NB@11(6%xj8@>4J6Qu#!7cS z4iH8IEl9{2JU|!?B+!e`f3fG|0AV!Hf`pvG1BB5)BJGurWpzducRy}dVnIUA-~kPy z(gb?3_7-cnY9`Qvgq*>X)j$HhxD4(2I9UQMNXQvHO%dp2+k#&+`jX;&palszgD0zj z1bT6sw&&wy3A7+Vs~UH1PE!PWao@D(<75f6AVDimSPf#%kw|;_6Lqp0JYLzeEZHL0 z<&iJDPUJSlzu9@e-em&P?(buH4l%zh!Il&eTUrRlsug|5OW70NqnN&CrR+)U5qZzf zpR(tTd2*t({OqZr-jXKx`~4*q5JHb3zZ%bhLq=`KB0)D?Gln*Hr^qQUIPZWH+@;RqbJGm~MH$(lrRS^wO zpcj@xS_4}Hc`0AIT!a2fX#y=s@F_S&?<%=g+DqzxOATLEX(CU%6h%rm?+Gfa#H)C_ zvN=E4lp@C;Z;c#m(wwKh7aSHSU9=#ID?B6zLy{1qqHUiuR9$Kriaex@bR7EJ$!< zQM8{Y1bW#S$Br@S5e_X#aAe^}qT&R4@s~>d3MWmV1qqHUZh!sQK-)zEz4$wzvT_oY zYK0agII?(Yb7*8hBJCB^>>OTSi3JIcEH+-)K9CQZe3NUT7i;^KljMTuTC^a+k;Of4 zh2~l$(2L73ydpyj5*%54blul^x}!LKS4g0jZ9Sot3|f%j$YQrAUkPX+fnKvU^Br^DUV9##@l>!SSwEJEMqWwIvAi+C&_L)~UA9yYFqA`X_rO0@dSdg&$jG2+a|FVB*Ev&z7%9_w#Bd(iS0D&+dgoK1eK0pcj|nF4ry(XrKiNE;qXup4C7C zy=+^E(;DWk(1L`mf8GnvY9N7L+@?F$)&~f*Ai?d}?uBPHkU%f)n|%t)0vc#Rg8QT0 z3(smGk@l+A%R4R&XmBlhOPcUI-dPPKc)YUv;*EJ8E1Pew3uvS*Lh$%#ch9pLNT3&w z`A6nL8fZa+$9eniM^*y~^y*xC<33Ro(m)Fmv@cG?{6Nl;KrhnH70pLtL4x$$TQ-4w zBm{a<8LFc7kywzRa-)6f1%Z6vwbEYI%C{csddbhsgNY?g_;<0g`Ji@{5WK$f?TXs8 zD%wB5A_TQ#+O1t2$Om2vy{K=}DM&^7d166=`lEZBDw_|y7JAVbqbOg2yFv>RG_K_B z`(9ZMB+!e-O0~tfOSMw1(SihxkM7O0tOgS3MYDw3V*W51XhDL;dG|hCRs)HQ7v&dQt%)U$lRV%b0!F6NTK1~tm zW$TI8K3M`SNZ7jJwNFz7dT~A3wNI8n3ldy6cJ0#?fnHoscI}fT(1HZlja~aRMP$5O z4Q2_dn#7VOe4RH%$R0pRg|xRUk+#TnrHwU3pqKQUEP)mzq^~qZpqKRjEP)mzq|Y}+ zpqGqeSpqFc$k^2sfnG8mX9=_*A!Be;MB2;GD_KHj96K`DIfK3YT+$SQUNS#siL^zo zD|2E~1bWGuAxoeI37OlQBG60LD_H_9NXQzcDFVG@-IXQKf&}TgHC$5!dQqvnwP=<= z3ldarZY|mrk@oT{=PbeVtz8wBRHO;N_HBxwcIDR8B^A^QTx^gf(iS18<-6FRDFVHy zH@g@oOP~b_>W?nQX^KEE8kH!5<+V?iKnoHyuEcij(-eVTG`hN&GfSWa2^t?=%-Ixy zUNlR%*f~p}1qmAGUF_Txk@2FO^V%m%L{x;{k|unt-V`Bw0A?O^I~G}j^C2_6T$lBV z&gTh%UR>%$*CmMs2`;yy>ym^(FWY*GtgqbOQb`38w*HH(uMz^ixEB;%CngpoxE&W= zCnf}Xac}l(RI26VXI8I?1qtqtekGf@QzA{Iz5LE(w$6FHvU`?h9)#=qy~U;o9K62=tQu>nwp5BxKLp5!JR< zsudFGMR)7=^s^dhL4x$$`|V8;=tZUOo=s#4v>-v{ri#`_a;>zNf0B~b;MVBdRhsb6 zLYg9|UAbp0W*$spxGh>cScIUKpG105^v&dj_4m+!H_EKkM`K>nB^6TYjrlZzmN3Ej z_}rd%XEczIwCNwN3|RvSsgK5dm|%^0biTndcg_zIl4dVo>a2kTTEYa=^>kXuj*IMf zosp0<)(2}K!RvN;YT@q$3D%(h0+hdJY03%-Nn?D@8c1;b;h$QB3D)?MzF)Gzeb*TY zNtaaEXvsgDKmsjcf;C>Jv(JvVXP-q#NV=qgqds{yfdpE@1Z%jjk?A% zuM4|Qjz$8?%KTT@NJ!e&hwPELvN8mhkGF&g)@YzQzs;R-h=inlyYhQ|NZ5L|mN3B@ zt|iiXBy#P_5<=VlA$yicaC`NZFu@wGM;Q$yByD@G?7bqv{mxs$1Z%jjkr)jmB+Xtv zKIb||0xe;J={8gs?^2y`Ss@{5JMPL}I1)S#ipAdv60G4yYNLUKr0x76d-_Q5c zf;HS6Wi*hGbV-Fo;apZope0N=jh-|Q8Vw{QZSqm@cWX2fg07ob!h|a;{+^}JM?wf~ z*NIZMlEGY>i%3D%$*%=tP;LelKzqi`-OB+wEjn0DVUG5J73(x!j7_}sN! zJ`uqX)Ly~j?*s|f;5m?c6}Ma@ByIY+i_cjD3F>!=B}}jejSPzBL8F0$q|JCmc0XPr zLE}ea2@|YABb@SMA`+4|<1RcCMuNt{#1bZ0gW43Icjrgygb>=swK7W}LF0My)H_VD z2A>7#=O`p3&0anV=lVbbEn$LbnroGxYmtz&&4-`0(*$2vEdEZAfU+`c1|%eH>qFKh zuB;5f<>M`3f;DI*qx{+j2}%2Q<=0n8*m|~>Fu@wGB`PW#o(HKVT0+vcfB4m4n&9^8 zEn$K+T#qsuNJ!fDT3OX1!Tru#!USv33R(FzH4>6$FCT?-yFvmjVS;H|>F0cGfP|#& zC@SwpA;IIISp1zJ!5VI)Hf4o`r0x76?|31>Gk~{*3D%%ljb|LAfrO-a9>jOmkU&eA zV2wlRY-j$C(A;MI+tEx$|7F9Q0Bp^-u)E!lA#raMHiL@oT z6C_B3=RodNbWNHE||`5rQ<_ zO5cp4NI;t6!Lbw%j&K@Cprr^w8oajRuL5ydApvQ6&Uqz8eZ!mv5@;zxkVZNllxqP^ zUi@E&4sjYtprr^wG)8wwK-%Qv+48|o0|~yaSdu$If;3#t3tU!6K-$#DuGjwAX&}Mn z<1Ix9(r`6sG?0L_YgYrE1`@WOt)&P-8m=X3&Ib~ZHvMCt+CMoBB)GkLOA&%JT#qsu zNI=^3+P;MWP6G+kb4zfljp(YT9D>`u6=J#6KE+ykOqwm z5D&_=fadXv?!k{&NT8(%K^io|K|Cne0-DEN?MK%%ftDf!Y0yXw@t|A_Xr2uy>htpl z5@;zxkOoF~NI;sr_^mWQ40u>}6l7|(c~@qOkR^L=0c@8^?@ z_88y!d+wLHo;m09p7XoUc-qm|zUw1j{`;>y_%omQ(3krU9Cz$PAN=2b>gfM}e|wIe zO#a~|@4oV)+n&9gq`#AH{*TpUvP$;O{)m%rT0QzsS1xb8_3U}E<=-ch|NGK&_TKQA zKTv|6VheG=!zcYm&UmlV;{>CMoi(2Il+W({fA@d7YS2?`(YW-M{rfLG<}Ic%Mlh<_ zS>xaT>G0)u-t&0Xpr_cPapM`c>n}Ru0@D~H7**`7@tp%6v6TOl(xs=^qVdS59Mtdp z^b1U5j9^r;O(W$&QYISo6k9a@`07Ja&CQC&2*IdgXAP+fDPhr|r`V!#k8=<0zjMm| zrZGk^s@PdW+LW{{(V(Z;qVWrFI;_9=)IZ%T_GB_fFsj&DLt47Dc+sGz*mB)VZ#k_0 z#V0@ItyyD?U{tXijT1zJo?;^(+Z&BF!cwJC#cs-KJMxk2oqdUt>sq-@vxb$`8o{Vy zXAP@CCFm)(T-WN~G{y)<6+3H4|4VImD*2$N*rH+W*fhonMitvMavxL;dWtO?)*p+; z2*IdgXAK(}RD+&ki-wIWrZGk^s@Pe>MmW`=r`V!lxTSm|n1v9pHNpc3>HTdr&MZyI9+ql%q1 zr2ol`fOeJaoqdTC4Qt1yF-9<|*rt*DplZ-lY|*g(STsfmMio12*vOz7^b}h(Y+Nyo zF@jOW&KfqtsRlj877ZI8O=FB;RI#&$^gmfKNqx{$Y|*fB-ZaJtMio12NdJ@7rD)Jo z>|9oPM<%xJ)k4B%HBCvetHzZ@gPvl`b#30Yd`N2YUpFnQ7rEBoz4s3NsrUZwRP3^H z${Hm;}L&EenAsA(4xLntuhlG{eCIq9bEd&HTB&_~7AsA)7ARy==VeNPm zf>G8t1A-nB)*m+^7-c()fS{)(4(?As|De@+4U)L@7LT%>MW8_si5uU3VE>8VI5N;6 z!KgCAt*43}5*L2q=G6yYeUCtc1f$A`x~@UbI&pNMK_c5Zs>}@Q8uXC(!JWT2k`EG$ zDl^==20bLM*!AgETpuJDRc7jS4SHJQ>Q&sXNSt)DN0k-Fx&}QYZax1)t2Dy}Es+GH z%F1b7gB}v^dGEVdX&wwTNHD6b0M|9>A#vpUE>CT0SD-dPqF$;cr@{c`%qiNHD7GEY>yXX^D$hFWmD#f_ad{NjH0xX>VWGpofI% zZ9*{0%5b`_K@SNlw@nB}Sz8DQdPrFPZ$dE2+H^qBL&DneCIq9bZw3TCB&zm09uhV_1{x$7Wn+GzK@SNV=K~EAjIy~a(4c3XIJ(v7 zWN$#iW;KnnIXKXuhlI_$t;R$&NHD70@m#M#dPvy%A!vqns$&Nm{w26y+~ zVupn80e54Uy46&9Zg=-y3PTO%gHbGzwyb=&wY&G--BwdY!uOvWrHWB3kv3Jnui4%E zK5DC}BH=r|jZ(!ZmPnf_-$Cr|eaEuZRFUvK)kdje6icK{m9^KEv{9>Pwb>S0f*umq zVw4^y7{wB4311c0KB3p8wh~?Dx~30WFLGicJBy9VO0R2CERlTmqT%b$-Mz1Ow_1ZO zQP%Jqr^=&PB5kUCrMJ8HmE~4bMZ(v<8>Na-ED=prSIWxQRJ(g$!)-NHEm78`8>PzE zqE#=gsg0yoXeswK*bY@<~9`l`0$w8{|T z)#=p08=G@7x#xJF*jeVpRVHr4IT??tGiQq0iE%~ls*MpomXMHCote&LeALd#cofI0 zon=;2y>Y@v9}=P=ze~uk?ou-zRcA}Ru8&uek1>K#Zi@y_z0l+KPRtCVF-G`oKteTe z>cyitAe0f>CaZhSY`BiIf#RZtpCsfmEKNF-G{jL_##=cL`}JqTx|>m7&-5 znOZc)2u8Ur8q(6G#ft_#Zc8iiyTjuIquhpu{su{p+dIn|#rDpYsx`t=rBQC9tdghZ zBiVKBqlA@V>gOn{HG)xYi-y&p67;xT+m&gI5!OmH%5Bk*{wKebNj~UtyS8@I7$dCZ zYn0onfm1K^xZVB=RQsT&%A>dnCm|X(GALnvJJ~H^W6Uhq#~8sVw?)IoMAe|j?K+B@ z#u#BEsz$jj8a7g^20d=q*}yc$2%8x+%5BlG8Amnfaa+!4$nS$??>t5@%5Bp)A@wTN zpvUc<*m+6+NE#vGGc^e-t9t6iqw4BabM7;>Xr!_V2}Zds8mR`ir(UJ`pvP?~tFi(R zjWL2zZi|NWKl#;tlK$v%duLhurWnx}BYdqzLNs{l#iO_u*@@MeXp9lQA|s(1IQ8OD zT=nhjeRZZ9BLt(|77eKjDPbuqdfeVwR^(PzV}!2_Nr;A=dXbhQ8Xi?w`g&boElWPe z2u8Ur8qznU#ft_#ZcDo=t8md6BN*j2G<2?|$L*bEpRhN#E7MpbEL9riHp(h_YCe+9 z{Xi|inVCwfV|4#t25aZ5rY3&ZFvl?ixZ& zC+W|kX1CtDV_s%wIa%ZOj(NLgpvUcW4mtm}ovtM3eWd@%m?at>wWEo0LNrnh%6?D@ zdfb+C$oU>}))*rg<+f-@|10w#J#L>pFKfH3F-9=TZPBpZo#ulcx6huJ6=&8MBN*kj zYG6%GkK1R@%lg_hMhHf^EgGpVWIwoFYLFhc&z_fkLe>}~80EHT*zQg>=yCh(dD#_Z zjWL2zZi_~0>9QZxd5|8rrClA>AM^fSvh$*21f$%BhR$mAxLxyM=S59pjj&W{l-npP zoulY+yVi%DhqJO;Bdl~a%5BlG8dQQFw`;pHjWNPniAK3C8ma%uesGC)m7;c(_Ns)n zW78NT80EHVI% z+jZPEjWNPTQH^q2G;E|+4SL+Jvw>-h5jM_il-r__`d^)+=yAI|H*vISj1gs4lM;2? zG-P)t`RM3z`|Np{gL8dwuJx!LO_UQ>R^@DMM~~a-9I~A$${JiVc+`$2$_desF;{w( z8Mbu|dRijid)=65T4M9W zp{J``mUDe_EfVZ29xr7@f>GrZ;(Ds+A;CW1YLH-5IZe5)K@SOzU9AQQMwL^c>l*Zs z;27L$kYH3f-MX$p4+)=f~%0?w8ss=qRQP%U;cB=*n8+}$%&o)*D8uXB`@lk0_P}Ly8 zD4Qh$4SGn}I3H+`U{s!cR<2P~MbA1>_MDoNoSl5~EWJ-g%Ex9kO-Xr%ruL7jK@SP; zaa}>ib`p##&jPJ$&_jZI^;UxfqslW)Rl~4uNl#1UC!aPZnmZHC8)!UT=`=1pBzW({ z|V04SGoU9k1d1L4r}`DZzCOdPwk|T$>LPj4IDT zu4~Xkg7+3%4HAqhPi?Mi(9;sU_v$Lr68&v9ypw9$y3_M`X(jZKFuhF(Mp+q7*YiOS z2`jfv2u4|32nc#eSp9E8Fv{9=K+r?N+VLg?qslq`^|GReg!RWjg9M|>GXm=x^t1$j zEAntit(Pt*tEzdfvYtTc&#z&=HL0TdSMwMqa)-~uMVdH$DL4r{>+Xbad&pL7R zy2jLZLiN6AijsRk`MC+Po19PS@x7W6>AcUzL{4Fj@)Qm=e9uwuK&ISoHC4VV5~A$x zh8oNVqgWzs&V6-X@Adr%sq+0ty&I`?tHD(HuBhH44G3RH*L!4XKd{xZ@|C_2Wyi8{ zS$Pyoq|Jw~SZmssTThj*scTs&-D(77rBN)AmhiP9@6d0xtbFxa+tq5b)?U`?wH*if z@Ksp-jb5+I{I&U@$9j4}KVQl%&JG>RqCYWR9*NBPbCN2ozxk?knI>Ti-NUnka6 z1OeeIiyh_H=^r6gzV_koksGykUy4y=yUiE{GPqlcIB%KDXX$t+9*|wVu`dh z=(A-_`*iDl(C717R!X-TY>B?gsC5$%9QA!3+-g~o@R@q!vMTF@+Kw$%|8U=X?S9R# z-0o7D&u{ze2lsov^!!f5w;$f`eP*Zj&(9vzC%@Y1EjJ+OA@S7*|F=ZEd=r9E zfBTjP^jEz4oPeN*#Kl)Xw7=k=|7;V2QD1$>G5wh@jZ#GqiBmrH;Qsy}d2OIUf>8&b zcEA2bf3qVX=xK=u^zVQ58#W;hKFy=P`!DzDzjucy=k$A2HHD=pnK1 z`-hJ74-$+z`96n_^mBShyl}rmM*2AkMt$rRw;vg==ppftzx?r$@rneaZhz`wb*ya1 zM0!YEaP95th&oO%>d|jLwEu~FoDsBkdPqEV-);NXzU|CS2u2-z+My}ui-4e~C2qR~ z;^5OfN>clsFFqmApofI${q7TfX%m7`QtH2c_mcvG9uiV+FMYst6M|8>EzAOf9um3! zAG!&_C~4ELzV5hypofIC<9|Ns-kT7NlD>Jb9~>JH^pKGL_}9-raub44GF}~Y!7%|r zPfHx$zv{X}HX&s6DN!<39&z1$0)ieAGCtnp?+)CAV3dscU%Tn(fS`wjjPp-={%tlP z7?o$ANQ0hrViIVO$aapBSv$@LJtSn_jq^c*QL>hZ>w_K=vVMr`g9M{w6*bnb+|v>d zs4b=)cX=&YEtPg9YrD9A&_hDjb8-J5!6;eP#{HZg60$Ch`#A|l<<Cc63&APfHxP1>)e- zJW90V`J5gSq8HESBpAg#T-(~|A;Eo{65G;#@V;rkH}zh$XYRdr&peM3i`1_6%v*w< zbwWm>jR+ro_RM{>8xr1L_sqS2Y&BIaQTqH)gZc1&zGu!7X>;x^V~_5ga|_>Us=V#) znR{Q^C{>JNiL|Nmy4^GPI^SxlTB5Y$jZ)=pH|ym!+>nqu$h+!2b4h#N#cwrLByuUp zj((`Y8e|kpq%A9HuX+EP>pAb2x0)(x8BUbF`bMep{dsQ3r9|3P`Hn94iIPI*uO;Y_ zUepr1HYux2=O~s)tKoa6J#*iyZMCdgqU=96E-Q~>iL|NmUCN%h?~1mXDiXeL+bC6x zVu`e=^8LV`x$i%=nyQv4d#a66<@>0tm*=QOhmG2F5JI-r3CDJK!dEfo#|L6Xf#(iR!&WWXW)vqW`-|^~i?q<(% zdza21ejiTWb1!GyhlGzMBqUYoP3e2(?e(Yr^gr(QD2`XV((GJDpIsXejB;Bv(#d6g ze(-xQ`m5daxV=l~UB53nM)){SLNv0aF z^Gn<4aXY8V@B5g>8X+kxQEsEG_CEPvFW5$p+xeFb-+x$Htr1eXCCY8luo~R^;?qC4 zjUKm4D=GV^F(S8^9ObrXSW8@f<){B;8$E94*6#bkF+y5?iE>*t>}kMf{>Dw)=y5yu zTHn`NA6yOzUsID14I3GjM}GIf`+5}D?RmT^JMVEqMxPSpwrJRxxcsBH9eiJU+|Hw@ z-)9&je05JkG;E|^o^_v}xUWZXKaghwzh5#&$ZSxe+!hV{iqdk|;}5zoJ#I@`$uB0d zkCHw(Mli~4)6g$eq**PMRk>D~U-NZ+4mORDV3gZdR{H#4n$@<^xm1{{^6?>PieZ7B-5x&+U zAsXdrz%&nT^C+%Gc42iU`4}U7MMgq3>}kL>t8McruKIS(eRZZ9BLt(|7L8OF^4+Dq zX&$@}J#O#P6?qv^#|d8>k`Rs5LiEc(X&$`9qw-3>T-R62l8-ThQErQdtoWo?rFrnp z^tdhUs;t6AV~k*w+t4^6&4X!uRjwuNs@S`9pWyd>Ok<6ZRFx>VQC8d2Jh+=4w{z*1 zU-)ZTtr1evCCY8lusYwK=E2?cxLw*+SznD2xs~K7w?(5o4VdP^-SoJfTf3hF7$cvs#2pN4!l-r_V zBiuC2gK5W7qVjlE2pJ!J|1m}|%5BlGk$Rfu!At3Jdzaq1%ex}!A7g~f1|`aE(U5hh zwD>d+UP_PKWge8f6rwRkX z+}_js>5DymU1jKg(4%(E8RfQUJR^;{f0xGIC#C%$J#O#m{oILYj1i1-TXUZFgWpOs z!gqB)=%-seYESQ{VMODG5rR=}i-xT%r?MZU$L&46p92z&F@jNUi$==BGNo+#inJf3 z$L&46pJx({F@jNUi$w)r}tk6 zv_3`%M!78-ssAl+Nd53$X+KDh+tRMe?;@fxMli~4Xk2**-4B*)N#8DZ&PP5u0F5<5 zQdOedMp^0ZjvlvjedJ%TP*!V%lx~S~TQsZ&_x@4Z57OgyX;-r}Vu;2Vky}ZQa$7X4 zB`*Ih?FZ>`JNJ+Li=t?Z5z^XAl-r_VJxX_X^the-dH!WoG{y+&wI#}Jt&co1Ebo-| zgY>wa$E*Acuhz#1A)`-;a$7WPgtPr%iIR3z>^$z~U#dl8jF3^ZM7b>*+}+XRcAgFL zFYcl-M#wl{qTJT9$}^7c2kCKJ%1ZWdM_ao}JyvG5HG)xYn}+W0(yV6tLAh3$U-NbS zoP*X!o}HINf>CZ;S=HSgJ#O#m{k(>iRY)+(ZPAc1S9(>N2e;AVwv<&lkz#co5{zCaZM(R=W9p0tv2kCKpPw(e|L}QF#l-r__ z@-USdI?aRI=y7{b@8_9BV~k*w+oF-`Vk*5V&4c%$$L&46pUV=BF@jNUYkk;$FwKLP z(Bt-=-p`k5eT)!{a$7WH9V)#l&4X{I$8Bj>ho7FQEsEGbazLO+qpjS>2H+P8X=`yqTCh@tHJGQ9^6fj+ofG~J`YMO zStD{Q$x&{LhPA|Lng@5&<96;J`6RjIV~mj2UZUI<4eL?5yQ9bL+|Tn#a?uzgq}P@x zx3xa<$S_Uw;HC7qoyV(ul3eR!gpkpvM7b>*HYVDButeqYst__h=9A>2F-9=TZPDQF zjvlx7^fJ!pljNc?Mli~4Ei3E?>2bTvgR&#jvKk@s+?S)=HVxem4tIAR#oe7~@F@t% zZCNKss>*zx=`u2qpl6*p+VU|*WI9K2HPEI?+G|{$3$wk1U)U`qxLv49NSBYv;;>3jy}|G z33^Cyd>khj#S&==_B-}-YPSSEEm20LVUHr=quOxXW&e%I#I?F zYVcaw&QUCpRzvnqWtNdWPMHmOrIw(lCCZ(bjmyfTSR$>4?0(BSL3XKSKBsm|&_g2c zKf6u(Afs3!tp@kY+@DjsCFp61W77z|*d$fM`wXQ-S`F?@xf7;#OVC4td-ZXGQ7n;` z;Hb|%C$(FGo|f=k@i@V~GfQNGzixWqL+&--@zPhVQrY+Y>Gw?QgY(sX)x(cU_DXF4 z>4fP^cHM3M?>EVpnhKHaOiTjerw_Vte*Mp0I1}Op&w11QBmd_Lwg2qlPZbTdC;028 z*IanX>eRnIXeGqcuf25j#z*X@_UoVazVzQnL-LVQHAAY@wp6K|$oiM_k#atBLPmx~ zZ#h@Hh9{$&e&wD=%=3)A=zsivhtFT5&wMQU+dlJsDSDFrZ;{%t|8-M(NWApi+ozn* zHX#^w^^*^q|C&B4Gt`jlzF(ihEGfw)n&~dkpeLs=6QXgMK1({(p!&_19y zCV>WXPNF~k(3JDVCIq9H!U_IL>E^VP5WPGy4D-QjF={;LxlbIe>9v-x_ISIZhs3ov z-g$mUeez|PDiVxh86xAUCDKD;-|0ur^BuOK1_?&7O}83sR}z)y!BXeB)LVk3OG5PW z?j=rDz80g#`yf3eq!jX6VyHoaQBpUh|F`*g`A;5OTlke{KDhR~JYG#^>;0S_61SfC zppkw~f>CE(_JBIBw5hVuS=DXSR-5^233^Dp{a^31g|cGQ_()9;iT?Eajnp|k7rpD4 z+OBw|HXrnmkg_Tx-#EdjT+*GETT9R*HCV<$YPSSEB&7AkqYnv2<$vF-U6JTdKXzmk z<+T{aHr?ifElx_e%y7I?OVC3?YBnByNH8k5&?x8hkdQXE`6$XLt_<3IJnE9mXWu*N z-An1ur|i3Y_K_>ER@=tP)p|dthr|bec-ic0H(jT6t6@=7xfaJ@BlO=}f*umz`PDtM zw?Fk;0YMGR)0$qZ!RwMZ>7vVKA3Xk|K!XIM?B9d3I_Ru7&#pS*c)iw3zp!g|-;+L+ z-dnxsKmUQZ&R(x1QU#eTbH z$E0t5Y+P2m`{l##9B9z{}D7u9KY+5S=wa;8cY?Vtc{Hl zc_bro?RA&V((Yvwf>GoBoOSTMcfWB}az0)k^pLpeQ5UY_(j~#DADr^KRjJJh{<w;H?_qbyG?(aGMK>9rItB_+&XsIk(~C+A6t>tBD_D$P-9j}weyYFpys=e>EA z<|w_^9k1K9N^_KsoX>mTTUTk0ny#0XrCmL|uIU8?JprNGZK_BxALFT_Cm;e15@u@@ zOQcN|%jf6pjeAl)yi!ZhL&C14tATNXQI@Kpbh+}fkyG-sBR_Ju%$1f#xnn=kig-7*a{=ppf( zNBmQN-1IR4K@W*nJ@Zrj>!0|IAXOw7b>7{s>Oc3r#|9eokU06)tNY31n}G%iMqPQx z75%Aqdvu^d4~ZjRd*w(zNHFRlPubHy@5&Pb4SGm?`K9=L52f>D3<{KNPC z-p4Np2zp4o@Voz&(tqYA1fw{PP4L%E=^^pq?|!#0zaargWkrHf9En=OJS!<(Bh
9tRrqkgzd0&>+Dmn^yu2dPvw@5@?WMl+BNU20bKfP7E|iFv{ln zK!Y9(SuQR#Ol^<=$HZH^KxK@W)o(@CE6OOw*$1f#zAV;9Oi7!dT3_*6bQ zvmXB5cH5ZBtQSN3BjmKFM3s<)+GT!4++sr=MFX@7{!{M;IEs~Lqf_e zow5itNHB`+4HBvC+W8y3*7wp$xAd!(+PO_n0u6ddNNX=AZdwfzjLLoG=s<%#M>NuJ z=1A2lAlL^r zm3lzXL&8S8fUw-E$J(yi*75_wMrZY~e5_^zf*ul9n*l)$>)UI36a3Y&L~DwKjS_(d zQ^Kh6`k;q|ja`8T2}ZFkARDQFuw^icZJ{OTAt8G42?!F5VvA`t*nX^UYi`-zT7n)D zHcBWxPB3b`N6|yV#;!nv1f$rS+f=>f<>$@I9SEM9eCOoyd3;yx#%+h4Sndvf@-qjW zSnddZ<<&RVGncIfJtVeYdf(M&*BB z&17W|X_yDs{a**YHnpqh&K=|K!Y9;>7f;Opp(HNF4jH$%*mZ4-$+z^#zBYn0}QB zH0UAm>F@p5Jid!Vf>9j1P*iDeKo5zdzW-f$vL{Ft2}W`3YBkI=ld;bTwe3o3w*);T zEQOm8jIt652zp3ZNpC_h%4#+s=pkV(Cb$Pcf>D3}GNifR( zJ(vgSA;C5ciPWz6tBm~`s{PLPaI5uskRB4dZ+T84zqtv)DBF<*1U>6Sq(LIvIqJPn zy)j)sx~oRdIuU7*$aaq6DUu2P+Os(8M5MuMWjjalGz=tC4brntL>eTroulk&l~i8C zwGTb(M5I9?+c}CW&Nd(PtP_z2iEQU6&Lyn|JtThfHfN@hI?^D)sPQ?9I}?ja*KVJ? z3{y3eC=#Zp|2|GI%1R_4=vgPexd~xqrBPP10YT3?5owUHI@jx33k@{rStlY564rM0 zy4KSI4SLpzNP~p+LA|bx7=Z>o>qMkM!p0K4u8n+w20iOUq(Q>QM7=KW=uPlfe>c!5 z5;kh3uqR~IW6#>Eov#$_Yw00j z&kP3|Bp4+rEWeUY@YhY5UVB0osfuPb=A48*Yde~%d@V*XwMbN*adMfEuqS{=H8Q~{ zmU^qfC*kcmQN6B>7=Z>oBF&I!-Xkp2!YTWzUJK$L1@w?a9!9pofG#4H^*k zw4{3Mxl6S(9p#)J5?Ol|Xpmr(J(nC1%(*>Zi&U)wg1IGO&-QLYFpB+Vg1>G`4+(q9 zIM5)$D0}ufAXp~$gseuf43Vfb`p`qdp0y1$NHB_J7-{5kCt*(jk7{IsQR6Mq-fN)O zvL|HKW>0HVMGpyk);35L2}ZF*S`B(g*b~5k1_?&7r?nbyz2&g}-S>Ke-o<&`n-1$Q zKJ`!aNtC>Pn9SDq9|t~s(tqTP_v()K(p&cLzwnrRj>w20Rd!u{mWWYDotxgIb;|z1 z-kBZ}-PMPreeEnDsKGpuZgWmgKm<7_VYWu`7wlGp9unif>XTs9_;2*Aga0_=cKt<1 zT%hH{)V8Ujhs5zuIjG%DlJhGrlIsW!6-{%Kv>&V z&mB&_Y4zwkU8#0nk#E-8Sqerk*ZT)OBurzqF~O+E-uxdadKG9ehgO4{kFAw132Qw{ zkC!f^ScWZ;_fEMKUvtJ)DeW`8?yr4u-zxR6kxGFp8z#5-byIF+W0mkT~x(*RRUl z)oL(@jADOm33^Dp_^n@+aV4lh5{w$}=NzLfYAPjdSDLN2M0!Y=p3-4H^jeJCTDu}) zr4VTFT8v`F6F{`C5$1shR}@*Ur>q3vKg34+$yt`0ZjO7{z|mYB0T0y5&ut)N2WPNJwp# zH>QmfjA9B~f};V)m8_lnO-s^^K> z_D)Z{&F$x9C&c@6t;W?~-8U=y*PGA0YF75O_A5a8|A+g*OP_tadD+X_bv5cYZ*#!B z>~~uYdPscWxXC>2Sb{b6O|QRxR`xPi?DyGOxevFs-zG@h=a^5<%3Y&2Rm`CgniA6v zQpKEq^Qi~T%buKhYBlH~@yNeBB>h&O?;wm5jQYnvJ9J*^sU@s*mr_$!qH3G=YP|+o zCa*r>npwFowzbkFVJ$}W+EnpcjI#C?5cHgO^H3jJtVqczp18hoM6=W=);lIMpSKy<2{NV64q;j)=q*^*5?C) z9ve$EidPDAzLK^?!p5;cgV$md$Cy@wBaW5skB}-7R-2ooic!|yG=FWX=pkXPGSDEw zD9%K!21jJhyHLS;fC%zIf^}oRg#{Y)1Vo@gg1@ox`IZU(x+y&*MxUEl+Riko zcfIX7)wcD#+A7iM|4zE4U#si=368FJz4Y(+>z2L>>+Bw)oU`lfSD9=BNE&{6qr(>w zy7FBBrCY-HnI#|R&s;;+)WcNSFVgDq_j*?iC%TFLbxS+3qaHh>p|+2%Lk&9{qf!2L z{0{TSkdV_G`7Q5VIq3uq&G=pkWen3T3){ZF?f!6=q`4$WM*v{NWEDHHF(U2o@E^xs>89uh3W zeD(al-I4^O>|Bm(7}hQ6A;C7*YOuXpU(xI46h@^>4+%TN6r_p-qgd)~s^}phC6d2A z5VypfUPiGOv>L2IJ4b|^N3ET;M#4^CjOILFi&1vsA|ULXgnH}*gxWrW4|7fr2|F_p zXxKRt_1LK=Xhe0MHL{0x0)iep@AD(1iiE$7 zf8+WnZ}u;<+GeH8>)P3$ARnv`MzLlm`0JLeDLdnZoNtyY64J)vKFCxtiv1snO0zRP zB%~MQ?|%$Smjt6Y2e%r2|GU#KA?EK2l{G`u68#QjOZXkgVXAChq9yA0{kq=o?+yvS z-`e5+ZduhtsmdDJ@!tap}HP}iR z#TMGup#R#_;hi<5M@8+5CF;L4b-lkYW0)!ujPkc_7}4dlbxVJfO4s|FTe{v)qzyIb zA>nV0*@$42znNx8Fjds^x3~-mdPw*?U^XHc6B;ct!E zh+vezPi9EaL&Bd6*@$42znNx8_{qiGUi0^AN^6h$Ip+^Q1DX3unSI(GMZ$lhE&I=- zXX`sJ_5*)sO;_HA84%1Z34g23Fy|x~HC|Ts`-iIguRUGwUlkZ?`1|d<-oGT!;Y$KT z!hd6F3I8U+Mg*h$3k*Yo=`~_1b-?_!HAoMMYwGtKh8iRo<=+c1qRUF%(%+lkrPDh4 zeS>swx-0MOPj|eA1f%?&{Q+T_>6ZTWfUYNDS4#Ithxs7EDF61rkl?PGyHxJ_+R~+m zgnwyes6m2J{xz2&L63h|rrcqPW;JS%@Ne1-HApbZzm+p2{Hrac_2rcKcUp!7J-Ll# z!oSTjB&gxvm1*_b`rvg*_&04#qsv^kB*7^5f=FXBlNLw9e_bBtgV$mdN1|4PcM+Uo=dPw+JK8E=q!6^Sa+mP@ta&^6b&#T%#CR%2?rGH;3C&H6OFle5i+n zV9uhV_I#D%9Fv`XlCnou?j_v9p;b&Wh^}(@(t`_jrbcf8nO< z{aZO@WQbD5G9lq#2^wmUVAOb7F}?nUo2`}=3IA5kFjXuoMlrQk75bkt?&dNf;a~6> zYVcZ&VyU+peg?AZ{kfuz_JjUxSJ(TKVH*+L50daF94#MRPFwmtO5d%XXBMjE&U<~lUqj`s+E)?2`h!5 zK6ougSxGz5Wu$$r|BLI}YoE*J6}E z?KC9(Ij^qwXX473n6=wf`4eXyo^Y$gY`wMTF){aZemHzep`x$#QlsS1eMXz6M`SZ=&a)oRca5Yu%H61>;L z`zWmjJpmDDkT6@Lcn7J~U~91YSAuzJ33^EQQ?0`qB*7?uif%~wvvytYPwEA~e{?x* zwV%(V+)4PeghLIE&Wz$1+~(Y_yA%z7a&oKvgM>fZIZTz6)k-uN#WAK$m7SAOf~y)k z0i*xk67-O;6EFc`Cw8EbN40#VSwPT}H8No*QUb!xWvItaT&Qg)E&_rc5_aMuAeaw3 zx1>=_;RJtWWtr1X!rwq-HP~gWB^bq$hD2Ir&_lxRm#)^w5)zDBtHGKowh}uVqu1q? z##2SYPT6ddDn{9F_W?l<2|N3<3Bf373;7wvVUJ?F5{>*eqq2|6H5=tTdq~(Rs~}am z6f?o7@z!o9EA(1+Mni2oOA%<;i7oZmsRy-Lh73Ip8>Laa(gc6qk{%Lv7Aw#o!6>Q0{HC#CKBS&YzmryypE<85C<6_S z=OpX|ofF+e|4M7mrOT-C*&ydbo?qyCf1hR7+xt58-}A-we^dYPuWNL@zqh#S{jJBt zoZFkr^;-Ugimtc!th+{*NE-Bz@NZ}gHApaOJXQ3N@UMIfHApauC1P37|8z^1sK1dk zDBYTKmOBZ58|pAsBpBsid>9h+knrz9Y(y~1zg#gS=po@>tJsKOlz)L^NYF#Vzq+vz z!6^Td$dI6ignvC`BZ5)>MU){y4+;MY%0>jE*wfmUNDm4Bn#)jw1f$p=TMf3vJg%%} zGOlopX$g8r*nF<^IKilF=W(nh=pkXNzCeQnqp}@o&_g2cWO6CAsUpFsY)2YAzsHk# zc@Gz9&_g2M*V>F=RK8M_Dtbs{J0f^`ho@{vw`D~S34iPDuao;8xf51FSHK{dPw*e;Wr`} zG=Rtp+_L?3=uS z1_?&7ue2IWm4B7J>scZ#K@SQ43cTgK%Uri4!6^Su{jjX)A>m)MA8L?jqUx8%hZ^?9 z^qJHY3Huhh-+Qh3AkjqC@1L(}z(c~ng+9!OePdnKo2dHj^$`udXGy}p>An%sMAh%n zuMzN&@Nd&^L@>(gX|>)z=pkYCzX`!8Yi~}}8f28UU5#2JCi$2D4V-9wU!0_Pq(CpgnyfU zs6m2J?2oMmJtS=24N8{;qsIHW-7nD`+TIZMO6@jPwrfOGeiGjHaGMZ}vb|wI&_lxZ zaGMZ}vb|wI&_lxZgPRbHvfZQ;-9-QDT{ZRi*9*JecKZ77IX3@qx1@)Jf5~vz2T3r> zzbrUxiS&^0FBuLsNHEI3EI1_SA>m Hxo{qx{Q)Lk)UJ_?HZa8YCFyUltr{&_lw% zWH{6y!6^T-;ECylG$8!DeO>QgDXsUZgH+l5 zUG{~rC*m;4HEvv(v1j4u|H1mm)?YszmlyQ{>8$2w_g7pK$-_x zRwVojiNjQpV3dE6aY)cZ!oT#m5y2?`3g3{RhlGEzawCFK{sq7xK@SQ4PT)oaqwGq) zkFrYXmh_PD?;Vb4=(QN--&Y(G^pNoHHf}^P%D*f*BZ2v-A;EY3j1!FVZ#@t5!Lg4kCyte^20bL0+HrzW z{*~)ts^}rHmX9tg)n8v{QiJ~8@bbGsF6lN^EKw5v=B8n)NHD5-4--VXrInSY%JQVP ziqfWkcNB^$5J;SXw?>_)Y^+68_dlp&gmf$>2JrgV$ozcXvMy_8h%lmu))7 z7J?oU_T0YG;{>B}3ytm?&_hDnSpE*daQ+~{C~3#(Z9PG%=&|>HXcVv1=7Sy*_Rf(& zg9M}OjV=MgWA*!*)f2QU2cIA>r@3@5bX}E{+8xp zs+bQ(`8%G6guj!z>kr6Z70{>cd8IZV^pNnkX%96>Fv|XYw%!t%UVo$YR?CWnzfF6i zR56Mr(&n6Lx18%c2gdV34+(##^hm0-Oc-S;^m}AoPFuHRFYhx2f{45~MRl^_vEDgqy98iEN1^ zthH~_5*fwRwyC0rg!QgKg9M}4rdtg@>B(n1^Y69MJu-SoBJ;7i5HWCu1wDJ7LCh)ufOt#|NIiwpvUd5=edJ%f>CaZ z#w%X_^b>yZ&(9W(jvlwu`{<7Qr}=Ty$E4`4B_MZ#=>@KukPp(L^~R z8t;ADe{O%^<9c<|U8uYl`o}XxliAOD(Qx<-HLNp$J)~`%2`oJAjgC4hsrxQR-JZe#% zIMfl&&mf4#*$4m5^wXF8Yg#)^I(pphdY(aOh>1rnnkXkk<3&&W{pp9^zEd^maXUTL zc*PMXKJciAYYH1;;!%qx$_ddp=C9WKT>CHAuL<2%jd;WtD#u${H~- z)F9z@-A4y??rpT3PZK>7&{$5=pYP9WpI8ZDddcp*wJSl7(KixHGj?nx2_)?U>U6RMH>plXnCyY||m0mAy7dSXH}Y-CUk5^mS= z$}~vW_@SPd5DgpQRD*=ub=)-#5;hL1CniM0Mrzd{;da;CsBIb~=!pr@usKRKNVqL! zrSp|(kf0|fOykPbb46o9!tJj2H#aSEswzQGOjud%P5n?cNVr{}&h)aXgukI_fs~LC zjZ}ksQ?F7D5^hUb=~HQ@L4ux`5Dn>nsaIK9`L&#`&)t~@34iWpfs~LCjWnw*<^NK3 zOh~w$-Z20D@6NCP*$YjB1U)gK8YvHwGSML6HlHzCNUA{i(?<)WgoJ2FT}TOw1_`&j z-k+5c4HERkglI^cO1(-oNVwhg{>+zXkf0|fL__*U>Qyr1Oh~w$-poDO@5E>P?<0L4 ztOPwV0S%pNNw{6}k?KtHVX0EWuB)Dy5Dm-ucH~0|r)zzz>O3f=tAv%0dSXH}tOnNz zr)w)Q4H8z*>WK-_u$DNTq(2gF*ZyG|B&>z2Cni)Q_d(Sl;dbq{MFWKOJN3kbXxPZ0 z8YJAV#GMzP04SL+J?_@EJF@o=hb6YfyyX@q>>8ycj(BpR3 z^9^?61f$#*jT0X9-n~D$>p7}HkK0|}zFlmLV3gaU@s6kc=iUcD?zdEf9=E%mZ!;Sw z80EHToc7#%EKk1f=T(Cqx4WM2SQ{r8<+f-XbL8>M-}=}?RD&M3+qcV&6MUnb+oJK% zvwmgy<`3LKHRy4B`0lnbVup9#xh)#6IQVy#Z@c7Qbv~!Z?ezQk^AF$mdmq1GmixyT z!6>&yBmGjnOlJ*LgC4iLp6^>5Cz`1Gwl~rE)x%%B{N|Z=RSl0yo*I=j@P@Vx2u4*~ zG*bST^1u2=PqnK?ic5C-+mOgnnNGH7SU&bbBYSF8x-Q<(wgJJYYKw-|N7kUH+O^JC zIUi$$)u2YXEgIHJRD&M3Yuh!AF~VA+M!78-*4k6~OeXZWUHhPEj1ktOG|Fw!uzs!@ z^tfHek`&!-K-kEjQErQdjaRBckK1)jG>tLBMmUXfTQqFkRSkOFu4B7tj1e|cYn0of zVY7j1(BpQUqfBFruo*|A+!hU+2UUX}x9ePM8e@dboEqh}XxQwm8uYkb*9@jHM%W5K zqukc|$mnqiu$L+d?GYt?Ek6M&>v1*j9 z&P>DBiK;=5+jT8!8XzVfwJ0lAjj~myY1n#KHRy4>uBlA}#KfZ(<$cH+WvgY=uywm? z(BpR98<+-&iAOEU4nm`B)o&WM|4n->XsVnQ^&m3}AshW+M6!tJj2H~&dKNYE1#qVa#z-SZ#VZ(bza?s|XMsA!O& zCniMW2PqHN+izYZ-0pgR8>(oKpeH6oWK-_upXrvB;2n3+%!m7zf(_4h=z>}szJi-I$oIu2^&Au6BD9gBb;iG zaJ!D8ra{8SLG{FhXxK=t8YJAV^M`4Wu<=|yF(Dc@N2vx0x23GEPLcUUQcKVi6Q)sr z!6M;y*ZW)Z7dcgxpeH6o?ekb~&{pLl&?fQOd%LfU2M}~T0LNpFM@Da-|*l%7W-0pgNCy!~6 zpeH6oYU(=)>ty{b=VKTLxJJux8~ zX{27Jc~JMxB;4+LdvnvYj_sA8CniKA%{cWJED~-@yDIM~TMP(#VgedE*OG9%<|B;- z&``pztDcw;4J)hdlk`Wz?OGqJrmU2(@=;Grh=$eR8sT(pSEfP2>RCN8AsW_pQ+-Y* zB;2n3!!$@(dsRG5^gVge%-Sr=!pr@SfxGGVeidnKS;Qpeu=&35%?-133_5eH0(s9mK6!N7k&Gk zQ4;jTglK#&q4P9%tn&R`67R}h zo%8V%_c#L@g^=qOPfVb!bdDn7cCL@hzVv+4u+mjR%BOf@LNxX};OWz|7Wv#O3AanT z>P&+~uIKED3DK~&tD`6hw{!pSw~LXG_F6nKAsW`BRD*=uxu5$x&qzqWE1sATjd!K7 z7?a3N?VnQ@h4el*j5^gVgekr;o=!pr@NF&2C&4a2z!tF)R?@6}=Jux8~d()caV!JO&!tL}6 z&6y9bqiajh6BD8#Yb)thlk`Wz?M2V`y0-*9F(De4r2XK-UYzGB5^hVoI(F{!APIV6 zqG;Uv#d)qJ;dai4e?40?3L)1mo|r&c>6(Fr+qpi<+hS{3DIw)kJTV~}vJQQh-2))u zc4=2L8?Q*@dd{Ah5Dja)OQ~}bZs-2-n(K};4HD8`izg;T!}_3VkZ?QqbN>oB3F&vm z6BAk=X&w44ySGHb?L1zU?}?}S03qW?@x+8^q`kr3vNs^%b{==jcgkBr#=+u=3DJ;s zXxZbCa68W*|9;caRv#o}JTIP@5DlB7v_4367AsYXf z=D<6qd!texB-~!~$3Nwue&?rOU>YRoi3!p8>9h_#+xCMb++OtE)rX|WnQ4%qCniMW zytEE|&Tr@aAPKkAlLY4;+JEPi{Y`@eJux8~|IcIpV0!VNl4V$A>gM{0QGGCbn3BF%2CQReX zG!Lo<3AYzL-(aYzssueTAsP=zzu|n*&dHE)d(qq5FfAV>=!pr@NHr+G4{AP0xSht5 zo3CA^dC)XS&=V7)ky_$1&4a2z!tF)>{(FCNmF7XyAVE(|h(_vB%QO$F1_`$p{kBS$|{vZDurAoO1NF?Begxzu+mk+ z%11phAsSYLYlPFaU6}?6t7rAZglJexTuMGjxLx~)X^^n?s-Bn-4eL>=LBj3Y&rO4b z^*i;%glO2vpc*9HuH%(ykg)MXJux8~Ho~a}3AgLGYZ@eM98^zCh=z^SszJi-I)9i3 z2^-JV6BDA5W;K~{RD*=ubsjVg5;iZXCniMWW&55z{j+z7fGFx4Wcq*7B_Bm%p)44SL*O^mn{&*Xq6}eJI6<#u&jUw?*S+ zzi{^SsDodxD`a}yUi3eA^Tn%|U;83^hIfo$l-tnI(T5(lYd+FgAo(zjHNsM*QErQd zF&RTumlN z&t!Z(<&&>W|IN1lyOdS_8xo6#a9W6zs%2`snySx#;H|UNc2j!0-t9$y&{=PurMBz& z2nj~HE%`WidDikxUtg#OJ#MGpyuPq&mfCKLkyMQljB;BvQY%@ewyUj#9=8|is{*@b z$GrcSyzPbrquhpu_78g8uKCzr+pcJ=5tb^AavNopJn0#VTqeoxO8F>Zr& z+nSGD=StAy_M+6kX;>>+BdnEZl-r__|MHvItc|WDz1I5F_J1EIYHJ_RLfDQawadwb z@9B4Y(erKmEkRFAERu%(5~ms@++OtUTmDJV6BDA5X3lyaj)dFNc0W6d@59j(6QYq; z0QEi`3AYzLzY)M1~yXIqW-W!;P5_Vnn#01JpM;{Vy z*ZN5PwDZzc!pcWIF(DdOgKLD-wOyG839D!I#Dr*AOPtDhMZ)dcKTLy!wO94TglJeF zR1Fet*M4pqB&^@5CniM0#uC*a;dULbOoN1tAL@w-(XcU5HAuK!$6eDPVdJ2BVnQ@* zq*e_QZrAz4G)UNZuAZ0>4c=8F;r61p*~c_U&=V7;QSYjea68>Y&R^GYjY`lH6INFB zTm}iZ7v&3ZURIUhciUn@G;9YsmHt7(ZF#fm0rU7i96d218nzQw4H9mrd&tke-8{Yz zM^8+M2JfnoaC_17>ufDSPfUmg@2Zh-d(rcIZY@DiOo&Dr;g)G0)G?8S+l#*aP8BS%4)A@kZ`-!M{3`qVWq2tm5+L2LNu%f*9fO;yD|+DR?q5*3DMwP zH4<*u{$Uy$qzgBy1d1PfUnLn$_yL3=(eF`NK3w*m$mWgw0Fpi3!oT zA@%WHcCU}$ymx!i^K14kK~GFrS#2+8SV*|N==nAKy2@BeE1@SQMC03OKX`c>dxwP6 zi(bAuUQYG21U)e!8b^HQ@ad=RTm}iZ)A`+Z9MhN6Ni9K7Oo+yX>0HJy*trZ6ZZCTI zrh7SM)e`i?glIe}oy+L#Tm}iZ)BWAqgHmKZE!GnB#Dr+1b5YZBR*i()={MnLKe#Wa z-dcj5m=KLC(|+)TKh5VdNVvV|KXt!j`*M1(CFqF>(U6^2ISEL@?L~jcX~(9>#j4Ix zm7pgkibgpDNy6=%k8&D6r>YQg-QtM}lvSE7CleBG=lUq8@oQNrA>~s%F(Df1OzO0p zNhRTSX;+<<6^UHW*%K3@VQn{!YUv!Aw$V(uo%=^Qjo%W|UW+FtM8o=^YLIX{_w#ZZ zza^yK6;Div#(`-px!!);CgFA-ugYosmXPtIcw#~{K9&~2 z#Dr*YcSpkQJb(E4b`mn47f(!xhRso0A0*sP_uEgqXNoN6^hwYY6Qc2@{F|3*kZ^m^ zfApfe)zr2GJuzWrRd;tJ+)lrxe&f!y)axokQ$CVnQ@7NOSpf zQ$G|95^gX0zkkK;Q)C&hNYE1#qVd=Rp1%B*-^%+z5^gX0!%sb|j;<|1PfUnLng^F@ z9@LSVgxib$(QiJq&Jry_PfUo0><7z?L&9wtuMSO-i&dQmD?v|86pb?1l5jic!{>8J zRUzcM#S;@KE8VM+a68wBuS=|Sm5}l&o|q7gpGkH8)ZfZyQc1X7+SSa;ibSsG?1>4{ zu$H)#woAh8+&_GsNJ83c@x+8^SRYgk5^m>y?(1C=((j5VCPd?mG?tuX&%TmyJC9es zZYLq*NAbjjXr#Tt-m*6!;dUN(%W3?Uka4hhVnQ^yyCdOtoqOraoJbxzr*=Dt5*ZExky(MgZ-GH#NYW9O^1)zk}bzNc_ zwr0?r+d5$bLNsh8vqm^w*H@-N!qz+Li3!oLHJoaYaJ#M(O@oB3+td>iqA}bLrj?}< zPS^FWX^^n>=LUpm4EKX+g{*|rb=__nBy1hM0U;W;($`UxgxhuhVHzZCKcJqN5RKt} zFzr~BaJufJOoN2&Yc?Q6L-vDd9@IOKB;2n1LDL{%`!n^#MA1mIn%;XQ;db5ELZc9J z-82uXCniuDmv%KX4HCJYvnM7*V|_oE z38(A*64M|dEj-PG>WK-_814rP;dH(4V;Ur+r>1#OJux8~c5i7qNq;2VuJ^A@gM^G9 zX&zKhOo)cvBU23$ZrA&8ra?l+!88x5CniLLyE_tY*ZYa4K|*GLG!LpLCPag~I}&c! zdC)XS*gUA7m=KNi{a{X&({(;K4H7oLswXC_teX8`$+^>YU1A!x%Fr6Lb%J_gLNsjc zvqm^w*H@-N!qz+Li3!oL6`5*~aJ#M(O@oB3+td>iqA}bLmLBDFUGJI(30r@vCniLL zyE_tY*LAyTkg#>MdSXH}Y^ASbA_=$a{=+m#*nU7gF(DeZV^IwfZr6R3X^^meje252 zG;HUka})`;>weHQNZ9^NJuy)<%3Mpr?YggpMj_<7>At9XVghBgcar`{xLx<>reS5J zgp^NNWyFMN*gb$X!s*hkI@2JL>p6R3LNvI$BjI+vUt$_0q`j6^UrdMwcXuS*uJ?UR zgM{?EvU-gP(Xe|<%Srkp;dZ@$Wf~-8{7Cmj)e{ql=!pr@_)fYfn*L8UNVr|!Q)C(>?7czii3!oLHyf!23AgL}mP~_$ zz5hr(F(DfEh9(^oNw{6#8)X_K>^)BEi3!oLH%+Mq3AgL}uS|o4y^l&gF(DfAR<88M zEZq;1a9iG;pzrZA4HERkMA1m^3e&lkgxfhEW!G2VE~bQBw|HU#Wwm{h{z$l;>!a-Y zYUwH=SX!MAdeaJ#<0#573Q`%Bal6QZ&H z9WK-_NOd9abkZ@AgxmGKQKmt{-s7a6n9%x2zYj{UnxsDx zZrAr;nTDL!Dulg{N8qXrw#a^6s`Z!s*hk@~*EXay@5HOo)cH#HHkegxmE! zca{$l(q7AcFeXI9dX#FAaJ#;*&ooF#zbpH}m=Fzn!=Gx9a66AzW!KjdGJX_KOo)cP z+fX$~xLx0$X!#%^<6zkj#)N3tNUa(q+|Khy+4Z%AjOWD@6QaSla*=Sm%!6e=NW%AL zoz7%gkA!IKz2t2tJnt^~*>Hc3HhqV+K5M(^@4xN*)#vVVl$8|;dSXH}4m;@V?H{`_ zzt@?B+v)ubr@U_UrDxsUG)T}B6Qc2`^FFcty1##h)&~i<)3Y*2M=Hw_Z>#Dr+<_kxE^|L7U=oN+oSi)*>P=&!l( zlGUkydyr|6peH6o8Brak!p}|JG}$q`LXWPZ5kx#i3!oT!;NQ8-}Whm?>ojb+i`)7EaMud`ir+065iG%7()Oo+x`pYo#R4R6S0MZ)bx z|ENnYpLup%8Qq0Jt?waQ+p3PAt++Osj&o7+$JV=6`m=KM3o%@Ns|7CM63AY#h(|+@HGoQ~%&=V7)@wW$^ zy?39j8A!Oj=>PmD&!73agakb?AsX{b-gf2h+uDbO+x1-yvph$U@OOxGNC^qiun|t@ z55C#N?K;~?YjRk4HC8=P)|&VhV58XgM{04A7vUOY+s|Em=F!y zd8q~ow^JX?`!>@cK~GGGhK+El;qR$w-#}yIqiK+!$LTs!CqguAq*e_QZrAz4G)UNZ zuAZ0>4V!UPgM{049yARSHZQ3sCPc$#PSqgccAd{ngM`hm>WK-_uoZx6kZ`-MOH6}= ztrOG}6QW@&8Py=+c3oeY1_@j5s3#^w!&YQE!jW*ht`nDaOq5lh61HwrPfUo0tt{6F zr|WvxG)UO`Q#~;u8n!}K4H9nGb-QVhuywS0VnQ@*rLS`>3AgM1!!$_Pen34jAsV)0 z**i&pB;2n1DAOQe`x^DcglO2#OEpNiUEi@~8YFCgrkP z*;l{wvgnV{-)nd2zvtLOJo$e-vVY-I?lBeO)%zdc-{p+2tDT7c4R82?+8Wyxg1;zb z4f)+DYcxa#QmW3mSaqlFqBJG;??I{pVvTNd&g(KIOyM}e zD9c}vDtbtmy){CktTqFJ9$t5?KDwNnZh6h;cj3L2yH-a%`GB`bi?M%CeQ4O)S?(vl zz~8LNQg6$O9ulp#Gu@H|ql{kGR2kGQ=^?R}k4jvBzjAkZ(ZA!@%U$5y+S5EfTh~Y> zIxBrGwRXF=u;^32v3mf+*3Rp`YkRp1yotuDsFQfx`^x>@p@!6RAsF@2i^|>FA;I*f zD7&|ysYM7)l`wV_+#a* zo3XW@Az^lq59>uMxt8@uwWZW26Rdr@iT-uVR0r~_g_fetOKK-#WL-iJ30rXl^+AGB zw!&G}oYz#@XsI3>Mb(xoHTjt2ztYch4oTRkt+WN}e_Dc3HcJEqOVq|hjY_GSji#!4 zNZ1%0Xz*H$vN1m(=&`v(qvT5Q%90)u*3aV_tk+@``~O7#I{n`?CbAT5HC#RQD>}eLP|LK;?S3YX~ zpclyX7X4rT;tBJYTr8(L(l1!k?eo8Q=kKbmq4q!BvOoQ}c^Rp{e(NLW_uF}aMm^}Y zC(N(9^UpZZWu(>MbxG&gLeN9vv%k81zU%5=o2}=Z1f#}N^}~85bmYSG$TVh^Fa@ZKg?el3^YhEDxYD>b<=9l!_#fNQcKW7Le6`Y=U~SPMzPDrX!(fwVORgf zY`q5QAt8MwpZ6Q)oCKrZa{a^RKX%O}fd)M!qz5-OXqoAjBp7x5A3k`#?f3Tt8uXBm zF(z(TBp7x7zdB~V`ir**8uXCh`8&&k{-;}#VAKg0-Dm!y`~H<{beZdx^pN0*y&M}6 zjA9Sg*sc)ttP|(Y)>{dQZ09KU|9thL!QLrzRB21>%`HI>i99FfbIP4|fF9A59~rWD$H0*0dxJtNF`FWb9zdu(#T-XrRs_3 zq_>z!9i)|0AFr>N58ic7y{k=?3F)0}dyZa5HG6JfN9vlwHdRb}8sRFDMpS#Vz;I+B z!Km?^Gl%~lW$yxQ+jf;@E+rv~Aw(1bEs86TB#2tVRYdfjwKiH2X{AV@6h-7T@<1pN zqbLC+Stw1+gO*D|ERqy(!5}XQ#|rqud)8XU0HVR7QkEuBb5I&2N-04DM8#D9`(uu8 zoZ08zH>b7a_O^Tf#y`iH<2}ck)5fSJ=QdBg^s`sqHESQsRk0N2e9%L}YW`9p+XSPS zznP$igtZmR(*uWfiz2}&Yf&3l#hPd}Jm0qQSnnVSn+NCnK(4!kjI#Ola&P9G(<7p0 zEqJGeHjt8$~VW z(PL~AjM{FsER(qZ$Ajt;%W&49hlF~i>VvllMyb{Iqcc5f=QX}kds~Bq`jwh9ZWD}( zwi5HwnP6XHtJF)am)X0{1U)2d<$bA@_cp;O-T$fXCU!j0L&8@2ms;u18YCDMH74%= zOwdEZ=8u=!57;IcrJC5+5_(A3Z1B?0EJ-j*V^?3V=pkXV!An20B*7?+5>+eboYO)66ol0zB+?$lF_ey{hVZED^9ON%>7La) zXDPTHePXv~Ne_uE5vM)*qyN9H2Xm}-59u65{qG)o^#3=49uhgO3?hL0G(_82>rtYu zq??@cdh@O=MD2cN^8TOWiC01*M+T?22}b2e)DXP(ocnmxc0TAKk@K!bg9M{;1u%%? z&i@@x*;cg%pm7{h;ur}!4*f0G(inV8le{nymt&vd8 zk9V7H%-g+nGD@v0-c))&q54xE)vHQ(yN9EPgzjwR3E8l|gzD-g;(eyeilymGSSBQ* zf9#&IkYE(AcD^clNaVWhyk4u3U=+)6)?k^a9^3E4Jzb_W6ZDXX8hRL4bqwx!BEhI! z$qXU@yB~~FeU0}P-@a@U^pMCk)zCPG$g=Ws52JE+K8OJ9s^}q+tG*iuM&%s7A?P8I zD}WmaM&%s7A?P8o-7}D2RLe zBIqH(QDU25RL+)NZzkv=vC2ncp7X1kf7lgjZ`#wfl(dK3Yb+j1SG&L-WqM0WnY{mJ z)*xXet^M6bgK06!dLq-f(-3x_^(GznSPQnO=ne9zQ{Rg&*Bj~TD+sqQEQKBZE&J^r zMZ)gpavm0dwOXddD62hs3gjuxgz{l)WcOJ6(6d{&t?ufnbwkiY!dkH9@AeG@qqfV6 z9um^4x$h4DmM5cL?u_Dna^M)4&%&47+6-wa1=a;fSn0A9ZLHN3jPrYQ2M1vzk)E+Q zJ!|j|GRo#bdREjB^pLReO8fga5RBrTov(@>5>fMyjRpxuvA)e3HZQpvb02@&=jrNx z)VymZY>vCMJKe!*kJ|)2By3%>QLjiaD$h1FIcGjd+sx^z=2~+;Y;LHxKzUj=v%IQ# z8|j&#hlI^)^1~2hYV&oUoHzy-&$jD&bvLVLVE$$edPu1D^gT5RMyX!auOns+ zUa$JDYF#XmnV^S+#*)77l3pMK^!3W>x>eqbSs~duzU-F#yy?XA`U+7VJwGBZJi64F1FTZ;H z?dRM;FzO?o^DC|%eDJ}B$lUt5X_f--lb6y`R`fJPqd|ft%2WQc20abYXprD3c%EXP zHF%%j@{?~ky!&bIy5XMlN=W>`ga7Ezmo5oLJ@d71JoI;vck1O&eE+MuD%J(hNB&=| z)oPp|@hKnhq^qjO+XSPY^PDGLeaYeL{dWN~!9IgM9DAjipoheEK1eVs?fqsObPtK` zd@wCWWhpej9(eBe+*8|jjaR+$%?E4SZs(nCu8JNK?|JY|2W#^;5RA%N(h&4yy?QUM zibU4qCg;otqu68kJwL{sKb}~tGao12HMWAeme4~Y%gyO+f>C*&2C-ZfJzx5XZ$Dgp z`JMOTsz~g1KV$9ubweXBEl$K&8)Ot~<(!Y%Gtzz05B>adh1&$9IQq;4YjySvexKP2 zW`Z6P*(>d@Z-b1=(WfEk$x+RtsJ(qvByvP;G?*5nvaA|{o-Ez>;;KmG{ckjQRg7Xw zn{z&Uyq0*nSt}b25{zO$Hf!*=GHj2s`&BAEBr<=ebuA&mDA~ORJtVew4M;Fbv%cDs zn{#ea7rR!=<$UtUQd*wA&jdZP>m-=v?_Bma!6@0AbLz!IB7gtoS37GkEk@;U$r{3X z>T}IMY&1C6>?Kp`@1U;AJtS;oIM*D-uj&}rc05`CaVd}W442Z#GHf(#WI5Z6#rr7c z$!3}7eqKTkiB&$9t7-_plGMJt)ZK-khv}|z9vQdwp!Fr^nlo7MbE!E4YflFIf8uFI z)dmvQ+gW+r&2Y=pa5>)KbpQg?PHc&A8Y zTXA}uU=-^@OL$q?h-2+MW-ly}nV3C;u(9M^GpB8WQM^wx!FHalXw~LtBCpEJghcj4 zO<9p(RNlcs97E}NVjq?F!^@3zdcG=pNMv1bdYfQWw)sIUS4B_uEAPcsk+3<+#vNon z=BRQ1=X|gfvwiGU+ga)}K@W*+k4|qBjLLe|5cFhCd@rtwM7EVigZW?-Tl1Wc+2bYZ z>1Ihc8YCFSab?!XnamkI&Z+Fp`IXIH9$68YKc{C6T~!f`l3jnF33^E6yu`J)2}b3t zrXgZCJDxAw6<*b|=CC7wvj#mR>Zxf6PyVIcOKEm?QJq^E)SfcFjW^ZULo`_mX zLGx1c-G4TUX<5#fsIWT?dPrEQFZ2%oVmz~^ns`d99M`WJt-%?EbJu@`>t zJZ%4!5PpRXVmG4ho%5-~LAf3Fz4LDOU*GkD{p0s9^>;_pGwl0+f4)WJvk=!9wlu!- z$G&3!=Fj*<8@+ZrdWJp!-hG?MXCbaJY-xP%yZ-e4W&iGPxCTALzJ1AOAx>`-j2gBy z-t^s{yZ?PpdbexPGwj=!d=`=#TLhzqEsg*9g`cv2`O`n#`n%nZo?+j<;HKB7rF*L!?t&3PQT~eA{aGnY5ak2ecr7f`$Nxj4SI%s`;sSlycD(x zMh#mUZ@BgC4}I82zrZ!<8FsyouAUWb5!uiCl?*#I9xaXRaV+ZIdDxy0{CdDNTEebs zi5hm6)!iy9dWP-y1HXc>(rpPV-6d++(y%*tx9&MT!}fZGUvq2`R!f$sVN1hm;;HH` zJ;V0)fnTL;5mwums9{UPTGXl9AU(tOc8*`yY!TLKm#AS&!+M5O^(FKS+xsj0N@$C) z-e-v#wlu7VJ5`@Z&#=AU#jl;V2Kd4O<#Ea-M3erDxdp|LS*(u+e$>ZSb(AVKabJ&KY*}40}28 zdx*Ku7Gd*;w+~hpo&6&*Z2z8@e$Sa2B}jv8SAq&@XDr(-YFL zZ=db|+v`5v^Fdy}f-?&qo{*!}jm?>37?yLBdWCFP@%| zMt&XGHAoEGzdxwABBTZhJ3YR5dO{lZRm8o0vCzNVOJdl|TSHQV#Q3$#y>m~L#z%am zf3x^VV%U+7I1#V9D~%$QZh3kFWu-CdNMhJ=KjLh)G_tImQ2CUnC#0e8nA*29SHz&J zULCTmNW^^(PftiAYvM`yATjJ{A8}q-`5>YCTArSeMz$!|ATjJ{=W(i78YI;2%F`2m zKdk+|)4pe_e2^G+^jC2XSsM0D)`d|2QJ$WV#ur%o`w{!Lr8GzkJNn%?FDwlb>Iciy z6Vk|@+BHZFJ4S;zRV)n>>d(v56VkvJ?2jadUE|;bmcBGd#JCimo{$E=yhvi${$1qd zYG-2nTCzq?>5<5?()WZ_Ryz{IUfvF5wDMtPwGeg|e7PSzA&vYxuxpSQw#ur0$tn#J z^z?)@^6S8^L1NgqFXNZ9(jY-kPe{XBl)fkI8YG5&`(nQ&SX%Q;(9;vr;1^a&4BOrc z9dDq@`$2-9o{&a<9aw$hj>NG2jhjpFIurKWjK$Lvem~;tz^*}J*taiszGN9Cyl>a{ zgq@(LC!~>I2YyufATey!D?h1nj=D>No}MU;8f!@mJMuBcb7>Tzbj#BdD63nQk0J&g z_hZaU)MC|ViBS2JrzfP5-xFRDgRXjY%(5a8_c=U0A&snwdtDWYVMqHI^F$J=ujT0p zX=EF84HCnSc0T62B-HN8(-YFj?+LpGiD5^7RkQP%Q2$Y$o{&a<9oRKU3_JSWvHl>T zey}_}A&u;*U4z81V>B4+C=%+=%hMCm;1}#k47ki@Y0?oW*$YJZxK>Z+`K^b03f?+Izx zsCG-U%lnBzd%e={yga3uu=~7tdO{jGBg?WH#Gt)>=+|edLBi_m;^_%#Sc_WLgCvIS z?OeZ)OAQj%?iNo^NW*%D{kwBLNMhLDUtPs})pS2dSpTtjdO{jG)Av4+#IX71X=#wK zeo(*q^c?nt-w&%H=&2WC&^~_X7ob^IxyGr{VDa>XG;-zT>p>d<7Gl^w4qA!m#HR8= z!p5b=(-Wm(qngHAo3{^Q*pUw#yP#2o(k)L%P6Vk{P z{fZcL)vIG_kcj&no}Q3K*2I(YL1Ng^K5Vp04HBxa<>?7&WQ%eQ62p#mZlhglkWjlT zPftiAcZytt#IU2kve7OzNT~lPPftk0Mzve7U)Fhg*8rnXrAa#nThg$Q6rgkQlb_CoZGJ zOxXV3;^_%##B-Sy5;E! zl+`WW4-&(U`%$xxrL3G#`IM(8q>+07D`L=9uMUTpGmwb;9G;$#M%LZE@OacU6Vmts z>l1BXbVUq0`rTS(%!K;E^7Mo>Y*bUNE+c}Z&IoWXOR^91+wgfwy{ zvmyqqvZ^}4I58YFUEB!<1LYoSqu(yix%J%O^iyUX=p5rbaV=c$op z<%G(oo)7kfG;&41A_iUc>W~^F;y#C`C#1pE9f@Ht`z5JCLiM$t5B7vKvPGR#RwRbK z?E9n!3AMX=KG+j}Kk&4V#IU2ks;7Wf+d-)RC{IsFBlpNWA0&po?89X~NT?qi&j(A7 zgfzIiBQfk{cQ7?bs6VgggFPV)uI@+-dl?5)gG7#l?&%3>tk;7NI5FsDJWmZ0Ilf*) zWLZt?!OHodmw8EQ*;Qjr-Sw)iVrwnYX6~iJV8frzfP5Gkx`m zHE(xf(98P6|2`AB9=L|^`+?_!B!<1Lqf*2A_T~9tu4~-W6Vk|)*Rme0@ng`-dN4Ie z@EddWWqMCx7$f8uSc%`CUfYH-c`t9C9kw*`7jCXW&#;%@-K7SI-H5t(w$tj%+lGfN4LcF9-}Y%7 zJkm4l<@bZB0iu4XXP$d!J9WRjqjA{Mu#^4zjiPJNGwkJekf{M;H=^#H?bid#yC#P% zjr^^pYtS?7<@cPa0b)0z?w##d5X-wQhb@i#1*m>$ainM1%dbpR14R7-)I7`YQa#Fk z<&p2qlt%uN)yF7$hV8#&S>9T?P2}%jU1QkNu-<1mIbeN>^)9hbHEiz_FSQdk6V|IO zo}S2lciCGaF>LRtb+YcD5?NL(`zIO5Sgfwi1e5>{oNetV^s7vik&V-FJi>D`~ z!IJ|dhV5hRrFK|n!p6SE(-YFL(Rn#*Kw{WFXSmc(@l4nlzIb{<8aB(A&Yo9VgZ8

AwRn2M?+4BrkQlblMKARP!tMtMn;R~k zo{)xiitsdJAqKsiJa(8e=47%#oG0TcX+~@H0gfy}y`Z!2p*wH@fM8Qm` zzLuvaq>*jVHAoCQ+IgKQma@W~4NDMprt2$9I6Y4+8(-YFL8M1zl;~FG} z9sO>dD3}TLgXQT7X>g~A#IR%hs1pS21{Cl_C2!YYG=astQJpCWLYhHOC*NvJ9kT|FDn-1TxaeUPftk0o|xRt^Cc58 zXq8ocu~K6#33_@$8o3_yt0FOM-+NtJ!A#g*=;G-KY2+%^HAoEG_mG#?JQKF3yLfs+ z8n)|vvNLzCL1Ngx7jBW&Uy-oA>BZ9%(#Tx{^@(*x_@Ft?pnXq&>0M{S_ShFsPe_A1 zMI?sp&nA{WeT)x#w>t=;?{lsIivBup=L1JkR|r zKb@d-%hMAmt6RDsB!(ULW6Vpqx1{nZPftiA_Y+-%#IUPg9kQ%Q#C;A=Pe>zc;$Hb6 zG3;m`HMg4y)z|X$gfzHQL}J*{&c}S0gxXzsdcyAq&Ki&ycJxZL{_I;`u>bCt{IZ8$aqsj48RZ@l zf8>ducy;yUm)%`!lt+Dg+E#{(eGQ?s8sb)H{QLLB?*M-8N8b4NN`r)KUhQu8vbVlq z|3822FY~nlJ*7b+G_rJ8MA3@MlFqUsK~G17M%Jslb~}zF%2rg?n8Q@BoS>&8w)3HT zP*FEiyk0~EYYtYM{%po+G^UB9I0S&7^yLy9}UF-7BGqaa`oF)w? z@=DxOZEz-}!4^eg*taiP3aLSYo}Q3K)C9MM()(tmH7*%#?rEe)GR*_`K2YHSgVDmye(pK5OM)VIF*TxmV=MXx={{#{T0$g7Y1ynAjx z=XKJGe=(b(=ZnAZ@lJp3Gd}c+Da`~uB!1+nAMEstKloSOr$K^I&wQVca^g)N|HS)< zm{~@dl&#$6dq8tMkL!wjRFwMgVc$C!5q&!edPvmOM&G_gFe=}GdRS}x^)LO|ySfJ- zvVYoDMJXRo`I^JG>F;lR`_t~rIXxuIw)F2bIlqrsqD} zdj^?NAM=H8JD1+|`S`XU{!?C;KH~R2Wy;g6QE4f+Bv>oA2}ad@TGw`ZNYuSi>zXx4 zFsknVny_o%tE_H)`CHGX;r5?-;y*hZZE4@J|7kpre^C?ZAz>}e>3{f)e{vtedqBM^ z!}a~3hXl3ft0KWD`}-mCp}9}|i+s>S!ph3(Y?pHqjIvTs;(iT!NDTXaf~9D^k6-%- zeck0T-VYMi6FL2)U-$jz$al35=9W>`UpetDpZ@Ll5p}()qh+fuRsPz#>t%93QQGU8 z$g~($rM}iMk6owk)a^_4^QwK-R#cC7`7iD{d*o00w;yZXJBKH{<#CU3G$8TB7yV|Z zU-6Rva!83>KijptM>%9v{k?5bPRK)|?3X<6h31ccOB=MmL>*<+a)pn4gZblM5G<4G zuhiyQhBHAAiR$y!qiz$7Vt+gncD;wX2UYttTJrwS1U)3G9=D^jYv_J3s@jTX1G5H8 zv1*Lk#ACaIBuwwD{IzY+J-X+NVyVwpMGuLZqo|kICK$!GG80vz%I$J*tS(ilw{`bW zHIanXO877vLU6E#PfHJBEoY7Ev)ZFxtdjo1D=;Y+Do-|n``&F1j_#^$&m z`HsdF!Kkt$AGVrUy`@>6ic-3^7V$SWhsGAcsIo)DRz<7#I?Gd0O4rs@{>J9e*diEJ zc4*k@ZuMSgc`8cj+S<_H*c=*L1f$9h4O^wI-s>z+MJZidr>s z1U(%QS7ke?Cwu;(UFRK%vK3`JkQe(R^w@7-2zojqG;DT!Qu_KwqHJiKBIow}<7Cf2 z9?j<;Qg;st+b_M?^N)NsL5=cgOikO$aIvo;bR`XuPfToo*YlCjKNj^O*7>mg-IG24 zs9onJ9~}{8mG@&sWX?~D%975qB0*0_ghtj9TjMYH+|w#rQCVZoQ%!V&o{reghwedL zl~xu-$K0pO$2OtWU6&6LBi-fQ>gUiPQTf;=pfR;U5!IrQ4;#U?qVL+^HX)6!4dSXS zU4Q=JZ7?)QRGZi)q>(kz+c}A0`|}U4)1gtdJ)eIp9ujF=tB}SGghy4)4-K{tdYJC8 zRl3=Wu4-c4P1U~agU?YDw+Kd+9ko42gXzun@>G=4&9Njkwg^U*9U3{RdA*{iY-!|} zm>OFIqsk7A9GzW*p0cHpV|!|B5sWH3G;)^V8uXMcjhv&T#umY-vO^b$VMwJ~JIqP!`ddikY&KXlv!*Py3tY2@5DHMR&wl^q&63wI5A z%9cjX;ZtLaU{u+mk*f*Upr>qUpbm7Mf-@| zeou>0b+zkSLJx`DM>$WsQLaIPQLGC){X169t4wrntE}=l&LMKH@jU*mYYBQDqwH#ZtX*r+L!$b}>Dh#9kYJSMd_#j# z)l=&!$u>a`i5g3$^9;JG9SKI&-`8!B9uiB>z#aNYLuoOp`jz$Er`oo9=jtW$S!&j| z`$q%TR}xkVPP8NEk`|*ZPyYAmS*qv5uH8L)?pRUz%*+42E~~mKc}SGr^vugONHD7M zw5nITN;jYU#1+PqAGg=7wlw5f@??bF4=38uU`dNnmD2S&CsFqLo--{*Em!FEYW*AD zhkb5nwbDl9hkZ_+zkJHQB@*;>MC2oX=e6J2KN4jtDu2P18YJlHh|tL2tGNb=vK5uT zL`w}4^mIgM@NI7-%2rhVqAoQ^(9;p2k-s1Ge2^$xQTfZj)F44mM}!7{kxQa%MddFX zQ-cIO9T6J&>&#oa=OoHjRQ^&kHAv9Y5uw3fbXHAv9Y5uvgE4R54Xw4zii?H5X^L4ux+2#st}8b6LC%2t$G zm)=CCjtC9wsh79CktkbH`HR!kAVE(@ghu{a)}Kd_C|gna%h}W* zK~F~vjT&o7lwJ9#F?ji%@IxwHrCXkk2#w6S&r3*@ttgd(-U65XZu9*pc{(CA@^{;= z!L-U&RNT#DYLK9(BSK^S8{SB(Xho@3>Md}Q4-)irL}+A-+N*R)l&vVWF1-aVG)U0X z5uuUq18@xzWh+X(gx&%d8YJlHh|tKl6u1V7vK6J?PH%w=4HEQpL}+B+?iwV@R+M^e zy_GFANYK*}p}}9|k||0yy$vSG5q9 z?&9f)(8w8pmlcV!6=kJxrC&}jWwpEoik^-L4I9-~-;YvSMJvkg=9PZW9U3I)>4?zC zIb7ANC9R?rWwr83zhn;$67+OLXjqF{-swc5Y(-h?y3#N5LxTi89T6JVGpxQJrL>Ax zl=TvJ{|~7_f}V~DjhyLwpGcx?MOklmr8gu*K1k5h5uuSQmg;wxw2D@g_1af@(?i}5 zywi!EjtGrhdDV!sq*b({Z1l0Rx}6#%=;?@|QSWpjQFi4+@6m{SNTUd)Tb_;xjV!CX z*0mo=l&vV0g5KOTm6a3pbVO+6ihe~Dt*E%0$J8J}Pe+7C*2I(YL85F$saEREO_2{0 z^mIgMWQ%eQ5@jn&txIoi3JntUbVO+6PLXSnC|gnLCG_T|&>%riM}&rrYOC)@DXpRv zrQS|&ZVC+&^mIgMWZ&-jAW^oW)NAX_O`$=8o{k8O9C2KOMA?dp(dXgRAVE(@godpk z`A#Qm&yiNqin7%t@0jtGsM0Vp5Z7hTdSTT!+u#{D2cPe+7CzUkIANR+K8Tiv5x zk)Wp|LL+Bnu0f(~McFO|+6M`GIwCZzMJ?+=5@jpOc3aTSNzl^~p-qfh(gm&f0JPHK>#rz1k+zgiytmE}bmB+6FQM?B|OSb05|8YJlHh|tjL?tAQ> zNP|S#ihB7I-~aONr@iZL%o9n_(-EQZQ?|N${8z`9-$|6Ms89KTCtW_~ozF`R67+OL zXnc#Uyk4H)I3!WFqMq}dCtaTY-EVkJz_k=Ch51sX>CC zjtC8_i6R@8eQeAC&+!PFo@Pe+8tf3)@B&)ff0RwT++)H7fE#CC zjtC9w8BR71x(11|74-uT{v(?cJ(wCK=;?^i_#wL&&$D}?e2^$xQE&OlH=J!8%zl>y zJslAm)>EHs9CQs5Wh?57fBf}l8wW?4?zCp4v4?l&z@jwNrxxJslAmIpVkmiLxUqR$)=E zNN{!65kd25U+!$4l~&nWHRi6W|J|QKPR|GH31~;env<(Lrd770a(6g2NYK*}p^-b= zURET^R#fhCrv?dnIwCZ3hu$?vl&z@TtxpXS^mIgM*bd9|e6XIy7pW~^F=;?^i z;L|=5Wh*M5o}>l|dO9LB^2v|)i6qKaR6Yet4HEQpL}=tQFV`SZwxaTBR%(!-rz1im zpTzlyL!xX&A1tD1MX40} z^P=>0L}+L|cqisQM-pW#D(>bX%Zda&9T6IQ+DD>nMX6Sf^P(i^>4?zC7IjitktkbH zYF+(#QF=NeH1gztYmg{gQR*eO&WjFDM}$V6fN%|_Rkotk+tr!E`3uDKbVO)ybw{FX zMXA@Wvyt;RU+C$G(BRWP5@jnYcR#aUk)Wp|LW58HNR+Lp+*M5t67+OLXjoY-r$0%Q zt*G1`P7MCCjtGr>(%>2- z%2rf9bw~{o^mIgM@M#~3vK5t2Pf~*fJslAm*2A5$Pt50o(f1XtsC){P8YJlHh|tI< zSnAvBd6cJBw4(B9R%(!-rz1impTzlkkVM&v%BOOvL4ux+7#ek6ltkH;k2)1PpBGiS z<>`pf$ejC}fkfGgQYrN3Md|5?(8wpeu0f(~MaA7bW?7M-rz1jxPy0xetti#XabA=J zJslAm*`oHUS0u_-lv-EKQRlD3(9;p2ktYXSgGAYiQZKP}UUYamA~f;@gljOZvK6J? zZk!h-K~G17M)uUML85F$sn@R6()^VedO9LB__U8i*@}wMr_PI#pr<23Bi~|vvRi%( z;*QtRvK3|T0P!ycuZUemX$8rsvSXEMZzH+&V}Iy*u0c=PO4r_H;$I354G_DEQd*2E zJ2dRADy#1a-%r>(S^P`Ep#fsYv=~)(XxQ6fR^Jnrr=pauy<5h=6dW2LmhTCRU{u+m zVQ;xveNXs)!rqbNUkVNl5Id&DsIo)D-qy2!`O`n#?*~0)D_winkAEpRG(arh6INP` zDmygntwXEt3ExlHJB$2F!Jz@d-fR`>A{bS6XxQ76R^Jo8pRji?`Imx21H|$@VG)cf zJ2dPqQ2RH3#wYqZik`BSuDwIbzZ4uAAeQe5D=kKq9UAsFtNr8mFP*+8d_Q6D!t$>J zhX#lp(_&QFpK%#6#*$%Yb|L&{-JslAmwtK#}XDnWKNtCT9+etr+vj!yS>4?zCr{S(aqHIOk z6M;j2)_|Ul2n~B;vbSd}^)zEit7t{pla0eTYe0gYj+itwZ$FYK8~L~utu{5B$aLM) z5uuS~<$WTFvK5u3kQyZD>4?zCJLnoD%2rg~&3)v91U(%Q8d-OJ93)Y;qOw+|1_^pP zA~do^xdw@{6_u?kHAv9Y5uuTNiEEH3TT$6dqy`CkIwCZ(hjR@QWh*LsyVM{-Pe+7C z_SCLHqHINFubmns=;?^i$PvdiNR%B>KKi5vi5%73(-A@2>4fF%If=3rWhWIh+NB1G z*%MbnA~d*DM51g(*@+8{gQ-D+o{k6&J1uh8&fKZ2b|lJHl${*88fOhi(9;p2kx%wxaAr(p7)f zfS!&B4eb=!nLG7~I&-(ARkot+WYyI;Ye0gYjtGr>8txh-%2t$}5WDKn8qm`bpCCjtGtH;ar16*^0{EE;UHd(-EP;y(JQ5D=K^K)F44m zM}$U>IGzs@Wk(d(a3r|8>xiIjH)>fA+D_4BH-3xkw$_=pGj$nf=tKTHTF#fV z=OoHjl^X_D6=gfncK_?QG9>8f zh|sVePS2gaPb5*cqHHJqGJf+zf}V~DjeLIY8YIeAlsyr+)Gw6$H&}bsE%l=GbVO+A zH$n&j*RJ6{TLg|1B~-9T6Hi;p>D_E6Prepk9%nrz1impAYJO>`0WY zC_4dz_CbQ4jtGr>&gmK?%2t$}y*tmIlPFtJb|T68_Uf-l(9;p2 zkx!A;C+4%BavNtCT9JLxu$ zg9|}VM+}V`Ye|${`55DQo@em&pwcZ*M}!8?8jvVkQ7VNoFCjrsM}&q}cQyARQMRJu zZr1#Y1U(%Q8d($fqh3W?MJr0Ra?BG+(9;p2kuAzKNR+K8wXQMWB|%R|ghrl1at#t? zD@wh@n75Olrz1im-@fM>B+6Eldb_dyAVE(@ghuw%u0f(~MXA>w>nIZRbVO+6h~pY0 z%2rg2J`d#liUd6!5gMvb@$b0Lw|{$D`L^-Je&s9Qy^pn8#al1Af82lh&htBd;a|Gv zcYfw~od3o%-|4pA-@Zv4jPNzG5eFmOmYxxA4+Ux1w~wys%WL*ktE>9b+vW2=;i}i@ zo>c4F=O?2><+!JZ&$H`^@;c`v7*)@1*91Kz_^fzblX7me$>j{K&0eo;eRfv5ne(Qs zY~Hq<(y{r~a+-!`5M~WU)!9?gb=GxTgB}t#FU4uxp>o`lU=;H=;+1pe*475giD;%Y z6ZDX<)yr}+dz)YsYtKy3L&8>Jc5iO`z1b!hCA!YZ&4l&N%YC+9bh-a(n|=FWTFQBy zn&Z{Z8uXBeQa|314@TALlyz;VhlK9=I1e|j>$oSusO`E-4++(=aUPBuBpAhZGvZYf zZ3S^v=f$i?wR;oix}vXqq$w+UNLU}dq%>=gV3dsvOADR})(jg5mv*;ZOXwkCBiz#F zXAKgJ(p6QDF%!IA5p`aW`I`xPNazatJ4k|2Dv`ck(G#sJYB*EczA6$nJ6l@UHo+*H zGj6nVo3So^hN9}XAiAo)ozp`?dgB)(g+wE>@=OlP;an|67%zlNv(oE1p zV*9E{FsjZ&u6t^FNNnfBH1s`czqdx~``2z8ec3Fl#Y4h0^o8!emMjFLtfckb@C~Bs zmDNPeygkb5v}XDZk*h}cXmwX3@^(I$mi1R!r8q63wC6iW4+-nLw2o@7iUgyqAJgit zA?UHTZRK`&FRqG&^%7bMHyXSuMycGY@0xRN^OB`RbD!GNwRy0P#dp`6$JN+oi0Z6^^WeQd6ZX)#K7c5_r)JgOx% zS~8{ie$YcgwX#O)ZGus11>>ClV0`>oJZghAbE5W$*N8(83G0uobYrfyO)!eR(oE1p z!g|!@3bzSHSr5MCZzkwb-K`R(_Ds-2Lam_g<~G47n>k-T;D=t_)GK;OsJ8d@iUgx< z&2V|jH@v*jpofIb`t1&OwVec`Y~_9Vjeq_{jRrj=Z1u9V$GNOXFv?cmm*;#8xFDQ#aB3ANyw4QvyPQm=ILcupevl?R%fGc87Ojxt|W5_^qznOnE> zE8uQ#6O5vEOZXlViM0LiHxeGTeLr%PIVc}FlDVy`vacn&J!{lHzKEPzEQH;UCg*vd zJt}LA+bp+PgB}t&`)IF9V^LghjvpSC<5fd2=ge)6q7A|F$r*r0k)HEG4~d*{G#Vrr zl{1`%h}=fbnOml`eN`lK&d_KuEkEm_QO|CaQeR8xAra+PPi00QA5x}B3F7h z5RA&1Q$x^0BG;cc5RA&1Q$x^0BIkBD5RA&1Q$x^0B4=th5R8f%b8HBDNaRfI27*yJ zb7}~-9QBX&6p?LnZXfiJP|q-)4-RH-wT#MjdvjIv_2i2=jm?uCG?QUS!Q!pBp8+R-G-otM9zb6 zAQ+W%?S`O-g!JlU-CR~A7?mr4MuQ#_+wFq{qjDwFXwXA~?QzbBwL$HYds^0_w8!qY z)%L5J;mm|xyLPZW%F4>3Zo6$7`Yp2CGr@GN4eBYt4H{G@VQo{-KN<}ZjIy@!81lhu zw{p{-ext$Msub$1N$y5Bb5VLoNTcQ`b6JsKl(kLEM>j8_$3_M{AM|TyO4}MFZ0yo= zqc-Q`$vUHKMAfsRhTuK0K2guPJZk%X(6c5UZZt@Q9Z@!a(3=n%f*umqKQ31|mlX*{ z+5ACoLTEJTAz}UQM%^XBD4Rd%O$dz!JtTBLs&&ozAi*e`Kj=*ejRrj=bpNZDm^DZ+ z%H|Jx6GEdw4++)E>Xl{<5{zOCo(XzLM7!zcJ|q~m-7~1Z+J1uPP&MCnCfru9R5OG5 zs^}r1-mY&^w&qxR09&yv{RdOp)*xZ4rKRuMCK#2^CYw9R9zZp*a{kzQ9};RSRfh9b zF)crd-YJc6)pIhXnV^S+#^CC;w+TkEF3g1PT8+-S=QWZ^ zyC2W#ArTr~`yjz6&L!rn;>gLn$(A+~^pLPw?Q-60n_!g9IQ71artZ>XvrN6Y!=tFZ ztwF+OgL=0}qrtQoWivIsRiz>5Az`yYy(6U|Qsb;Wvdoj)S#HhF9X%wn+-@KkWxInq zi`Niud&bt-H zo6cYRVISBK54`2u4&U_KeyMx@(l>tV;g7xk{pzX?{Z%o_(mhnVI-l4R^pLPCJZ$D; zNsCcd3WqAUIp_3PNgt}DsXY_)koe{weUWK*`_v>DWq&_!=6vyxFx&pVp+RDaV(r=C zpPw*Y&Wq{_ZG83G_sHqH4sUq$hnkw0r%Lx~A9g-fwA)F$4GG(aqlZLl+(0nutH1fX z4nOy)|7Sxy?eBd1;bk8c->7-TtG@H_1E2JbCtYFweVcF(iL@Jn>WpIkwsTH`dN&fD z58j)W@F=F6SL=V@CK$DS&;Rkie&q1cpZfRn%_ff=p8u7<<=a%c`S<*#_fR?RS?-_l z=l|N_2Os(*FHzp75wATNdPvOLgP93NCEetl9unL6$bRsk+-5K8w%w0&KLg0#pa}Ii zMI3rU_qIIQ6FHH6m)j%XDl6-E&(`m{$9mMW^}D69aaFut64|#m8YCFS5}B`x*PA_c zUDcAmnPARI$iB96ey%$^6D(a4*|+ys zwWP%;mf=d{Q0gSiw!e4tcBaKB*6CRz>(W{6BWtDG%3qBoGeHlD{Cz{yYDq9Ee;v^f z)(@U-1n?fmdbo3q8JUv*y}haxVSVD+#=#p1M)5ZrvxfC>XB(qDt-Qihj#2u%+cy#` zdM21IOJO_bBp8+D)?5`mB+`Ctghyq$H3U6Ocl(}OAAYtmD#xNn&L95AANQ0TqxAP2 zyGCjG__36`jSOcSqx?#EpGJI+QOg}9F>4QI(b(fk{0fuyzmIrn(8F}oZt|h$wY5s+ z6MkD+UaI}i8uZ*xRL{3fh^{Ezn_h#S`-!4w4H9|Jy?nBlX!=BYNMtY3l&-xIM&IZ2 zQnWX>*t=2UJ4n33`Kst4Vee$o7YiE=dhD$#`gWp6F{Nz{6863neciFqU|Ni_x1Zo! zTSMiz&#OAACT2d|&Xn99@v4dRkjOIhdOQ>K*!z8!uM{$+nV^S+y@3ed9~{hlRgB7% zZYV1fsn@h9ro|}Mo^eeoD|=Jj^4%_bGv2xC6>H^8&_lxB-G?t{4d%GFHwWr_S6=Q( z`(3lQ7UCOKBf@;jA;+q|F%htTB7WH@vc~G#Vrr#ZsR& zH20}9yE&8b^#@a$33~1)`h7SOvMXvXk)g7*56|KKMA0K&wVi3nt|+drW`Z6PxmNd5 zmv!$`-%6O4H*3x*3KmAy{w{V4W`8?Yma)bv+K=-l@Ffkjkl26{m0uv z2jeq9(~fy#dqh5wH6}kF`O)i_@d>Y8!$c64vJR zw$K|0MpE0ZQT3Eeg{cdkAe53QiFGpQPxXr+>d%&q^>0Ifsf}b zk)fc{rH4e`O{cdBM)7XW#C*M@UNL_&F?$A)SL-FcO)yG!zbc}Kg!M#5+-}x5BpAhK zlk-)vvzDCDirlsl z&icpKr9GIVy)9&Tvc`B+YTrOGD(_Q6&_iOoXJ9_E)q1+T!jX#{an$R36p8F5nyX@3 zjLKfAA?V4`;Jvsi5;^)b8oVk-vE}@JqUI>G2Gf#VQLM)^LC^g}(c6URipu`6nfuT~ zB74z>$aC}Vu`?_e>(AXb+U!Rff}S-I^eP`qT0uvYmBP8#pl3~V8YIGAG!B~@i)T%2 zXpk^FqU;Knd$Ys8m;sc!Y1~J28cZwfh>G(?9l`k^=P06U^@@uc^Ac}^4dLx(o5*xM zil=O5f}VzGG)VBQNuCz*tDQCIX^7N#!9Vy@r`P?hzvJ)Ht37XfkE@=U-@nUkquyV! zJ4vGUskeyeufFE=Wv8G0_qSbxMA?d}o$b&dK~G17#$W#ZFF1YpulV2n-RdODj;MGd z5E>*@3-zo(o{pF_{LOeI%0@mcuPUq5a3a%9&+6Gkj!~KOTe_Dd%9ci!!f7fiC+O*j z$VcA66;ZUJ^8Tj=33@srG@>pZjo}>psHBI`v{#wYR$K z`LL@x==qs6$`)-`sB;G+9}7WGM?^mCe(bI8R#`1+6|E>MX`PI?yWEe3pr<23!)nRi z>TcDNC9R?(Do$L41_`TueilQXj+ivmK8_^HMm{XBS$B0+PGq|2S)KjJc}bR)mBa2x zqHJkoDeR}Ra)O?Yhj1SPHBQqoj1-Nid3cb0&BPd2ecD zSYH)A_Yq5Lo;65Rt5v$&cX0NsdWq(qlgO*`D3;rNRka?_mDI{YHt+0A)L8>XWl5i9 zTS@zqc-b>S4~e`VPG3tLG-f>ZtE#gN_g~?x!7CwArxw=vAi=0Q&(IRfwdeVp8}h+& zCsC(c*BT@kl_$AeZ_YXIvt7HN9aXwaX(s3)VWr?FOs~HxMzL3#HS&4C_e*&uz^}db z$k!Tqip`_)^p@M(_k$i1*(*7{!@uS2t$tOEVqE}Wy-!9RbiJwJww2-1+sy<$Bv)nV=`{jYlzmGeHlDY>$lw2}Wg`ZwPv_ zw|g(HibVE&jRvoZQTBI@!3~iu$35Ai+_qBi^V{oto_)LDDZ7I@+3&XLX|CO9&_klm zb*?o?Fe-Z=*PHKPdd^BK3AZ!nr?mz>B=QQKo;64?Dodmx*!viv)3_eR9%I&^hlE|B z|I%We4-$;Z7TjDFOE+g^e%E+s=c}TJ1Z&SW!6++{gWgrW&Idgtwre75gY|HJo?7WL zfAdw*Ln6n-!}_X7Fe+ymNqnQdvtLTDw{JW>@kPJc{(9&9lIOkfoc2NXC;i)x^}j#i zk#9Kfb|mO&h(i#1JHAQme%8LKLn3XDdgl9llxuv;r+>R?kf5g_4nh2Ie$V31+V@OI zr0r2Z^3)G@jVJxO?>7w+^fbgFh&5qnQ4%qry&kOd}e;%@SoZ@o=BwaQQ!8%f66s(efe8Wg9JSdaR}n)>{}^2`}Yp} zjx>q1J?gK2>Cf7X|IYbizVL0PL4ux!I0W&&FNp6OTCLxcNZX@6=h;uTowhsYmp^*X zG)U0X5Ql~Ey%K4VNZX@~w!Bt8Ok*MFX^6~+<=o04%8EqV9%ZFq_503wDcyyjry=rw z*d262_nbu99%XmaHI`bk5cD)e)+?)tR%doQ)m;*4dz95m*H~)%LeSF?**>gAIiWU4 zB5jYd)^%1{Ev0apgnyPcsb?^fbgFh`*Af+N*6&N}@&_MLp$f4&SDJ_l<9t z1_^o^;;;~U0wu- ztOs*cbM+j_WRvjmYG?oAS(L0A2Xo{+i-7H8u;SJPM@|r_@t^`rA+b9Pb@Sl&z>= z`{w_Ae%xn&c50BIrz1k+Q-AC8Pha$upY_>3iLw>-sz3O1=Xd_?PfiUI^mIgMJneV= zxzmf^@iObDb~_SfE9zgp?cL|k|4+XmHAv9Y5ux!}|Ls|)zx>lb;Tj~$R@9sRxA&Z% z@DF}2#u%z@h6@B-+%C#u0f(~Mg56i{{ELg@b_Pz z8YJlHh|qZIm;TecuYJESbPW<^E9%3({{t`o>XGkF4HEQpL}>ih4}9L;|NC>F=Ncr+ zR@C49yB~7-f>-~w)F44mM})>p|K`gd{bT=YtPe<(t*Ga}@A)86wxYi9gFgE5=zCt18YJlHh|o}-jeo~ez57x1r`|OwyWVpd^{V2v za-oNWy}3uc(U)2ySMV2mG+I&^?kgzwu=`H_F&Pgz; zTJX9i(nBIn&2}0j7*##dT7w=E_71v@e2`#N^{8tNdPvwi2sdgw2}ae(u-2f5guO9u zX^-UN_+f>AXiUu)1q zLV9{*#q|WEYGtt|=pmtU)B75)Cm8k63*UYIlYimG4M7iyxc|o+2u8i=pTGP3yZ_U} z4Z)G+qxbJRf5(d-@hFa6bKRwf#Akii&!7Lzx4yd3Ai*eJ;jBRqi9hrS?>_&x&-<&5 z1_?%O=bSULdK0+r8s~QNRnbGD-toP@=Oh@VSyW$3=pj*W1z&5BU{uToyIMjI33~^n zz6RBlE(u0`d36ja+iM(pNWA(pe*5M9U-N65xhM%naeXz{tEay8&1da$sTAM; z)82Oe_`mYKZb$yQe9%MU!(R0h=im2HuWfQpf>B&2%vZ(PHp`8(^O>NB1WRO_V3gWT zKO>`u1Xq)@1_?%~{r596dPs1+J8N*QrkQ26?d{T~hlJ+7eXAwGDBjums^}r1IsDXW zkHH;JBp4NcZ`z=~F7KtNJ&P(I*;Q_rbP|r&yrsL%{eDgvzoOA z(_$1$eGxF@n0N5ugVN&NtUiCOK@W-QwXY`_Rb$thpoc__KGzeBsxf#?&_kj|(d!9D z)y!Z`&_kkT1J@Ibsu|9jpoc`wYOW_3RWr3UK@W+Von22bs%D&Pf~~VgHAS(Gb#?cS z*Ig1dimo-77Ncs^UK4EFx^{iFMN!-BoE{Rjm$}v;!KhkgtO*6RsI)sE+ypoc{5 z$zD$|N;OgQ_BBBdiQ1FBo?ukWyAF*8JtS&}b*({yQMKc_Cg>qiJFM3ejH(^aH9-%F z+F`w(U{vjRt_gZb)DG+Q1fy!lb4}1gqV{C3Cm2;bo@;_06169LJ;5l>=jV1#4~g27 zU2BkF6xSuQMy<(}R;})3*SdYJK@W*~Dz_%;$+0}O;~~4&>T7}?618`7J;A8jpIH;U z-g*Y9DCTc2D|$%O^Ut*g2}W^zoHghnQO}Ck8YCFSQFPHbYOTgH;r(Z+FN7J#Jv}6t zzion1T<^{VJtS(cW}R~qjN<--pV->l881ImWUc66XS~kZRV!QRS_?kd8883)OwiL2 zaaDF=Yj0<~{QMP(vK3`L(ZSAmr3MLlIwCae#Ma)wvL5wdXS`B_1U(%Q z8g^o9Z)d!89_~n@Y(?3~aIiC8sX>CCjtC7qv9-4|Uamo+Y(?1!cd#>FsX>CCjtC7q zv9-4|UMJ;)MA?e6k^0Kcc%=pjdO9LB?8MgI&Um>7iLw=CGma}e<8_L?a1!)%L}=KF zt-YP`at#t?E6Qe0S9ZoLHAv9Y5usrxwr<%OFV`SZwxVnXcx7k2QiB9N9T6IKV(XTj z@p26kWh=^NvR8J-D>X>a(-EOzC$=84GhVJiqHIOkjQq;Zc%=pjdO9LB?8MficE(E@ zI}&9p%2pOvcE&3;NYK*}p`oWbo=&@M>-H=A%3Rjninq$HGhT~_ zgzXLJ>vaubYaC1Wj(fs>*lpV{)7MWMf*umKhSS$iZy*?D`(^t2X+zLM!bUrN{qzQc zQMO;Eub(yqJtS=O(brFJAQ)x)W%~MQL(oIQ#w&gO^ag@awqK^NpEd+NBy1ei*H3RC z7-f4I`u1`|&_lxZwXF6WZy*?D`zZQiVMEYE!ggEq{mB~$M%nI;zH!(P^pLP!qot*d z_M{d?f>E}wrEfJh8uXB0+nhBbw+BzlW;OaUrS~7YLfa{9H0U9*-OfocN>`}&h_9d5 z(nEs%%A60It6$l9(Ys2^X8l)oUes-yKl;}l*BZ75u(Si)XFAx4M!ynUw{O&4dPvw4 znuDEaZ1O>ZQMOvzsJrx#u;)exI|JEh&|^pRfCoE&^IlvP30qAb?1WIG!K-4Ft&lfbEj=V^e!Z?GBp78Y{f$;j4~d#z zuQf<8%62T4ad*Ch^pL3e^;&}jqom!pL3&8k{CcfHf>A2NzAvGNM9r_)8YCDMbs_q( zxvc0RQSD}f_W7WP1n2W}Z70Df%`*G@VNVVZH4C>ViU&LI<0Tqb8?*CSgB}w01oL3$eVY40 zf>9hrUE>%^#}h|q)v=ltuZX;~ zwQIO0=pj-2e%BL>s&Rfz(6c5UZt_8*<_Su-<_~L)n#ssh^DEg*X@`G)YSL#i_Y*ar zTWc^aM%DarP1Gzyo|>1)t~u(Opoc`wiLNIY6<7PfX6c59M9r@!jiZguI$>&M6$GPd z%`g#G%EvuDBx;>-J;A72`>Y9iNYr}gdV*24hFcT#kf?Rr^#r48ExIP?AyMnk>j_5H zntDypL!#Ev*AtAYy@54B4~g0jxSn8C?QyILdPvm1#`OfFYOiKZ&_km3XRaq0ReMfr zf*umJ&vZS(C|zwoFQJD-?U$`JNH9vJ-p@u`j_5H3TaK$Dn*`J@5ru|%$lHwM6LAJ1U)mYYh^NVtt$Q!5)BZo_)+r&_jYPZJS^eSNbzS4~g2bSm&GsqqzStX`FJ^ zc+k#ouI}8*;fu?(V%BdG{3dfuQRoR^t8f`sOqo+QW1_?$* z4Sk@|poc{6AT$~z7?t}ELu0urdPw9B!qA9p*s}=|jLQ9op|KG3kjNc`MuP;Sa{r;x zpoc{6AT$~z7?t}EjRrj=atEQ&Ai*fjqWWL=(?cS65SptZ!Kj!G#%v&Oh5zSxqK8E8 zAT$~z7?t}E4M7iy+(Ed3U{vluGz2{)atGlCf>F8u&=B;H$Q^_m2u9^@LPO9)B6kpO zAQ+Xq2@OFHiQGZBfnZdwG8%#&61nzi2+j?1b>~qWwdcA^&rJAwu+boqt2>Y4>|@rT zheWRQ8VwSR%GFXsr(E1c@%5Ud_U+Rk-J}w1_?&7j?Ee@#oSx+5@o5+ z1U)2jpQ*VYBpAiEIcu;K*&cbHW`Z6PERk)3QCzpr1U)2j&!NdV2}W@@Vba*w%v-x0 zHPe?}tBm#T2R$TeC9@`~hRaiJMRt|pny7XsPqkXv)&8$17*+LcP1Nd6o+>xlwQgGz z^pM!jISEFo)b&>2wFW&TSkm(yto5tXs&%dG8tv8^^pL2P_w@v$szt2{){8%NRNYpyj_5H?$?^2heYkqT~9EocE8pH zJtS&>?s|ez>btb7wkGHyQM+x|6O5|euQfpriP~+uo?uk%eys_5NYwt^^#r4$ZN@vR z=Jr9)nus?A%|y*VrOuXGu^Xs(+2}W^-Gv5zhFRzgKn+bYIPP)vm~zpoc{5 zYg|t-s&;qQ1U)2bf986EQMF68Cg>qi`%KppjMCNivsZdZ)PC7og9M{g>h(Ul`JU55 zqW1mP8YCDMbz$S}N%jOQJS1xWa;?F%7^M+)^DR(|heYket~Hnzqcqy-EwpQb9ul>m zd_BP^jftCYYF~V&+lVvC1F?eDKOm=>eznZ=r*heSQ6xSn8CjLr`< z_k$i1^}J=RL4r~B3~5c!L!zD=T~9EIbBVbP(nF$l2iF=T7{xh?eQh(|WwDo9rK=~d zWh>pvQ=EVxK~G1-RplEtT!Tc}imH1P8YJlHh|tJ4g}4TZvK3WzEHp^a(-EPOZ#;1g z5@jo@+Dd4Upr<23Bj4QO8YIeARJHlgAVE(@ghsxB#x+Qkt*Gj|LW2Z79T6J&CLPxx zQMRJ04-O3y^mIgMvyp3%C|glACWZzHdO9LB@(oS? z-Y61fE2_r!&>%riM}$VcX^QWS^4-j$6;*ST&>%riM}&rb6;bcl@^?CsC|glA*9r|1 z^mIgMST}W4U!`B_+5A)A5;-d^o5|{X9B$jp;9`EaBR2m3c(NJtrGEQnvto-nc$CeS z^^LMqT-9Kf_nv!{jSNPFo{e34Q~J<2mIl+JhV3ot`)Y$onbL@KL*tG|*|@TyK@SPr zrMUEO>mk7?8znB&FLIZB&_lv@TQ2?EdPp$J)>oJM&2VPg|Krcq77q#AHM;a~>tR}q zvelBl&C!%DJtS=R>(alihXkWkd-^x&&_lv@@h<(_dPp!TYD`ym=^AfGv$~g%}*Az@D%^>wZ$=Oh@#_Mgf7 zfBclirQW1rYaD$q)5ma)cAIbUSUeb9phlH(O^ljNjg9M{g z-}-#eL&8=s`bKV}L4r}Ll~smw>C!{ORxkS2Z=*qiQL2?&@3I&k61IBLH;Wq$ro|}L z@TfOL;-i-zcM%g~&JgTM8@k9>^TfOMpATO32CsxsTKn|9C_N->A5PzpZZt?RisMyeAaZj&*%=>w zmD}I4XivuUweEW3;>FIxH5&E|YVnY;XKea<-3^YvkmN$rFT@^jNYt)X|BIqH( zQuo+nM=*-3@Q5vf9uivh_2UN#MsYV`($E<%?=!S#Q8Q%OHP>GDG7>xP=^;@ofHhHf zO`f{{va1Z&M6FolsXWQ9waA*Fhs5?(kzkZcL~ES220bKL3UldJ`%qdnJCj{=t+fVA zx7H$x;(eMm=pj)nmbC^6M%Btj_5H>SayPL!wqo*AtAY)ytZoheWNGt|u5(tCuxF4~be| zT~9EoRxfLU9ul=$x}IQEtzOmyJtS(ibUneSTD`0ZdPvl2>3V`uwR%|-^pL3a)%66U zYW1=v=pj+7rRxbs)p}=5&_kkDOV<;Os&&+wP@B+m4tZ)9Pqymu=DS4}4~g34UTZKd zM%7OGnqc2vs}x0XrZ&&7=pj+-owWuDM%5gCP0&N4R$*&`o>~toiYd+cpoc`QMb{c6 z7**@tHNkSPy--E*KFwD}4~g1UU2BkF6l>+IK@W-A>s@P*VAOVPuV+F^tDY6fj*+^X zWza*So=vT_ADK1WSFJU{vh~tn)z+ z39h4O4HAs1eTKCLJtVl&_cLA(<@bt?)l=)FL)l8V=Gt)r!p?Xt1U(%QS7j%*9?kDA z>6=K)bB?kVRdemoAVE(@god5ix|`pR+L0(*Q8m{N4HEQpL}=KFt-JXhtR0E66;*TX z&>%riM}&r**gEC+ymlnYR#eTkLxTi89T6IKV(XOOCEJlGTTwOF4h<6YbVO*_iLFz9 zUu{RCY(>>vJ2Xhp(-EOzC$>)cowyx|vK3Wx?a&}WPe+7?o!C0%_wIHi%2rg(wL^mh zJslAmc4F(4-|gFxC|glA*A5L5^mIgM*om!EeSeTd*@~*Uc4&~Grz1kcPHdg(JBlRA zR#eTkLxTi89T6JmkNp=9{nXbz-_H(akF!@=Wh*M@j23gx#*i(7QDw(fJ^8;s>(Q@z zgknKIiVI{oI$i20djcs_f8s{Xcu3(<`3)*{(rP+0w|FY-(%~j4C@cp7z|2KKfmH$BBQ=qXzoIU7igErL;HhsOW)&Ods3;degHHRvf@ z8aV?@jV*#vWrxQ9_uMZ!ea`2e{7fo6WlJOHjH$6jFskg(c=q|rPA~bFw_SstvZax8 zQHxO<+#(oNc4+*L7r)^2jbHF3e(sf?vXyQ=*+`8of>C9M#t%O5y^sFq4~TZ2tBHd= zWlJO135UqX7Qv{pL*xB^D}M>Yg~h#vZax$;?&q87*%#?e9&v2eR|=i{2Ol{^pq`) zTotFr7Qv{pL*w$&KX>|}zxA+d&{MWFavhx-TLh!Z4vq8w^8C{$zvkb28>FXfY2^Am zHMR&wl^q%{d*usGfAilxOJ~n_^pq`)+&fE+ErL;HhsM|Z$uB$ordL1bt~BT=TN*k0 zNR2ImQDtXY#k}Ms4X%XBR#eU(@@aU^OI8G<%GMR`b~(#%f}XOak@JVt*diEJc4*`* z!!_tBTN*ikNR2ImQDuil&N5tsp0cHp^M};fA{bS6Xyh!zHRvf@8aaPRjV*#vWrs%2 zGF*e6vZaypht$|27*%#?-nY|Jw$jZ$I5oBiMwJ~JIU2BU z_w!;EC5;?QQe%r?RN0}Cqnh7AddikYj)|$UMKG%D(8$r*HRvf@8acM7#umY-vO^f>C9MM$WHXgPyXbk#nuo*diEJc4*|R&o$^NTN*iMOpPsqQDuil z&R$)Ep0cHpbKlh1A{bS6Xyh#1HRvf@8aangjV*#vW#|2f^@nTFQ?@ktlw-Hc^~Z`} zRN0HhL$<~daWv1NennGu=EJ`xDcd!Q*j1F$va4F6%3jLqmaTDIgPyXLu9cgAb22on ztcuuGl+t2U*`Z-~@RqG{T!Wsnm9E`?|2lMNfY?=((qdHEpr5YxUT_ zAsreZb`_4Ud-QKehX#mUMJX*tl^q(^Gwf}R;~Mmot#qwl z@h?z^28dlnDJ@2o9U9id?QM;tKJiFT*-F>?NB>TBXn@#Nl+t2U*`Z-Q_1@Mvu0c=P zO4s^%|FU&xfY?=((qdHEpXp_wSM{5ivX!o_Mf^*spn=TID_vWQ`1evn1H`VP zloq4P4h>te+_Jq_*Py3trE6;u|6XcnfY?=((qdHEpr5YikkzCTnPb*j1F$VpQ3oVJnus?Y+7NJ!LChTZ{Nt zTtfrIuA-C{qsk5qTe0kI@6|QvDO>5e zBL1D(&;YTkD5b@yvO~jGEPLB~_5O;UvX!o_Mf_{Dp#fr7QA&$ZWrv2XarUKgQv zt#oZIa-~!Lp#fr7QA&$ZWrv2XSoXH}>U|>+0w|?oElpMqsk7A>=|5xp0cHptvNNe z2u7718rd_r20djHFBTMz>Q zxv9iFh6GF?iGs+*@F3Z1t*u;+Q4vI;l1c$B6*-a10YQbFImZ0YIezn9^ZmZfdLFU| z-x$C5Kkt|Ks@^P(If7Be&KepST!Wrsn}&L`zd_s2m)PjDM=+|`Swka(uYKq#wrOZ& zkj5OrsA6Xgtz^3Hw@#{FnwkWNGR(phY>RJ;gQ+?PR1eM=+|`SwlN7*Py4^rlB2~H0B6K6+3Ha2k9F0 z6x%ekvy{dh!Kh+q4ef+ogPvlWhIYu(m?Icf?5v?3y=%}@Y}3$AUm9}+ql&HiIOn(Q z%!F&uQ*6`F8H-XMGX$fGoi&agf6C@fzw=gayZ3qPYqu{u_xYQ};?iB%>)i!E`|I0x zp7${S`(iN*{oA9P zvrm78k0m6+wy3MOXaDdiugMxD=;;&CurV?Hc&uXAe5CTUd`QCy9ao+nfwD^Fuvm}? zyVgf)7bq(yR6g$M6Q-dW+#`Zsm-?3m3DvWE`h;oZ-v5wU>Q#E@$}ZXI z-)igcmXG|K5|>ViRi=$dsamGC>-k8jTBWw@sS4Z6YL(h<Xsz^F(d!g;+JjxbWY&iQHalW39EZQVQErhB*{O^^i#R zw$M4Y5b`W7A0phAb}G;4gT{=T58wMG+YjC4>@5gSm3p)P-6G3x+|a{RvD8bn{o4|Z zVoA5ebFaE#_4!A?(bN9RS6sjP-G^OS@?<%8yCs-&64B?UIVZs=mRqaA8ccSro9JCr z4SFU7=BQAy)>!(T9jnYAm)gu}J*`uNt*0R@g@+JIl}E8eJWXRx*|<69FRop^@*yX$ ztd%_c`>$L5<`X`BNPVO_*p^yTi*Y)Yw5>imHAoK$wGyWn_>G$hks@ry@s>Z+N|>tD z#g0pRV$>=BaQ*ggzHm#2U>|(lfBfa`$A0Q=+i8Dn zQ>8Y#u_zL6IC91I-=F!7PR|pJ`i-}|a{HpYpVcAgdCrxu-d^;3r+E~$=QT*A*0W8m zr=!7RF)FpOZE9nlzgB}Dm8eJYNG(AR3Dr$Ug9M{g{~dxJwXv@tRV37=I~q(Cqtf5o z*UtA4xU zu^5$F<*I4BH6I)SQeRo6`D%4=KUbM7Es8|yE34GIoQ_=B97TdrN>vbJ=Ee=jL6xZM z@ksL;Bvdy}&l8MN&2|X&5BI1?tyG)VgWYa5G#a=^V~N}9D;*7bNN61EXpmqO$4XDt z=>JXi!B&#`hphlMmJhbj99sx_NU#^o6O2;Lx?W4rLqfILA=s+buC|sB=C9SDhlJX( z)AIzQ)Ng_qGdFJ7s?`TqmZ}qLyCl@-oz6!u8ax)GR8Jj(Z8s6My|VSR8uXAzDYRLw zqd|gE>;-B6@#^2W>FIaz>$PQHyS4IBdrkJ*#ucrceaA9GFe+?Y+x^OEM~}VZR=>Yw zK~LCg%MluXoD1)AIzQ!ZwWu-tx7Z>+f=* zYtR$+dZ&_>#vH+@uubFb&v@YG*pJ(OX|bRu?6u8TTBBH5%@K?W+cchd&&O=;^6b01 z20dY~ZS>Jf#x&*#Mulw}|KA;-uzBmxeDav(gPyS0w!YTd$28^$Mulw}PrB;qoA*ER zO4pz#?DbB)Am!CG<_JcGZ5qcfeD>yl{qWbj20dY~cd>FZjX8o*VVlOCZaunr;7c~& zX=O!E*y~*ygKZ73e9RGy3OncHS)1ove*O{DpeOA0E>>qbAAN#RVVlMuz3!=-D?aun z*PtitdLB;sm?P56V0$Nz3L6?;AMz|U%V@V%^O62;`H;pQp;UQP*eEL}=n1>lhcu2~ z=w-D>sB}FlY|~H;z8&?EqAo4_4{50F?h$J39u>A} zs7EUF$IQN9YZaWL6+ z+;w}N&?q_~OhY5JYebaqKePg<^M^F%2+al_6}D+;#&HdL!mjh6H0B7+Y91A~X=tu> z4SK?^^SLzU2+htO6}D+;1>hR=gk9Gq(wHN(%J8VLO+#xR*PthCKjXR0XIpG6nImF# zPr@|P=(8+iBGm3H)|k;bbokw%{y6}D-l(PvrK z4D^KUT~UfFrZ)V3@ib3_`WYE;;!k;bcKS;Ns2 zwvShFD{0ITY9$^OwrQv(x&}RA*Zv`mIYO=7qrx@~^(fb% zC+ynKr7=gS*LqagrlFC+HRuVuj#tu{BQ*MWRM@7W5zg0e^n_i<-INY%S963$QI87S zG&E9|b)t>VDT>!|>ii*%IYP66M}=(~nsLf{*Jc^lh^RUbN@I@DtmaW+n}%ji-y6^q zcAd|qF-K^2_NcIPK77q^Y>|HSgk9GqH6MLKs|=3{+cdQHaSeLHuGhAuF-K^%0VDt6Yuifp8(*rrj|b7t4^%3FJh zvSTr-*jWQB%aNX9+i}afG;4rZlqfqEql%q1utFZ`DYhL~EFFiJ8fgVkuX)i^Y&&jR8TfUztT9J0s@PdWXQMW@hNGw0 zcHFeWNvoT4l#e-rQN?aF(#oseJGe5BqE^U<+rGZCD~fxBQq>SmSvgUn%u{UBP`OD% zWwl2zs@PdWHRuFA#WoGqzcl6uMio12s3p1vJ;gQ+wPR__5sWH!)=(dG4SI@g8tRYI zm?Icf?5v@Y!8Pb9wrOZwk;WXssA6Xgjc`8W&{J&F(D=AC+t*h%itZ7NDt6Y;NbLkY z#kS*WoR`KN!Kh+qjkH>_>w~UAPq9ry^OZE_2u2kFgT`G_l6^c34Pv@)pq=o5@8cGl2J=9rBo^c34Pv<{NS9Kon!R}DLRZW?3qtaJxv zS-1Idlb)SP4~;@BNHD6{wXE!XyKB%>Y}JRINsqEBgyr1T?O3UFYgDnbhE~W{=OaDE zHjUIu>`b~eKyXLjL=~ds!_S_3+oh-2rjgpQpW`sQJ^N9j>{yH{cGgHe%FegD20g{L zQN_+0+6k9&*NOv9m^+aqN7%6Z90@G}3%!XVRrH zM=+|`StHGycD~&;=qa{oq?Lp5q}(B{NS^b zy>+`p+rQ&7y+ePnZ^&9yCbFH0h5y|m%WqtM=V@0AAO5Z@R!02nQ(rZ__~?_Dqi*f*um4k-i$*A*lYPYws|mFYiI`u$+_FJ@F1H z=j)CJbIvHHaDiVb-JDwzrkB2oI;)WhM$PA3E!>Z#mhbj_yP}6g`dY=1zUbLW6$wVM zL>Bm!oab^Uk-oYyr0w^TN=KDG8;PY=R&)}3@QLl7aQzX9daKD<-sX-Eq`r?It zZK6Za^R4Il)di2@k=pv8hr}mt_Ui^64HArEJ+&J2kht)@dGCC1oimDUy4B#$^ts<# zo+~N!(c7iwd}I%a$NYW1qPU+b5{&x9+w*nKed6X{D^FgJgQ9%&(UE3LH@9jM((8qAn&Xd@)QcKW7LPtvHPN$_yf>BCUr*ygU(#Yxg(CE6|*Pw@l#^6H;Mrn+hCARJ%p_!pW z(4#rZqfShNgyzSN29L!k&AS~!qqBQ7&byu4an9cYzi~+q3C$%=14#XY1fw)xbqJ2%9+%2 z|NOM$ulw77^uMI`|pY0yH zd}N29hs2A2;(fbUJob~FRFPoRi@xcdyAOT-Q5_9>NL+B+yLOAkr#c!W7ecuU;WQI8uXC3 z;I`{$S|SNXJ^B}3w7Yn9uZ{*iB<}i@SJnQwz;9fVVAQ|({D0jI$L)Ohv=3f?+eycN z?b=_s&OHD0f|HKF>rJo8bKi}3I)1;iAKa<)1w16i2Q7|2^?v6bLNMyLo^jUkpLx&A zI|Mx>p82_d+$|PQJA_~q$FT)|_y2I+EKh zK@SO~@DPGgD#H#z4+)j@Aw(0E+d_v>D{&7AwHRMHE$~Zk62!5Zs1JR^@l#L!nH~WT z3ASlSq#9g+Xrl7pbIS)(3HLMvdI5l>p+1<}={TqlZp~Kz_rJFUJtWlUot`HcrE#pI zK@SOyT^$V)jM8}A(V&Nf#^81fbHLUTz+g9M{AKXx?eA)z_3qd|gEn&&$j z^pMcp-q9ezD6Kv^8uXCRs-~mC(MRh!kK#DCz;9gALqco2PO3;SYCcu;kkHz$qd|gE zED>ZQ_1X`7$JyyPd7p9G#rH^dzB}RHfBQXm<*tR6c+~3KQ`Bl}ef#%bbKhOMM(_6P z{`U)aX%_8_SM-qh>(||9m#&34-D+4=y6)tjtT(#NQKBX2A#v(c?!QY{nw*{|81>Pw zzQX3g4nYrz_ucyeyL3J35Q0(n`B?+qq3I zIvVtlu-0DgxM?*=Fe>+zb2=LAIi``WnIl!(4#7T1!t$4{>K{TdioIZg-?*fQg!RF6 z-$6%%1f$qDA(85X{h4*cnr#VsNU+rB2}WIT+hw~q{PU;ydcGy-AtCL~+DCP;vJp9*?0?N&p*$UW-8ZmXwt2#qD~(OBZPO1(qSLqelnhfr?aqqgg|T7HMn=HB5iXIXgyE+;q7{%V)rs_49zGx_C zAb8j0>lZf+{j+Mfo_pr`*97w;bW=lbX&@i%vS=g>c&NPA+>u~Z{(J8}fX0L4{=#X$l-gDA%pD0v@m}sW9~z^! zwk}bW+d7ilEkO?n=^a8aDj%u0rlyC4%57Fd$I4~pQL3BH4pJkhM`;XpTVrKMg9M{A zR;Inw^o%e)BsB7MG)OQ?BWg#39ugWKI|Mx>G*)&}MS@WpA3GZKkkDw?A?P8Y(Y2E* z5{%Ml*U_Mdghtnn1_?%KwCiZlLqel#M}q{TG}?7E=pmuewWC3TQ5qjR8uXCR=-SaB z!6=Qp9SwR&a8z30H!evq>g9j`Ux##6rlav67AK$ozR%qH8ta`mTz1m=<$TiXZ@km_ z>8ea8AM}uTz;`Up@1Ol3!KjOV_N?>MRhf7r4RzxAPSI6qyL=@9ggV4GgxH!evqN`LRngY=MKn}$ScSG+2ttD)ZSw1?a7&x7=k zxaP}GP2{HzAsD3{S%;u!pXh0j$aao;^Am1O$M2n0qi3J!X^_Zvj^bS;3;fzUYxaqr z29K5P9L2j~Adza2o_(UHK_c5ZN>8h#@|v!F=-DTF8YHrvqqyR1^Fhx((bFK2?Ht9q zq}8B@#N$qSS{kW)8YCDsKSyzAqNsH2_PNV$s#X?7LVEu9d4f?Ykq$x6KJlqT2$hvb zsb)I_J^MsYgM{kbkE<5i(V%Ca=xLBp+x6qBr*$;w*(Z7$B-97}xEe7!8uaWFJq;2X zOZ>PR`8pc(>=Qi=5*iczxICk`z^`66@F)@*wf*k^(s;#VF>3x^96ianwf>=JBHdQa zy4`BfLqgBpb_hKo>mEI8>vld;Z(mCf2|Y91(ICMnOJTW6y1;K-GQE027OCpZYRowa zJ!?Cgs(dU)F||lkopExRkkAvrvl^LT6idC;(6g3)EIlXcwnmJO20bM7#OWafqgaLu z{Mxyegr0-#Xz*B!Vw;9UDqXe)iz-*ZPpm#jm|nU5*=q1ujLK!0>!~H^Az`IZuB*-y zjM5X?+x=CBo)dMC<}0`LWN3$=hlHL6?GSoe(mi_a((O$5a!wD4ti9@JkYJRaOYRWN zxt^~@s|^aSv%MkW|F-xBi(ca9%RPsqB>p4O&{9uj)iwv#FnjADtj8uXCR z6Tlq}5{zO`Yc*c`{A>i+uKD;fdHkVeSEQM~WyhKSz!|8c~QA%NlP}_CS*In?1?IXV7Cb#p7{IJ%}QV_k_ zZzc4QkjD04f>Dq9(%+@%ZAXJSR1JDQPONlEsP#BKU%HH98MZ{;JLOV**^}Ry(!TQJ z{)dkq-===v(Rj?4KCn&WhkM?7ulH_K+jW~qn%5w4&wqLIHnrW329L!krm)pedN)>6 zigH^=O8J_elc9%%^qg)rNH9uy>JTi&FW$J_mXVtI>uRhly(GT-OPlTAKK6Tj%%3M1 z#ng6*t!a>uo{#zS1fy8$Ex|HTi}?!bgT#wo_Tg=ryIKwAkWuW9EkO^7XTSF2Hm-DP zkOZUV`#HxbMJ=tQb)?mPOQeT{^qlVI!;i(N6Khu_R0`Y(K=5s zYCa$IkT~PwJJ&mCTMZJ7Vi~psOY{$)e@9zWZPBjWZV76Tu#)cIBTRx(R!{vqmsx|E z&b4;>#diI1-AR?@u-p-AIWKqMlJ4arAD4ucbh-O?o?ujN3;9SbK@SOQG5!1WNid3c z`L`Nu;kiD>ZPZ{dRV)({))vbB`>h5EMzPdeLN&Oul&IF+&PVF4uapvxQl3C;-Cp1~ zF4ZU8qdw@i`lj0e(k_)A66*hl5RBrTxvd88JyxyxaaFUk8aam~RR4z%j8Z*y2zp4U zRUSexN`0k6(4&^&QPf`GH!kTRp*GghAi*fM9!R7*XY135a|3ANNDVuO;tV? zqjIWN9fE6T>am5k`Jjh{m3sf}Vk8*Fe$#3&y;i#AO`gBo(6dj>*Lgk`^OV;sJq>#HiJk@tu7mhKsWu<XL)kk$ z_M|%wWhcb*bFId^K7M>v_OD-h+B;WeU#m0s>HkmngV#Rg_Cwjr>bM^DxRXv9%6_-i zpohfU9=aIPj-|7v{=zFhyefN{8&Ce=s+@=8^@LV~9unVtpZBiHS)(rDX&2!sk#;9l z%=xFDaN1Dz^H3jJtW5e_=TFnd4f^%qYp<;ji}xd=X(@AB-Cp=t(^p;)aN?{JsL|q zibv|^d~0oqgvPOs29L!kjxntUM;w*zSCA?as?9@E#VEBm&tID=dPt~Mb~H#ZiZfBG z!4aABuF7z=KbFwbAv*aW!Mf44u#N^j9ipQ_g4fvie9HpAaY+w}+2;YwEkO?n-F@NoJi#d4anT`kpM-mK2ZY-(f=_c!4+-5f(b3R-B<|5& zPtfS~sH~AaBy_J)M}z9R(+L`j4#9ko&|Oc55RB4&Kplb}-S6`iq>4nmjsM{KC~x*J zv)W;$%j4?apH4nlABF>a9_JaS8uXBeGmuk4>k>b1ocCJ~aejA7#QE0s5NB)4s;1XJ zbS}&_NW_`qsRju~F|}=3(L*B6M)oyw`(YGIq19lS#JTX2^Il72sz}7S_k&W!s5sX@ zCAjL#^`BD`*AS)zTSJ@$F8MgD21&&E|7TJ8}74Vaxs15nUY67de0g9t{&TU@3DJtX3-F$WQhiub-u33^DxTVoC)7!~i6 znG*Dni048MA{Z5KrkN6P=VETJ`Fk~`wfFit=a0AtGWV7I?V70uiMU2v_Mhjh_S-J| zLAP^FA(WYM6JHN#iTGZ?G#?}w72h7165LgDm&#qA66F81`*RZU zrIo1$kHx6?n#+`+C%!9F&am`mHENKEZ`w>XNH8kCl`|#ct1YEZ`$Ue4uj@<+rZ?`tDWwaIERoJ%u}nzBmv5%|Ai=2ky3Uk{ zFWjulSNJ@)dpWPEq9?wtvmW9rK~oJ9jG8YirZ>KDbE0KMBEFR~O%=Idmz_CJXdtkelVWxS`YDL*g*vMgCyb!N9AM8X-n6m{N3t# z#$lBHzODU3nMq?weOhuo#PfqSRULxIA`#CnPD_^rqm(BfyObdRXWXzv<2kRIs?~lz zm~#^GjM+@8{8)@)J>}&1e^Wo_xjvpRqjruh1U)3;iI{^@#VEG7HdQP|rQJ)ErQS`| z)=H6tN}*F9JQkx=(m{+_Y247G+WZPqMM60b4P~abcFzZ+RMP%;1^Ykc&Vj`q5l=f# z>x0K)R6Ol8CE_`+^$^d*l`%1Ex2cLJ&enLstrDyK)}F`2+|T2gxb+ZE*G*GJf>H7O z;FMt6<7vQ}Dlfw}AJT9SiFhV%szHKL@kHH}poitgBh9C(L#$>?*Ym-0<5{X!gPsnt z+}9w%b3Htd(rVDtAvzi)WP23PAhjB74XS@9n5UMYheSNpI;}wxjEbk|rbIkzw;tk2 zz0UQIF{iEe^Oco5iFlT9s=?8jQ5=KYoa?w7(}*W0PqcrKh-W*esZv>OO@mP!W7<^d zJ{c#ts?i-V{`Z!khlK8c=@7bO2O4=)%ST#u2zs(cCUi$ihtPc)?$I3=ZtISV4nYqI z-Eq+&m=E2z84d%xNbPZy-_)ju~qSMzN$JkyaV>kkI+k?fzIof>C=lSX0GT zqI+ZfxIEH)sz~TAn?q8?C|$en5cH7Hy+4N#jIy?npHZClD7Gup$Zs<`(K9S0beB~p zRk;*%D`C`pYuB9>ek|Ri;kNFj=xF3t{Sx=+t_QbSh70`aT^4(U?w|0#1Bm-F+{38( zRMA61cXf0$NHB^e(x!^#qq~s&xI9uz&_hD^$sCd@M(Hk_4na@6->2N~liNZsRoO$r zj+CD)p0?ebk4!L1_cL`;MUU={@+cl@K2;=iFIGo`$6}P#V1CosG#^&arQcaA$#46r zcTjdTIG&Tx9dtpA3;&hYp390+^Rq$DhdsZr9^!qL>p}19^uOnW`+rmah_7p`hj?%C zdWg3kPjjv}m;15e3l-}@?^zFxERi(mArarum}-z<)O@PwArW8sm}-z<6iY-|@PEb) zOElg{+9}xheUimGJ-Y0yI=?__c*w5cM&sBHH% zc>f;n%*%VYo(4T6@_DVp2u9^2^-@I-iEQ@>-o3-SY)H3dMGuL1>+Q7dl3>()s^a_C z>H2B?V)lvNQ$!-(zdKD8)6OWSu+6!?GwN+Lz5>4<;tTCl4SGn#7vT>g7!_Y=pAz(t zh%dq)L@+A8&^{&TArW7MKZsyde4%|x&_g1=2!9a4sQ5zrl%R)1d=dU2f>CUt(^gWx z3BMjl#24YG8ax)G*p6F`)wyRL&tGI)5Bd(Tw@Q6&*X@>|hlIYco1Si)riuik*b7<> zdPwM-yd4b^jACDDHJGaSD*Jk1iL?YgB;qUZ%K4bNaYKSp@tyi_S00+Lqa3!uGV1H zAi=2kn*CIR9ugYoI~pVy6<@QTYS2SM^HoQK1f$|>_EQadNNC>eXpmr3e9c}OwRGtr zq4h&(D~gJhjS#|1)mr zArarEpK6d`6#HYVK@SPdyPeV{!KnFuuJa|HL+uS=Z{2QFrClSU@{{n|!yQ5}N_)c& zK@SP-;SM1frM+Q?pofI^gNG1|(rz+{apAvuR?R)}^}_X_oxcA)$L9Zz8+u5@mkg(U zkOZUR%YxIENDqnllHpW?1f$~1f>VMX67eO&X{tytD!wc@)u4w&e93UCL4r~7Wx=Ti zJtX2whEoj^jEXM{P6>KQ#Fq>YA{eFfL7jF*4+))(?2IKO7^QQh9U{Klw;tjvrS&{@ zCsjJX>mCyE{n2TCkYH4NL3F>Y{Oi)LK_b3bdJw@V_QwT&F(Tm>@E4R92oU<;iX3 z$!!2>6s3oRavsE(xt3s*QX51Ds>Z@SB-COKAsEGy_QQ|<-=x7Oy7>e!pUBR!g`kH- zKHr{GJ5Mm`g4-_Jz2Tof}@5+%-OCej>RaY*3SpE8p^pJOV7BwJx}Oq za*xuJ-frv3a<>=wjT=3y?H)bD?KaOp07&&g4+%Ys>~u@;9b|f@+M`$sEkO?nJ;UA6 zAi=2lvZ9BCT1-cS1fy6_Z9Z6Qdar>Wmq%&|dPrDF=eOglC61XJHzXJ}U+46Y(EAQN zg>9-xFpBN1CD{5H#rD<`^pMco3p%MH!6>#$*BG+B<7N4+(2y`8x#D(T4=1tR3fX4@?Pq^xh9oJCD@ngB}uk=SU~#Bp9VPx^xJ= zJ;yzI%Zc0hI&N>SrH6#xm(tN7!6?0xr9;r8_r81usUo3w%XBoDDn{ip?B$#u5_%%0 zqd|gEdXrLz$f?S0RPPY_3UW?D?<|_t$T?&b+rk3Bal`ZN?2kEry?0I0vrpvwK_bm+ zB(j~OSRyS!4~hBKPJ&Uo8)9463=+yuJC**dJ1#tmN19I+32T-4`zF(ofyZK$^@990 zk10V-HAizf7+f$ zYV$!4iFlj#RD%Sg^!L?%OJsWEjn*exRwUwW+6SeIQ7n-*=S;hD?(ZC!&j&pu;+@hn zsq!*mlu{Vy$i|$ual>8|@9aOQN3lPN@dXAEHC6P)yR}a=RV3mq-3O(L zQS8CFluB8#6xB)&>9wpu5^AAQ9}=qfp0BJ`Gm0Zdo2qyN|9Xh`^w+ZTBejI;!#yP8 zjsMfKimwu^hxl5-iE5CDuOm$BoT*|ITTeG1TPrIP((AnUgU4bN=ap82WfI>|IMJMw zi0?N{OP4uk6idBLReY5o-BVP*X;4SF)&7{smPkUa{g9T(D5kbe6+I->yE+;q7{xZ- zYVb)O{fAMp!K~LE0f%hHE6O0PmG@gIylg|5hzjD+xMtZ_d@1uL@ zpA8RPK5~~wY7mQv8k?vfOygf%f5DNrJoEo@4SK>(PkrC+uZBy$yp#rrMMRBFR1l`| zh;M)Mk#D{Fsjfj!*y)QH_xsH7T|f8`X@FQn)YwD?VH$7#(SJB{zsLNDYtR$+df@f? zhFC<@*hB?k8bA2ccVGU{E#K`L^n|@0co#uKEFx-bqJl7u@3`~BmOt>v4|ENB!fx-M zXoy8bjm=#aasPyAJou9DTVDCLuX7E0!k*rp0AdkQV|n7xN4U5L!8DGZ{$tDczxscs zwbNpxC+zjWdk`985m93k6@+O#>#_fN`S#zu+%@P4J3ZBSnqQ)jF z2-CRmtY}54;DVAr=ueHc>&CMk=DE{nvi0BqeLeg`8Wa% z_e4}Jt5w!e&i4rA$)mzH4b_Je^n_jOTpDwP>c*qOHVw5a*Ptit+IFQeN2rZ?RM@7W z)}G2|QCeb(s;%7#^#Zr&2}Xr&8tUh+K~LCqEJ@Mp0|@nbj|$r~G+wy|Jz>`|Q5tiE z#x9Qv+cY%px&}RA*Rfq1bA-lVj|$r~G#j`EJz>{5N*Z&7<`Rzz+cY$*xduI9*SS_2 zbA;wZj|$r~G&{QnJz>{1gEZy{&Fvl)wrOZx;u`dXUDrO+m?N~3@u;v(L+dNopeO9Q zhLgq|p%s}&g>4#IC%OhbVb`^&H0B7cEIlf0)6ja?HRuVuuBoLlM`(rYQDK{g*6prA zPuS~0Yj|nQ5sV7kG_;#=4SK?E-zG3mX!qiyTG*zMe|etb6Ov(%<=baYw}h@Pxu;J| zHAsX#mi=c(Bk#}h{K&%-PB`a$fA4HjB&Hf9!XEXtw4O#jmytbvVyZzR z>``9>>uKb(IN8%DrWz!|9=lJI=d#Mzak56Am}-y+yY8bqbslZB+@EH8B%rZbq+jgM zYoFK}A-!a;qqRFhPtYW$8YIH5_0iE#`M9S~Of^V^UE5VhL-p*QJ~7oG5q53u9SyZt z_w=7Mg@Ura>a?dWZ2QYmkV0fm04^ zN=TT7^$qJICP5->YgaEEF8#o>UYj*Y(9=cztVU;yV(9T@xY2)p(VX^>ER zbx)sgjob%agGAW1*A@*B>UZwx6Q-e&!8J&PUB@eFkkI(yo<3n38sS`nMA&uQl?Dlo zgYM}QrlFDAHAsZL9yDr8g9JT&!Zb8Txdw@_t*m^$k_HKS`h+xYN;TkCq zmNL^I5jLMO8ZA{I;_0IiDIsARRu@*nra>a?^$^cWnFa}Z`h;m%n@YXPHAsZL9^#oV z(;z`lpD+#U8>v^>jI$sSc6u}S;^gz+_nBK?Q|G8k(9tkEzK`UJ+R6g$M6Q-dW+#`antwb6mRL}0|6Q-e-xLl+kiLh(` zkOm30aQE~H*T{X)HAsYAdu`DGp?>F{K4BUf8C-)z*mb;;28np`b}VnCOi?6ELnEAP zkO;euqS7FtanL<|!ZfV^rMBf7B*L!qhcrlN25?WGFb(T}wz^!TABnIn=VjkEP6&GX zglYWu%U8=YUvnSV;F+|r*8|^XHcv1rY)jRnK6mc&$-n=vT!Wsl+qbgK6MTbJ*rsvW zWv4EePkO9t&=dB0;JdKq2}Xr&8kcNlSLYH1m6!AwrM={`U{SwdktKJp0L*g-(WXSFe+@*IPcrveC*qsIX1rK6ifD=12bcfv!PM*zMcp<_W%0E^O0y&?Vou`SrJboomn&_VnFtbHobo zybIejo`3p}ZGPj`|I_DldcscE&!2JD@t=9m%U8L7%n^(V+ceUZ>P@=Wz%}Rzdp+=d zYx6`CRp0hz8b5H>vp1i5+Fe~EqLQaZB@Mix?Er#N)i#Z^X4=?){YOu=t44}TcKRJi zk`u#=?S~8eWan4jHfE1 z#?8b&=YoDi%J8;BBI8!V)ZDk zGNqyQu4~W}c3o3T1H>Yt#_~R7kJ4&c8d|rz20dZdy@519EFx+wI|z@`s$Uw~f4Bxc zVXr6Gyg)1>s=YE6*TSsMufsL3c<zl9c73mN z8c|JyM7$F)UDd5AAz>O9rRytyq-$Oz!d|C5{q-)cd6A%}PngE1({-Xx>Y5jcu-8Mp z`Ooq}f}TEM8vk!Pd;UdT^CA)UdWd(8ng$7a`h;nGG3DXIy5>b9?DY_DLp2Q&^z;eS z`2AED&($?A5@FXj>#EL4#5-O`q=bZNd_1+OQ=Xg8Mv(}6J;WPnEgvN4=@X`5=NRk^ zdKz~ZB*I<~@n&7qAVE)`fQFq<97%*-^RdkRLmE!#xbEo_rlFkM`f4N*b}iji)*zws zaZjHx4b`A)kO;fBD`}8W%WzMhFb%at9}`K0UHgYLNT|KKr%#xMdX#IB2)p)kX^>FA zb5EZz4UG)0K_curUP*(5#t--O3DeLB=Ncr!uA`_lNN5~%PoFRijnu9|BJ4VUNP~pN zbNBQK)6g8{8YIHDvU=Ap-J>B567=*5Y1AuNB*I<~@z(q?r>YY4^a<1WXgV+YNnP_I z5%zk}JB*bN67=*5)A+CH`pP?W&5K0XR#xS$`IZk7^z;eS_)xk|^iR6xMI!9_ern}| zgx-|1_^rlglT*<<>5A6^CA)UdeFOtN_~K!r%#y1 zpQpNbsIGaD2s=G9eC3OG>D~`%kf5hem_{0@H)$U9y)%ih*Mr{Nw5(%$CFtoBrjcfx zdIgI_*w(JfTgS!;K~JB6hR?Mm!mjy9V*xar&~e?!lxvU(yY_QwkWjyK zPoFRijSQ|qBJ4U|NrQyO5BKy5)6fX#8YIH5z*w^PoFT2ZQ4Vf`R07@2Z^xL zmDqdS313AdK~JAB4c*b`Wkn+FacI9YN`js~VHzJ#`@t`29wZU=IPi`@iLTKS+d~ zo}7K+9a7|ao6ql(pr=n1jop9CdrlHz=X`wa-JcANLfCPOr%#})e2yX!cCL@>KlTi1 zsC1pM@+qD^VHzi&@}%V@>wMoUiLgt%8l^!Z*K_vt3DZ#9^-+{W*tvhi+r>y&do7+m zVH)aDu0bN~+|T2kXC$oO6;GcqjW?vR^MiduI(jeZn+SogXW8P9kh8 zt9#eh(-QRb3De+;j6~Su(0<>U1U-GiG*XYUdmz2eNrXKP{8DsF(92zwkJ_W09wm%smKr9pz8 zK4BW)nbx64wI3uA_Bf31I%AjaqLBs(disQEyeO?hpZcHjevm}i=}CeY-eLFI3vVY4 z67=*5)A&Cg^AAH4g^BhGY>~VPQ zm(Se2@gomT&%~L=i$KuRC!pbHIZ1?F^O0sHXgHzcx~ET=hRQ0H!(u@q>{=hG?U@D% zm5+P+gy$pIxoeOJyS6K7sLq{GJ-eq*n1)*7((*wf?Akx1K|<}-J$=G7)T3O3MA)^T zOM`^^oqPI(X=r3{4H9A3@k$ybG=8|JPnd>AIM*N%b{%)6K|u*czL zPk!e%&4bb)K~JABjo(dsgB!FTBoX#F{D+So-==v`8YJlH6Q=RSw6^*=?FUJOJq};I zal1|PpwAL5K~JABjmy&-@uOqj50VIb9KQQYo9*8|_IorBlAxzgK;tGG+ew67^O0tZ zb)?D(9oId50%euTA(cWd6DPv1^^w}1X{dCaQ2Ds0Pnd>kaE}POwkv6nP(8b+Pnd>U z;>PkpBJA2fq(MUM)jfT}G}NP9gGAW1pG$*;`kj0FglTAGa19b+*YQdkBs6}wr%#xM zMmX0X5q2GSr9ndDpnLj+X=tQ&4H9A3`9m5cG@iSsPnbrU)ojLb4H9A3c~BZ8G%vZQ zPngE@jz4Aji@)>M)F&2;r@!U3+n1gDd?&&lhpV3c>)Usp_ptQ$g9t{2y-pgJY%W>; z)hE}kK~LCY+JRra{gy|+J;j*D9KootP2+k0_UQ8L(_i5$WO~9LhkyO0tG1WE;v&7v zVvb-`*wFCNhn}!&KGIlV`H;pQp;UQP*ruVJC(mL*PuR6SHceUW5h`7e3fuFM>)Z)? z!X5|JzckcJ_6SCWZ5sKPpMLqo%`ez47U!&Ne7*3!FG&ApJN|BEm48!WY>1$ZNU7SS zw(F_-%eTFDmD+Af?|KM(98SCB*H@|SMn1X(qr$d)yl`{L=2d^Yb`5&MPS?CXa`h^; z-4tV~nj;t$wrQkRvPo^%TM0d3kLjxdSFi5#%m+o=?GlU%8yem}=n1>#<4A40rm;sT zRUQ>K$|`x%GZeW@lD#hF*_72D!Kko3AGyw*peO9H)W0;;O7;k~5|0YoH1aRM ziA`;EYw1<%b36V%Pt?{vp^eavCAG`Ng74`MdmQ*S{+6JpPmD=JSK?fQMA+ldzU7|; zJ$=G7(#%=U!;uKv+U^He{qu12^a;~QD}Z_)jzrkwz;8sf1U-GiG|o(Wj}PenL=s_- z1HUBE67=*5)A+-*hdTSu^E)|6gq`jKc-lKxaUPBYJ$=G7{wD1O|CjE|AQ5)D58&g+ zS8*PW1U-GiG(ME}v_GW#6G?^gr)gM`L&_w)(V;8`^iVUL4mA8C-F zr%ye0eb~=ZgzpfJ+m7u3jsI2OJ86?6U%NO9HtSZ6pw)F|q&<=8G{ewi<_GZ;n zhW>dtdisQEXeaC%B*ISTke_n~Y}N*;<00K4BU>t41R1ap3pd zT7sTFVH#q3DZdP;3mz3u0bN~vH2ojOPqpl_4NtUNHfkR z&4WJUkO+Gm_*J`>pr=nj<0fmnB*L!wNO@gHs+`bq-P0#fR>w?(MA)@HQu{Uym97&i zANTYL(@+iW5kc2>B@Gg)XZQ38)8JV(5@FZ=Aq^60ukPs+roppnB*L!!TpA?Q@7&WT zOhaSI#_EGa*mb;;1__NH?&%Yzp)t`lNQ7O-U1^ZeIOv`}VH#;xtM_G)2)oW7(jcMn z+&z85G~Y}N>|27KKB2NYQtn|P5%xIn zYxZ@Ov9VS{PoFT2&!qj}4QcG15FVRhWemukO({X^Kv(SOIW`vo<3n3r>3#w!@9OjBJ4a~mAmm< z!p4u{=@X{$$7xJ_ldjQ|2s@9vabGwI8wZQ0PnZUGcO=5j^GDp@PQu3X;^`Bnp*hOy zgGAWreEY@s*u{PNB%`HJspD>M=r@8#6Q$I8f5@C~VO+uiv505-mYbpD+#E z50)8+MA$Z7-656LT4hCoo<31D%3Mn#?3|C7&rPEccHH9W6DTX+tC0vh*GH^NRJu-B z`4mr|FpYne>ih{mlJ7|+5q4=;E0qvag&PH7HVzg~pD+#X?ns24=Z|tXeoNSRUOaumG&DzfeUJ#d%!B8sU6IK1Qug!-)7ak+ zzGP)%pJugW*ZJK4-V&N$4x2Uc)6hz0j|jT1ucSdj z>mB#>3DeLT&NWDcUDt`yAfa`ed-{ZFO!tFnW$8rFb-gPM5?X&AK$r%1cO=5D>vn07 z&^p>ZeZn-f()Ur6MA&uzAq^7R54fjKn8tKJn072q1YP%0(jcLI%>jgI*zPXPgMJ2* zMA&sdC=C+YpSh<`6pb{i`MFmTVb^^vGzwwIP4l38`UJ|#*9;`WuKROosH~i@5>4}9 z%}3TFVH!FIutx-4+SN)LByv4xPoFT2{rzAjg0AOFq(Q>kYnlh$(v=e7kg#zu&4cdg z6Q;r49f`2(`9x`uuo)oDgYM}Qror7EiLmQDC=C*t2i?;rOk;mPm{S#WozJB~Li4M8 z`h?1=*$>;k`h;mr_k*QJ1zp#>(jcMrr+fN@X>fN(BJ8?umj(%~qutXdOhYSu9}`K0UH2c- zAff$$d-{ZFXvg9jB*L!yC~1(;zQ#R$!Zft=@;Qn`*mXZB4HDX)xu;JQjWXAg2)piU zp-~7sZaOdOo<4!HI<`nZ5@FZvCo@rG$iO?7zn=A4_i|aYAoDQ9ek}(13T=@X`La(<_ikBKD0uJ4VK1_`~#$vu6- zG}1Na<~?3zqz<~i|4JGp^gb&0^a<0jw{oR7X8C@QMA-K31b>g0G)U0XCyGXTSD4SW zB*M=5D7(J;b}=XHxW&^aP*z74=|>{$TpwlES4-CkE1%-&6Q=RybS)~qyKRpMy0oj6 z%8Ep;=j`bdrlFR&w0w{VyT0d68YHZ}mfc;SFb(x6*B}vg?&oEV+7j09il&FOdd`JTIN&o<3n3`|t6}M9}H%M}FIiG)U0XCsbB-KS(0% z`aYQ`t4iqoF7D|QrjcsU-dW>yP9p63UL0wV(0gj!(wAi%K|=2ha!;QyjWjYe@9`=lL(uhoOVS{r_aC{ZPnbrk3wx)N zkBKD0uJ4VK1_`~#$vu6->mywsv|hDHKN4Zr_g_iF?$#=V-bdx0K4BW%-H`~}+Lgb@ zOBy8T=@Uhx?CwZ}UEfCrjY8OQ%YLv=psbE9(vL*g^}TA+P+2))*sA5@FZ(^+|(-^}Dhk z>=UM;H~hHf^a<0@yA54~MA-HHiOL5F8wbmNuuqsq>P3W_^t$xx4e&{Y|tE@=S(V67=*5(|Guc z{^ZClfB55GA0)y~&&oXfitWEY^Bbi>f}TEM8mHXywaa(jE2sUv&4g zq(Oq7K4BUs|Lg;o|M!pEbH?dTSsW|uak%-4S8p%+z0;&Yf}TEM8c)3EW0rS$_FY|r zMA+l-qz_!XedR+=mIeuW`h;nG~VPR_g=UC%_n?%neW9RK~JAB zjVE38^yT{>d8KQR2s^z4;_t8D{>>L|kp>BR`h;n`<-%t#FIa!QYmf*#eQEyfH*DW= z)4QZWf}TEM8eezo(dBDjwfW9eva*7rh|Y zIf<~-bK=KuSVg-cK~JABjrUym?9C-Vl-n+eu*czd|LOWw^bZpB^a;~QJ!(_>Ac?TY z;j=$*-75My33~d3X{3>1Q^pb!VW)lVE!VDMydptQpD>Ly!fnc!NFwa?ez>b&y^3*{ z1U-GiG_HBZ12=!Fv7JQN@eXOIEQiAwf@{ zFpc5Wzj4!l*4l?e*!5ivt2{@Mh^kmlvIYr_obKrprlFDA zHAsYA=MQO+(0J~iK4BV~ao&#k!-=5lJSYtkpU5-h0fcF2=Jff4MA&scmj(&VukPs+ zrlA#pYmf-Lu1lmrLhA(g^a<0@O2#!vgk9HH+h*Qmaah}?7H5S1_`Y{-P0#bLn~z0AQ5(5w@ZVB*3s_i6Q-e+zH5*OyY4@v zK|=ch_w)(V(2m75NQ7PYQPLoxeT{qiglTB! zgGAVMK9>dw&9Cn16Q-dRfNPKlyRJ*5K|<>U_w)(V&`QQNNQ7P2SJEJ%^^SY`glT9+ z<|7=5u>4D(uIqMbkkC5X zJ$=G7w9@yvmPFWf{~-+$+7Gy=Pnd>wEXNk-FV`Ru_E_Gr zB@GhVpSh<`n8qLB-G=ezj>~uDO(D14cC@_zDjn(aUHXbE&fJwK^Ay{N@-7pz=Ltp? zJ8S$@Ivf1|=;>v8ifzaJo%}YdP1cwr7**`7@xRlP7N6DA%k&i6j$7U>lQrfDMio12 z@cb@4#kS+V_`I7}_BP$DF-I_}*wRROu#{O#q^H<++%M<1Srv^Lf>FiJ8deup!lpq_ zu}$M0A3ttyvy#Rf!Kh+q4LcibZOb(1DYj{pcQ56#nj;uh?5tsL@w66i8uS#~j{7_5 zZC3y8hadmitT9J0s@RQ&-)lfmv5}7>jm93KRC!dfo3c8Bd?fqwU5T>es@#@YLuIu` zFsj&DLpA6GJ;k=;s{W-hM=+|`S;P8YYP(Cz2R+3$4Ygxw%n^(#wlr{Ml%8UnhWcaC zm?0Qd?5v@Y!Sg{+u}wqciZtd3Mio12XoPbOdWvlt8Xu)GM=+|`SwmyHYtU0{)6h6C zjX8o*#m*XO~Nm21#b zY&&jww@lWUBN$cetdV9lyGzeC=qa`x_wSx?+F)N-$r^J6qlzt!lm|v!%4ZyUifzYz+(~yFzTvMQ8S`M5U{tXi4WDc2DK_$PEayY1+9Q-I zk1BRkR>!QY=qa`xSLL?J8Y-(jf>FiJ8md7j=qa`xSM@KAIf7Be&KlPLY(}tr&{J&F zP&<~!9Kon!O9OYx(o<~HP=72MGX$fGoi#Kvcs}SUwrOZwk;WXssA6Xgjc~3(Pq9ry z#TEBN$ces$uVF zbb_8@+i^ATDj$}b{2P~L^Y{snZfSN|Ic1F!pK`IJhs4=$d*kZce*2G{ zj`%6TsImgw*Pw^QbKZ8tYO%Pwqd|gEWhJ|>K@W-d{Mj|DU;3-Zb~H#Zs;tQOHRvJn z-~Z27t-j_Ff0@RA+ik~hT#{f^*;(up^pLQ(jeqc67pJ$FPc=v|O4?}@oD%eqklrB# zqf~~QeGPg@sN4=A7^Sw*A?P8Y`agtVlzKsjpofIo@gW4G)Hgc>JtWj04C8e-PfRJpRo5&OnVfGZ0D#lGwc)ekhuNFzciB%5{xP{+`a}qB(C|bQ-^+i zkYH4qsrNPLX^At2e!C*^xRWBPtT^^H=pixQ_;o{?;W{mm1f$BzXC8fzOO+Ki9fjb z>>`p{q540BV3gW)hoFaq+VLR-qtrJ$1U)3w9}giIr7@;M(9;q=60P=Ykc37b zkJ4D#(V&Nf#>b8Z2}Wtm?`Y6NLgRc#g9M{AcXc%A*(dDjAGs+XOk)?=pmu?Lq~%Iqsp1veGPhA!dFfm4H8-{c@+0>Df#u+?(Rr% z-&VtuF>WFy*X$za*W|OR+sCF+^qO|Zvhg~QXOHl&PaQ-=4PLX07BeMc4|olBsVADM z$gL5jbf+532cuXbZCS-`>zZBc?oKpSBx3)0P^uWk5@}Nv`QbRU~5NbWo}o#S&R8UYhP2cx7`Yb=oH`FLUBH z_b5K$#-0=QB|chFzDitL|1a z^n_i{4yPE?m?L6TBVii6>m{PA}Xkv*+l#*#fkqmM_0Z5kTkoS-M{I*LkTj?jqeQDK{gMrzlfC+s>K zNMnxBY~WF0n}%i_*Ptitaz9JiJI@iZk0K$B^HQ%;S@}vYr9|_q@6RsB&dd6F(&!Q~ zQjBC4*b{kXB#GL1QcQDM6V?s}mo?8|qtI&+N~f>B|c zhSi0Yu$2`(VW(LwugFzaa|ENpHVwOz!&-`I&=dCMSYKN{=7?BRlQ0eI8`k1YBcix& zw{{h0hvx}Kg$)g#Yv~EQrs`O3S4!0$5vzL=D67QRd?dT(!;hZFb&N(t`Sjn{_x{!hLgq|!KkpM(cRreRGrU5!-(Y~{S>vj?Y7H?GCSLy zHDO;iv}*=>!ah2b^+Uej$NHa*S*8(Dmo-sAm`18W+YdTHPuO-(Q9jF=HRcFLg>4$v z|H?c_PuNF?vYyKta|ENpHVy6WJRkIgeRL@6(yTE@Fe+@B|c zMydrr8whDHY0peO7)UTt&Rog*~*cvRS?p%KnC=n1=yyV95=G>Upu*ruV8 z+BN72yUqsEm?JdKdsNt_k@{bqqv#2{+%I~LH0Fpht67PLEe+edxDhSiCG1q#P<%6EE?LOpuw@}sqv52V4 zny4U5Beg`^54r|DVW)e9wYJL|Aj%Fh)zoE8R1l`2-JNUD6ZX-etV^>7h`O>g4Mv6S z8nLDx=?VMjP}bMd2x1XYmo-sAm`17#+Yj29IMNe#8h3StCToDGD}5hD5fy}Kq&8J{ zEF(Q(A05gLDQkczJIFLfUDiYeVH&A#*nZGvoROZetzDfnT>61$#XMMuvV%@mY5mo1NX;=%)KV5Ox(~Bg^JyW>`OMDtiHuR8So+5rq zFsj`9wXZ=B3D!-kL4r}`9=3fAdRiji4|g!ZmRRoI+b8HD!M@Vwg9M|>U5NV{^pIem zZ#76Ts@zSvuR#w9j$N$=2}YH>LiaW3A;B@Y)gZyBa(C;#20bKV#<6FY;x}$cFsj^h zyRSh{OT;Yd3S-t8HzYW7O8eNp20bLC7ev({!6=pCW?zFI5-PVKss;&0sVxMNGoHp0 zdPu1LgQyxL7^OBHMAe{&gxYZsRf7bh)Hj2u8uXA*e+;5(kYJQXr68&XJuSh#K?<)L zBsBVLt)4Yjb~NZAq4CjaPf*n$!6?lV9SwR&Xq@k8kYH4veYT-dQ$^1{QTCjklboG= z=h-43OS77%q&!1Y`$yHFhXnVyp9j?&cOuFOq8d&_6d4O@Z3q84-$+jPo?c^&_jaffLaX_j4Dsp?Q76Og6FbY z4HAqhPYLd8&_g25+)d{w5{xQOJML@HLxSfP+kB8EAswU3C)}y6)Bu* z#Ga#`flRqQ(Nx8*sGcJ|Bvr9jt7mRIM6B-96%*Yda^k5X5&NBK&RM#QVu`f%5$ouB zjx6m5PPD9IrO)$z2c;_ZA5|}nyHg@otUSMaqN$2CHP75mH9BRrv6Qex+OmqZVXf!w ziI-KZUTeE@y47H+VohD!v8S*lVii`e(SHT0QZEW3JrS{AA54|oieibhsfzW^W#yW= zr=3S?33_5hW_4axmIu`!qgW!XMyxD&)$&B!Rjhq3E7#9E^}&3^itMs-Rlh^T9DW(D zXP;=QVwG_ju2dgXR6`gO_uJ2~cUfGWRshU72}bEl^BsbombmZk#kZVs2yyzw5%szBW&1nb^35HB z9uhxs#l3fT|ASKxAsF@V(wFW3<_q==%{1rqkoeS#@3s4(XPk5h!Kl+OzDH^$Jq>#H ziA6_)M7DF3eOtJn4|+)4`(byT$p;BW*%y!d^+6Ab-+bVmXX=9lqfSp>icVk1?B+Z? zEpgUty9(m;izDhm>5JFtOP?JLdPp4q`#a3^4-$;JAbq*J-_PkG@ywIYnCa&v81=`` zzvIk!MGuJw{@T~fj8`NWb;tB2^)gnrBLh7oUjBjG*AaD|V3d8K{j(qa{!V?+L*fa? zziRiB-~T;_5RB57<~syEE%8;Utk#DRr(YaV`qF%dpofI%{nBqd?GS=dR_fP%>=_+` z9uih=$9`fwgkV%|3q67!61n~_?P!o-l(p#_U;5k*K@SOQ$1nejUp$0hl=aQ@CBqIu z4+-m!-};VUI)q@9jaTVQh8=>QmN;wo)|dY3A%u-SB}!kK?-2Bmu<`NJcfIluf>Ac+ zzwkLP?hy2luyOu-A92+o1f%lo^O6oh&pvVWAw;Hgl+D`xe9%L}=G}fiNHEG)AL+}I zomA07!qyM{`XIq5TSd*atMIhMeQS$p$6X%FR!gN_+1jq(Kj$!gaAi*eG)%N>2 zJtS;h+VAHi7?oG&z43}35_x^y8yQG2%JvNXahDzvwomAfyCfL(-g`e_m%fDCX;<`+ zc=PQaIx~NeVASasKVWuN3r|Zt^aP00FODeF?$77+kTAXed`^N<+{3l4ogNb0w>fcc z+7Et9+7B+H7hN|*uf1-_qr^JZ$8|$X(6dk2NOTYpqtA6ijCNBZ+Us>g^p6uwRZEmU zKh>H z{`26niYS&yo2uBQTsOq7=tNURBKBswK*v>Y!A`J}T?w z`D04N%KN$@R{AHJDiX05nQE{lGKwYAmK8_+SW};9s#>D#6AnsM>t6b)YuIzbzS`%HI1iWJN$$@NPKg*xNLZ@Uo6_yO zOUsMC^G~mdD2`WGr`frTK6d7Aj$l;SrjhPk_U8vb|E%A-hMusm_IWqXi_Q@-&XX{W z@-*Pff9!eJL=?xtt1&ZJKIVv+4M@0#o(BB+|MJhSiKzd-uq#%vqza;&7^o;1XuLW- zhJv~Kdglwo(7jTph}Zy)|L zsD(IZN%m0{!)J_p5kn(p;_}xg&j+;-`)p@FSTQj3(~G!i#IFG#eg5yD7Ghtu>}z8U zE~gCcsg(hZ$PCMSFJC*Sm+sp=UuEZAGmw4Kix?V_;g-igzIm<|V$Y&{&rmVAyH^G@ zB2zEloV|5UFYO1s8t{Ed#XvPkFJfrKe^FYd&)zs!3o&AaFDB@tum&rJdJ%_4`=1t8 z)ht$dt*ozpUDn{xxRIe=#1X6Z`$4N}gIb8E3s!1qAiH55o-)*n7#hgASXEXB2el9* zR=ER!M#WGsVraxKcowUJmapS7t*bKq{ zUAne9_>^A0)6eU2w~Xhg80tj~4ea=^s;mxPsf8HxDtF<~s2J)+EE@N$4%+@IuZ4M) zcxrtD-}{8dhJm|EFJg(+&g$S^EyNz({K9{X)rNscrx!6aV$63|2lr|r&UuyltBT>X z#Jz~2k-rACI=EL0vCnp%1E?67`RPU6G~(BQR@L@uA@)_v{cfzm@sz>7RvFNU%rIIV zJkU#fXU|tW2T(DPebS2<8j;~ftAp0Dq?hNbWFSAX|EL)1MGTF|)T7nGgIb8E_U6vJ zBCL;!fohOm#L&P#6f@rH;6W|KSqJf!0vZ*=E1Y`~hsKTF9lf->Yq=!)!RN<*@NQG* zX^43xjwe5McWNP?SDx3H*W)gub&&L$F4T({8edw@{oQi!7uFA|g?L_h?gSbYL%oRG zlUqOdk5z=1tsngGcnX1D^UBjO(0EZW)QcDzv9lb}52}TDUU?1(8Wlsmh@oN6u-KiA z-&sGX7UFs3c_wI74D}+0hKO~x} zI(BzzA)Z&B*N9l%$WSk0Xdvfe9aY(+5c`d{$ z@x1cU2dZL%lR2 zy#{vPc_&yCnQ`<=Jwq*9hG&VI;cWNPi1ZBfPFZEp<772Z?Vh2Qo{?`}{y$dq(unjL z=zepbfG#!bxoY3fEZNUx!t rsdmDu-80mp4DHoxhI(m4dWL3w?KxGuXQ-uTuq&<^+B<7R?%eqgQx41X literal 0 HcmV?d00001 diff --git "a/assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\346\242\2016.0-40.STL" "b/assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\346\242\2016.0-40.STL" new file mode 100644 index 0000000000000000000000000000000000000000..159b37077ef7b001e35b9a235ea6e287658df48f GIT binary patch literal 416884 zcmbTf3;2CiS?@bR*curqUXG@Q7c%pLwl`9b25T+yQXV^9klHDgrlv^&>dqamiZ`~V2u?x`! z#E%|z(c;sOx@ev?o_F>e7a#olE6skziBHWMW_S24XV+fzrtKMjdDJ!&&%Ex^?He9` zxY@6J+I!N!kw(r(O4Z!+QEa8k{+`JCEBQz{pF44(*~+=uH9Q&1+2_CS&Wrne`vmiR z*Zq%Oyz2Us%>GZ$dQbYdGdulTf6Ey?Bwlp>9a7Hc^Q>LNlhG24y5^UTS^WGx9~Th$ zxbOXg7n`T(ZOtz9G9c(7ku@&=>~97H)o;4==*3q*^91Pamva*RGmcIH7NxsUpEBmPm)+ zkn_%tMdIKy?z%YY)ei_Xcq~S-O+zBJM7FCObGyQ z{=hn}v>Fw9qK$^pMDHZ2wV|QM@u}^YO?xT`~X0-LRT}|Kr|&N-l+e zc;DORuR8u^o88i7eek%_3kZ4wBFF~`=3_cl^aMnpK|;1gu|(RkV)QqgYR^20bKB|H#YJ@gofqjAEN^HF#(G;-9%} zn?`5rMJ2V-T`D~!9{`M#FvRSGvbCCp!_v9-~sZT0RFPmlrc*^vKm-~jWLp$V zq)ipe=f`ilWc$+Vo^R(U9;qehA)zDL)xb2tD5WYWU0!)<d-Vu==>OH@K}t}c{d<5I-5u1yxFB4m;813)vc#?YjCyqM!_J943{kQ^85)&5bx@bEx`9unIZU*BK(k{bdI5{&xFVV~>Iy?GXB z&_m+vhkv|3Y4(_apohdOpY_rHbx-_KkSY?4y5JsH_n-R4V*?F(NSt=dHGS88InW@% zr~|jZvOnVDqA{R{f1&+i*(&_m*T&w69+j~#x?83{)H@Hc*^UmVQO!^eH_ z@>>o&_{SHVcUkuQ$IA~pc+I=sTF!k}-ud8zjyo}^^9~*o%ZGIb&wkMH`w)!!v)?@S z;B!9w>VTk!#BY85JAK!kvk$>2j$<8u%Nac+KJfLg_rp6R0O|Zef>9iaT0)*}E?p63 z>qus|1U)2_!hHxvsSE>x9ug|)eTXKiw1t3BD=`lVwHUi{>hN36NHkHOy34^M4}VTX zz(ay<8WO1nI}lA&`Fm;kKq_ILhCnX>kTlc>Q#)Pt>Vw;CtN+{ITY?@E>hnfV6O7V0 z7HH5zLSt8;L4r{lj{^;QNN5ZWG)OQ?=aoQ%9uhj21R5k5rSoH;K@SO?69WwrjM8~N z(4dEe&h3E)2}bGaBha9Sgsy4=4URs#p0g;9V;z3W89gL)Z5O191f!-?MGpyG+XWgV z7{wAnHd3#>?uU*`$0_$2M?L-fl3ive{PctG(+{&2TH>+u2dAj{HuvqneCq@I^p4)_ zxBv6`eL9N<;}tz5KL7Ry^yyuQ(XB>~O7ES_Q}mW*bChTadPp33)EEj z-9`C47!dT3_~`vl=+pbCeF#Q9=(}E%%J7_kpohfmpMF9jp1cpis7o(?WuLA~0)ieA zSuf2y*oR;gYqrC0IirU}F1IwxBG4egD7H69q_+FrPrrYk-iFz+zVW~A*Qd8uW|ubI z1se2_$gO>tanov$U{vWV_YO4JbFxNyXO2{D1A={!M9yD&tG^GyDE5L5zvYY`61fki zc?W?82}ZGRLL$`%`!nl?HQN&OkYK4#6O20Tmh<}cZJuY>^DRLS326t{KB|Lx9^q7* zW~-jeZZ*`4%%dJ`wt8AXXe=?0#uBqt>H$Fy35|9Eq1>8BZP#qI{D9EtY#x@6YBnI~ zA)(p~2x_Qr@91^-)v?5CiiAdqK!Yh^)O3B&LqcO$ph1FBYzxRn>K|+wjAC1833^Cm zy?6!$2}ZHSv>I$b>f4rEwzrm`hlEB6qo)Z*P4_5zNNDT|G)ORty}3=*TVHy?Vt4|< zS(ESRu2{rR)owigm{W(RgCF_CQKt@11V8@=H`Y0qtp+_LPPz2RQ{$(DBpCIM?w=-7 z#i)~i@s`E#3~`#EheZFNuP)-JgCrPr&zD@kh@TG9L*ntb`P?FYI!J<1Up(`pi}+a| zJtVF@>Eny|c_Il$y`%fkB7W9K4~c)d=hch&c_Il$J^Qr>Ch|cKiMt$+>u~Z`TKUBuM8p$d2rm{Kk7B9T}4mscq~S7E_bV;F>0ID z6=k-LWOhr?LqdA{5R58Eims{YA)#`c)X=d?Sy`0oCb)yt$Z1g;gU!}h8EBATl*Y8(tlK@W+Ked9Ze_$dwvMse&yQKfqWdPp4i&9CP#dxBJv zU=+u$Rzse79{WU?ts|M;67-Nz3ilxxr4k7UdPu0G_aPXinhgkgNT|gG&j3g;>d!uP zms8VQnSh{&1lx3n-*QHRQTlsu9;Al^+cYFnyW(3Jy$!W~r+c{V?s_mQf zAA(W3BMS(6c8N%XM6pZMyPtYvI)3z2jhAN1@Jkp_ukmnfb~S`B(gJn67= z(nuX?kYLpGIf{2Cib}_Bzq<@mHP2Bbq-TGhCK#m>2?%<2i7)R%sH`kXH5(B0>=Ka% z3DvnBS1mNqpl6qeG)SoJ+Huv>0u6e0iAaNl`k)&n^*ZkkD9S$JNLeXwb7u zL>eSCCfafNM6biIzBjNa5*oGb?*P(x#bYsQdM=K>WZdTdp>HD1R?V8-YS2SM-`xg; zzK}JKzO^;G94Wf5rH6#R84ff^Fe;~TcuU&hx12G(`a%||iq2}xISGAhJDI9-EJiW4 zNK`%JlrkZqFMuaC3c)CrdaJ=N;q{%U9akeppg|7_eQ~-E!6=qtn<{!p=sVazg9M}4 zrdtiRh8#7#0Y9|*Ad&Tk_n)l>kHx4`hNYfbf*umN6o&Vz(*&dRMfP_0Dns9inn&j= zv-M?YK+r=%UxNmOzLqqPzPmKL&{59mAyKsFfd&ai>AU2BV9xb@EmE}&2}4+(v18>ET^qgW!X20bM71#qB2f>G>gt;XAKKBj-? zeV$-XaUTE1WBNH%gJ-_m?szY~`8NFxk16wrLzfExOOb?0WHMdXqwex_W2J=L^%{e^*5#*eNY>VO>>{f#w64P(>Nib^q z9X;#d-_E>kfAO7PZRNw%wyC0r#3P<^RR8*qJufI-5{%lnKCCUNHfOmlu@u5oS&5R6 zhSAdmqm;scP}?=n9Z&n#_R)7aV0O78->v;EhL&ayFonqU-D8xq^BK|*>q=1&uhVyU+T%S0{a zR@4WH3tsi=e5uq7V-=A-M(-eb==rp_cT zM0DNGd7&S=_#SmuDM#&AgB}w1`O@9$jMiy_QPcULhs5ole%CsKw$&iPD3)PMutfj* zWp~KeR9mzwvs;21Byvf|bA(ASD%VpybD1?*=u&In{q+3)@yS7|at?7}NJ90$55XwaQ$Wx|LalNif>G)#0YQ&ihDA}k!*4mGhlJW# zph1FBY(0=jb-dPr#OnoLzW7Nbh4<^jQLXX>$qw)vokL@xDsbuki* zV!vrMnBH8v!%CjiYYBQtsn6C43Eas_PuS6R3 z>=Ka%30?e-uI`ZM0Hob`?m* z@Wy?Lh%|VtVwWhcfZJ-&Lt=Wpj3eH1%wo8Adg5VsSPXYUd_LD|T=Rv4^WpyWrgN^I z5BIfta-aVH_?qzjci+a*wM=XZ>-ByDh67M^yTckUd;F|hdulw|TxR<%| z@K4T%=Wu+V&}z^_;(ibK$b5Ke6cUzp5tb5Z2dQGtzx>pr7Q;O`^VDk4L*hsN>h_DF zq^Ai+{oN~$UJUir5-QzIt|^tM+0x$b)*#E|4^F;zK0Fs=8MYeqkWh;;y=j6`YHtBS z&(jZV=cygr9X7S6HAuYo@a=qf?mJB|N*eRsvZ9BC^z0d6sA0!q6nk1ru-~b4XE`O* zZV7rwsAi3xCK$z*-xBNxU;5K8%!lWR)NToSNc{QXc@DsKpHwl5{ifBRhs5%~eygT% znqbuQ=);jyBdWE;=^jN73H92bwUc0!`g}mpqp`%Ic%(4r+uW8&XdDYPcq~S7jA=DE z;;3|QMXE@sHup&tqtxCke{HJhA)!_oXpmqO&qS>TM`WINRfhB3v4oz02=YOKb)$D- zfd)MR5onO$J2rmb(&4w9(L-YLyNQkNOq2S$*FC4%x}G=NB$oEyZn^Pet$Y81W8J%6 z`a6EhjbFE|^$ao3vs>$}OtAqZ4WGTS#*PTFeddsl3+Jwpuc^m`-bkCr z*Y&O%PAoh7EjOC6V;;@XFxyAhv4-ZxSd_1hzsC7vOyt=cWtI2!Fw+Sd$j7p?-*Us_ zYBmjsd~Yz;V0uYt4%0paqgW!A9Q|jx$>mel1z-1?!(_)T+Q>&G=pmswOhzl%{#kBF zFp8yKLJPOtXco#mmx=e_b+7p>_V<>chXl*89KHN^xgo(Q&C78OVap9YB-qAU4YpVH z6+5o_N1#Cu3C&^JhhP*-y-gK8Byx$Ay$9l!SXu+4*b7<>)}ZDQS=w1QEkO?n&Au>t znqZV>Tm*#XNtj17Ak6j=e4KN7NNCPPprLsr=FzMtXhc1#XcP|#%{2-%sIHk#(C7k! z`5>WLPx}yz(mbGmphxq4Zbhm{_-g!n*T=B3|8Q2@uXK4_&HV}T!TMknYqrC0xnWId zju&#iU#dvtHWv3mrixJV~Fn9y~J9oL`xt$TmIJ0|>j>$>-+wZm0S)Ianr%rr>&lj5-k2}UusZCTMn!kl9cB{Eec{Mq|nsbZ8r>mL)m>MQkMQsVCr#sph~KLsB0v0n|6 z@aM^64SM`J^`UBz@Mq*>4Ym?Sv4yrZ=x=-0ShHrh3Xf`#CF*aQ*1fNnF-{c;M)_(R zB9%Z;z3vhIE5mUZtl(#9I}knmMw_97VNE7Ob#riyyLip!XwhlH;IvlqcAU&Uoi z&_lvkjoFJ}l&||TCg>sItH$g_Fv{1H858u7@b5zQA{gZ>(~Jq9xmen3*{^13?NLAH z`NQWxmcCMUwHs@Y@OQMs{pY>syLVpf2fk*_dRPrJAedVczN*eRRU{ZST~>PkVe0<2 zXWjd*0%Hwd-+tZuP6BJ}BrqoY9ZO62o&>1ld3B{W%HWX=SXzV=>Bia~Tu#_`Wj36PD<#Mhz0ar_ES{1fzVf zoH60MwhXPWq{R1W858uBHdYAVn`KN;!}pbG_1gO2aY^`|HquxYZs;E+C5&P(h%~x+ zZgC|1?eaJuJQkxk615sEci$Q2Q0tt8?=dq@73-W)EWTRlg=ZkgkJ8cYQmEV$&Q>9~>hlKC)u@}K8-<@qt_>Nrb-uLsWc6tji zCVYRjb?>{g)qKo%36=>7<;lveEh`d?;z-mI%%Sg`R#RnV*b*#V622$eIOil7#ngrx z^IRq*Skn6vRz7TRE#do}rRTeKXSr$zXB^+}tVY>+(DyzY=bUNxozvFC?sY*8vR#pw z)*!(s*?|T@{ubgqJSXPW;YE>2X zPrXju=6*oJckmf&@K}suska(F2Xfu}cSU>M5Bj%V>)yW%+l%1+APN7%QTbSww59h^ zwzhgXZ!=1Nw-Rad!6^TJu%;>?cq|hB?c%s}Nia%zvazd86-(5=^Qx(u?~ZWHISK#9 zY$8>5EJm@OELBVUZ|diK*2m{%)Go0DK@SQ4B4)2tF^cWYj=mf;Sc*!!l_*QS#0~^K zBvcAPeUM<3O4^BBS=GMR{m9+g`!S>HEbD-NH{Avo*eOtHgY_wU;rm^mG3vZr%IWb>mc#V3dD9I3}2O z{~EBS%F3|KhcwJX!oP_dYmi`+e^ECk=wZ3>NYkkbi1}pcT0U5Ad`i`7&=U}|T@4a^ z*2Cv0tp+^-5onN*ZBcxJ)M~IbsQ!&$o?3z)68=@|xCTiu%Djg7+WG zlD68<=egWT__u^(4UW!?;uzfKT*uvH4gYfTQ2Pf7|F(0SDwWkXYcPsqOq(jrlQDu< zHJSlqe{TtTNN5I3KxoDeG|H$}jx-MldWuFNG$SP-G%v$EnsH&aW?TdWJtQ>aA|RL# z&0Df4rm(|rxUwv1C*dm)sRow?YY9fNq#=>6GUy?p=cU`-v4jMpc51MuimgO*W9+y* z(sZgwXqL@BsbZAg-3J6cBsBMDAA(W2EtGE*$32SeDr=P0jE4KDQnOLci-&|}Sp}&o zrC10?O}BQ%nZ6VTWIxWwAqO{)GJIgJQFp4G8ri$gGSx9zV9;qehA)$FP`=p9dnq?CZ^!WNd!+f8pU6oW74~cxF@@4V3 z?UG=W<}(GUqDOP1EQ&|!@LO)^A)&cgfd&ai>v`yRxs{aFzUmChK!f8s z3C*B$V%gbmXzitR88v-2DEY|WFRXiC&vM;sy-xdkIk^2d^$*`&W8M3@#p~WzJs#&= zE0^1`e20p4uXWa4qevtTdPw*l8e`MzKVc1^Z{YVTt;Rq(SM{ zoU`0X_-d%*RFPnm@Axn#=po_zLhMB_%6G096ZDYq-75AX809-~j0t*3_^um!5sdPk zM8*U?Bz*Ufy$DA6jwoY-9umF_%3cJc*wfmUNDm3$&1I}Xf>G>`tp;0S8CSORJg#tz zX$g8r=zMPUG{LB1mvO8m=pmu2zCeQnqlz7A&_kl!$&^xPQ$>PN#f~&Me~&Zs$~|19 zK@W-YTx&mqQRPTcs^}q6?1DXde^wknkPh_aYeOJG74p zdPw+=@Ou%A@*Ud81U)2tNBF%6M)?lyV}c$Mz9alz1f$qO$E{@86Mo&3@EzgD8ax)G z*p6F``SHgbEIYETd+oz(tx~(~n%xrgkkAgh>HF|;sz@-3y`a^ghlKXz4KzqFihZTk zV5)pq_I1w^X$g8r_%86u`Lb}!4GBj1KK0|WqKAaX1kF@2tEiiGw; z_h+v)A0(Qny8ro(20SEuFZ6Lfw8y%sH&J!(^$87oW=X>Lbl;0;qUwJ1I|Mu=d~f=_ z2u7)%w!8g<9ulhmeF#RWy*W{9kWp&87PUikypH;rp~mW7*knxgo(Q-_3rUDtbt0L`~oCjx|Uy%6GFLYtTbN<9wh& zf>FMk{aAw@5;|W68YCFyyV;L5=pmu=ZlFPeQNEk~xOC|uq3Z|NC{>=H^*!sOecJJI zn`??uzMK6xAB@tqj~#cKpofI-6+hM>!6==(EVasl{j=QAL&Eo_A8U|c6#HYVK@SO? zcZ1R;!KmqeuID9|L){y~-kRN}N_UNjDqq6u9&R6kQMxw_2zp599&R6kQMxw_2zp59 zesCXxQM#LSV%gcRK2b*FECFR|sn%MCpwd?&+kA0)vj-&t_n66qn~I~k5O zNHEHG7911wkno)h$EhO0DBoFdtU(V6-^p;SL4r}fv*1{R9umHj;aGzNqkLzC-N6tpXPNa$%~FqV*Dl%A0Wgzww8?tPci`kXpQm7edKhlKAxI<5~AjPe~s zcgxClmo^O&zGLZL1f$p=JN(j02xXUS)9@V&>(hGsJAiZ^WLc5$9TLZ>BEcx%k#S7W zL&A4@+>2n8@4`1G=po@dR_;YG%69-96ZDYqeFFC)7^NfmeUvI?xuJ)I?{_$%VaH;W z@2@x}=po_zHtt0*%6FC=6ZDYq{U`S#7{xbDVcVVOYd8|VkLFl|$6^%U@3b0x&snZG z$~!h*eY6BUB)HbkG{Gp}>v^0Hj(xmx;#k>g&_jZ$ohBINyIhY`MGuLcd@PGnefv7k zHR$_>5AO|1Nw=wDiIVV@o5rak!Kh{(CWtIIDl1Es@?^I1WHx{_iqbh#zsN4J13?do^1QvIcA8++X}6r$uW$3b z%j&(euzZi>9ul&*l~@)eBrHm)wdX-4b|92Lqgvo8{HCIgG}F4ThvZj32SE+lh8NZfd-GosOi$BhlE;8ph1FB ztS4o`{#kBVYg*U9j>{vp1U)2jNte~}HI^(3x7?6m)O4NGLqh8vSPI)zkzf?tTT8I@ zF^cW2CFmic)eC}Dkzf>CrD-gS(sIK#s_*FSxNOrUb|B~>q3`yMo+cPoT4?mtfF2UL zjg@@}#^(^(3h=+U|#mUbSg%?CXswB|^Va}tcwiY@`6)pN|FRZh$BzNB_Qb0x-YjPRV1{wOrXJ3F{+edlyiDW=!=*@g9M|rl2SmFRFyWW zHH2=MNiX$g8rOt*Ft zjM8j~ZM|lYQ2E+v=+ByQVNpENbgD??R$2Bp8IKG+7Nc@6D7$%#33^J8THcCOkfz3JF<%w`9ALgkXebAtXgs%`hZdW82uV&m33^ zZK`-IUrqT?=e?5fRhq}CVm=tA5nG{u&?cTq&6S)knq*C#~LIUrN7U2 zTO!lzD_S3FS&{J7wD(FCqgWzs&Y5=Q+}0eJ&Idgtd`;iiEGyy;rIj#U5NrX(%g}qFTv5y_Pjd zLM_zmLqc`#`8>C3MsdVwQ{^l0uX|sozm}C9sU=h&<{{xL{*TMbcO_W&zFWbeYLM{V z5yo}SR56OJC(Oq-mlX-=1?ztBSd8L%rPW}W_#O&}nsXAqf5W(RnR7<5)Z0|~t^{dL zQQgy^j&SqcF_A5igj)MPEs;@7ZJR23NT_!O8YCFSHr;CQOHY2=S>D%1&&cQ@QLZ2N zBN(N3!a?cMLqgZ6heT{GsvIer@kCZ~jaQ#{ceR zw@rf{x7R)A9ZVC9ayx6h?4{2<`TzLC7iNtmJ#MG<=uZ0h;-uMQQgl8WfapAG)kHaw zHGcT=(@uHMZ~dR9L66(%tMA)@&l{0O@kh{(~cMq z`s(6QzwmHrfapAG)kHawHQxQSe?R3xkN;)UpvUcX&-e8W(RtLWiE<)q{KB*EHT%Wu zf5J5AaeLi!7C}RF9<^$soX8qKbk|4Be(rA`Y8v#o-OitAh|Z%{%`6L_Kan*~Jojg3 z7r*b0ra_O}?Y>3XIR!x)>S>yC$UogAFv%l9g=y7}9 za}Gj7bRM;8qMXPYd56FJ-~6M;?W&RD%2nT5J8ak_)20d=qbFDO{2%Qrx%I&P7v$JW? z<95Afkj50DbGt>koi%h_VjA?gU9WwlF-7P~#-iNL8oItR4SL+J*KpF9B6LM&QEq1q zT_>6bJ#N=)QE5yOy0Ww=x3h+>cTIyHx9c^vG^Pk$AzPH&Swq+Dra_O}>t5IJ(wHI` z<#yK4-Gph-<9556z%-$|7aP^w&Kl)c&N}=;((To-_nFZxp|?xsiHWfW3Ab0n{b!(2 z?$65oYfOwaNVvVy8m8@?aLM`Zy>pHtG1egA_ORP#q*0z_6i-ZyHAuL<(r#dpMtO=; zJTWoWAmR2Z{F=O!Re6t7G-6_`LBj2NA05=Wx6xsKTGk^0jZK$+et%y3#5NPsOSV5% zTN*)+(KrI9ltGgPJ*78$Qrp#<(85)NVr{R7;lOO37-p`a#&MBB5UNnk^4xN zAmMgySLZK2aNY%PD;gx|i3w;NND@mDZr4<$I?MGT4I^}1^TY(o>Z+_k!tE4QN@3oV zl@avBMAlFZ?hsDbb|noGs^{XVDIt+Ha{o(hH`QmiB;j`LAJQP9_G+G(Fpbg&O@oBn zwbu?BAk^>76BAiOBZFy>aJ!CI(jcMn!#pvOH8jGR1_`(8xGN138VAi26InwewP}!W zd);f)mIeuWVj^qk9Az3L+|FfX=PPNDpeH7zaUk`otkIEhJFT;R=0_Ll`(f9p1U)gK zvbrjbK&C;$?fP}5G*Ver!dGZoAtfZTMykQ9Qm--%5^m?RvaiylL4ux`$Qrr-rCz17 z@?$w&zq^wL3IFaUp9cq;MAk@WwN3tCmwqJNPAklR^XrRGKk6cBkf0|fOe5tXrz~rb zaGT#4={#5o|N3Z!l#s|8xh`@EXAKf=uY3PiDr=CSCnmB+Zd19XWDOE-uY3RID{GLT zCnmB+?i;CBgT~q&=V8TuyZX5w`)F9o#{N7HH^@4%@Y$S zt5c8)TTkg?Rx%@1__-3%o7t?Blo|2<=3Sj3AgKcP#Pq3UNTQiWR1Un{d{)J zTOVK=e3It&y60+U(*&d3&b{`rUq60!<_CVvH0W`=U6pN`;0ji5XN~jDJ90LA<`YeW z9=F#$*TR}680B`>IQIvxKII>7|LdkfkK64EUDE{D@p3zBoc>Gao|5Jomj&KfUz=`#Zm)Z;U^h)L%I&Oi@`K-f)eo-DHVt~*UiaFdS3d+6u~IBvqpMTy-9NoOoJY`)9Bo+-8MxuQI*IV zKX>d4HeWvHdriZmlBY%`4Xn_%2f?UnXN`1QzRCZ!A3fEs8YwQHarPlfRH2iNd|U;M z;;B)!thPl%Io~C)j+;s$5m`f}TZkG}%gT)0hFXbf(BpP(yV95<)DkVq z?X02Jp30}|=yALDL1|18>QNTucGgfoHw}8+u474x&UHRTXk@S`x3h-EE7PFI?K&n( zV~WrSXHjlv4UM9vL66&YY?sCqp^@66+|C+08<++?Zr5{^G^PlhaV*O1tfBLuY0%?# zJ=aQOiqM(UqTJ3JIy;*NJ#N=)25C$Yx&p8$x2-eiHy$Qoy)_bdOm-g%L5d!6$1`QG1ok)S6gvc^}^GlnneofiqW*S)X& zm-9h_o|woQ|8IJF{%yVUBH{MB_q9f|1_^p%B5Qm*<>AwMUP8j{b?>X8W(^Yb#6;Hk zK&p!u>zx+~x9iHfs&f*)#_I|xA(1t{klNG{FD_4`NVvW3eMQ=w4-)jmMAp#TC3~ty z!tHhME9+(r67<9bH1hMrB?-4{K4ztVNW%yn*E}(SvdY(2OA>C^(w!F#m6Z`HAM?aS z)=&-Z5Kh;2B@Gg48Rm(Jtf7`@V_+g%y$Ql~qOoN2mbrh8b35|p1iHWSCk=is!xLwa5(jcMn+&nRn zHFSH`ElF_ASsk?P_k zz4IdBcKT-c;#c-*?uRr;&=V6`BaPIXbRM*OXA*9&d#&6wt7Cg5=!uD}ke)Ooku^S3T4Jitt|Q@g?H|%0q4sK?n8+IHQKmt{?b^?!K|=k`JTZ|q zG%}b53AgKbB@Gf9Kg<&oSwkb7X^?Qcj=Rzzp>fbWF=6#l#&**n;dVWLNJC@05gO0U z6BAiOXPh0v>3SZN1__;)%o7t?bdi3OVAS&x!2}5$iv(Z5^ksY zqBq{H?i1J&^u$Egct^VTc%ROLB-~#0+}*P!=!uD}u}$|-$Gp4D{UG7?s^@;7EkRFA zWDU(|wE7_7_Ns6986`naOk|BOr2D~d>pV!p?N!emeOrQ_n8+G8r~AQ|Ke^2PAmR3^ z=l;AcK~GF%jnt;{97sD4l5l&~a~I#1peH7>#;ejh=l}7$W$p(Fx6_xi&p3L~bx%$` zE%zuA^u)xV(f@9l$w9*Hl8^7X*O|~5h$B)4i6ItVBX-xb}JtHIGb{Thv zRp448kAs6JCbEXcb}K6qZkO|i@77ErkLQCYCbEXkQKmt{?c4{yZ_#xZs$G$wCnmDS zGcdn|gxjk=uX#44wk7C^36)iz(P;S~;r6P}>#Yr?-p;I{CnmB+s`IOcIw#?FF01?3 z*3%O7#6;HM6&VS)SADy`GYNWPB5R}`mFGZOS&?vi)pMulmY^plvPK#iHt9TQ8YJ9a z_1sUoCFqHXtZ`MkCb>k z#+%ap;19i^oTEs%o!iw33qKE%peH5 z#`Wpk@g22Y5^k^he>?NG{l#~FwKPc36BAkE@6tK&PU+cbt`8D!ulh$k<*5GkAA6oO zNYE1#S>s33b?6IqKS;vuRlmIE_9=2M4HERkMAo<zT zMyPzu6BCw?Qs+B_)3semLv?P1>e)Ooku}s3XE`4v+^+pY8YI+S%@Y$@Lp{ngNVr}5 zximF8YDChnkOc*hDK`BAmMgB ze@KIb#&h$;MApzb$}~v0y&BF}(jdY01!F=Q2hw@aG)TC;>bZiUrK%G2#6;G3V0wr1 z8Ql+(aC_BjHB9A$1U)g4HBt@c_k)%X5^krl1__NH z=81`{p%KnBNVr|cU1^ZeIB1@j$Ql}{O@oBn_52|X5*p9V6BAh@oz?Og$23T|UC)Ek zAffY;d14}KyyW0nvse82dsCn2y63*cueRU+xc8@+tT9C}%I&Q2lAnCx?6~iKon0Z*l@xFf>CZm!$u!^+^+dZV}X@bN!1RaR9TeUD68b@I(po$^|5KnYKKtiT9n(C zk5cDG(Bt;1SN%&vtz?H_l-pUO{L1$-U%d9^+pfF!JddxZf8^!q-(vgUb6J(&m{>K0 z(`t#E)OIaZ|M0%I%~RV=>0S43ull3Tee*oEUC&2IFv{(mkMlR@Zr=E>Pc{vD+)nSj zZdlDz+f6Y!RZ|3`+_w7o$ro-?+qG6gkK3!XtH5ghfcO5Cx80Cnl-tm-{y~r1H6N$c zwwpC}2&KxR+(ua?Px^+Ulu5GJL-`n?a+@_}wL>t$pz8+pC_d@wWs$F_BxM-o%*( z3Aa~$yUITadSW7Lq%&uI4oAZ6+;%@XkDtTQ6BAh@T>;eRa3tJb_1q((CFqHXtZ_`b z_qa~;6G^ze>ba9dOVAS&S>vzMJ=AfZC~I<%a68QdIOpoQKZhehPfTQue@XX(|D<^t zB-~E(0KRZ=?$6;!&=V6`<5TIL_7^ojk%Zf;W`~lN;7%klku}nrpVZf^RQ0W?>@-a_LWDV8e z4&iidSJEJ%dNxl?WDT{%Sst%QxLx~)G)SnunkOc*hWemskZ`;9b7_!JzcWuvWDSia zra{8(I$lYGgvJl^#6;H6m}nX#+^*xUG)QP1G*3)q4UN>MLBj2N{*VRA&vS}jfC6j8FJZO$2BTJPfVz+>bwjRZm)(N;JmCV!F}6eB5UXl za+doC3Agjgsz)s1=Wz7IMAp!quxXHRJ3T`_>$Z#dIUGGPku~^KjfC5)p1ZTP1U)g4 zHTYDGgxjm0`?<9QJu#6r(g?Rn=Rq42Nw~f0+kN6l&=V6`BaPIXbRIMf5^k@W9r;?~ z2<+7t6ImmjaW?5ZXlEP}Zm)XoYS$9KR88}*})^6BAkEK)N41`S;35 zO~UO}|Iz!O&=0fsT7sUK$Qt?1YnTa0!tGUm`=_6fBA>ji=cr216BC2RFb9%^+a({v zZ2Xd{fyl=lJTZZ?N@vTiBjI+bk6|``Eh{5(`3#TH;kO2X}-T`g5sBuYIO zPfTPDwcRwTrFmr5MhoF~=^w*v{Fcb=b@0SQ)=(cb4H9mbem=~`Z;9OR22V_6jU&@o z@@c)>CgFA&uZG$9Es@8M!4nf%<8RWK_%6MpC*gJ(cYR(si98Mto|woQyt^aeb~%6e z{B{y~JRdwUku`LVvicz5c6#3a^zTcN!#sTw^u$Eg_-uLSWf~;hUiBZk_#QR2EkRFA zsI2PU9SOJ7yVNh;t(JPd%CJW5i_gxjnB zuU~eD6giAnBsg{D=!uD}k?*{QGY$#2^LTZ1ihT06o(C&IPfQFN!?~7(+a(`YI8^zADNx663t*X<|uvPfTPDoujNi zNVq+m2k)(RMWURSiYF$r#_s*#h4b8>byiDuJ)hg(TSDj8JqVRmb3d4_0E}?DUYAHi z*9?|(T_@~8WDQ-(><~`Z>nmxH(DjaaVj^qk8qPFGxLvOkr9nd1ZRUxItTDbHOjnjh zI9;!Ir9nd1pL-BlV|+iDu8@szx?Z2CbGu( zelXp!7~yoikCFxn-Pi0vWQ}}3n9hUt1d@c?^?pzqBy@jfo|qUk(pk-(y^?Ud-q%87 zAo6k3dC)vDfwHn|1`=-9`*Ufitc=Jdn$CkYA4QKu*3dJ69m46MUCpIIqSSNo#6;HE zy&o)u)Af0YG)UwYp3Z~jiHWQ+z8@S2r|WYcX^_Z0HJt~|6BAiO&z5Fg`jK$EKEIL% zi9CL!^PqWRB5UXwnQ4%4yFQ1L28lclrt_eAVj^qs?v8}p^?9N+NaQm>IuDvBCb9KLcD?_Q1_|8{m?tK(hVEEQgM{1lK1v!S zbYEkhn8+Hs^Rjak3AgM0pfpJ6{>(fvF=!0uS`u#8`&wuWL_ThME^3~bKv`YYr5_2m z>;1VjR8~gh@)@o&Vj^qk8Nd$V^w6%B(jZalxp-nCYw+%lgxmFbi8M&$_Bvek#YEQN z-5m+H>vJDzkjVXRxO$C=tf6O1n=buGxLu!LNrOZlKhkqi^Tb5f&@(dAAmMg>4krx~ zc^pj7Ma>fvSwkbWX^?QcK2MYei9DVUcSSLgHF$SN!tLQaSnlCk!tdzT!;{UF5)xTs zcO9>CEUiXjgjPRMK1k3L6Dq5EKS;vux}J=eRVB2(i+N%qYiP|Hs}B-x*L88EK|<@) zm?tK(hE~!s4H9mr>%_8(k2FZo6BAkEYw4M2`k!f#aJ#NkBn=W;H^@9Oku|ikk!g@{ zyRNq+4H8=a$UHHTHMByLjfo`OuIolggM`*`GEYoojr7jBS;uP_shzItUrB?6)}t~{ zOk|C`Dpy)D%kBqBxSiKduywqoL4ux`7&OvaVRo)1;daT#aMxGY3Ns=fcksjn%IcIZ z{Ybc7>SMU;tEFp1E}y{@6ItWt^e!r`-L^wGJ+!O2%8Ep(=i-Tptf7`T%lRPTc3tOA z8YFUi9q#U8B5SBenFa~BOFtj3QClMSyTKC^Swm|Ang$8C>$-!=2Z=m>)ce7zMj6B8<{dOt|Q?Yf?fG<3~iHK_Gn%o7t?Bh_GD zvu1~Ix~_{O4H8Mh2(rdP~wEq4kf<6BAh@)kR*@$;LzyZr63Aq(MUKIGHCVtUl8F z!Q895^dsSRUH?iNdA8O-Xgwe7#d+jU(vX{fA>$mKI!WyD0*NKdx&+HE_8(?h!|cYQ5U>bZDgB5SB6 zZgM_IxLwz|Q$9%K_Bz}T#zfXok1`DsZrAntq(LJ0yWxH?CbEWB_%jU>ZkO?Dxa(_) zJbnzGn8+Gh+t4&fxLwyzR6a=Lad5aFjEStFk=is!xLwX4!(CrX?Gtmu)*8dtsPPfmXB-OIP({vB=FhqZodyXt@7_zSn6y8Ce|D-!g? zMAkUws285{H#e3w&q%nP)@L~VwcF4B#yzD$f}WVj8jrl-Z%?`YuYb+zgM{1ZTbV~* zwEgL0?j{Wq^u$EgIO6*6nO%MN(@lef+v$1xJKwOq;9kc{g9JS>ku?r~-a}{q*RSR8 zjMGe69Lw!hf9*wY+Me;3M@fSOJu#6ro^hYY&+h($?==k)Zm;@hUU%vC4G%wD8YJk6 ziL7zM9iBQn?73gEF_DDZtNz75bJ_M!pZb+qnO{PJo|woQ&%EThvyVOIV$&euc3K1C zo0o6@ku~0P`U_^KJ^4M2=+gxjnB)33XH`xlS6SQ;eg ziHWRn{oBu;{rG3!Wf~;huIm9vgM_aXu|`TrNMkc-@M~+g)9!2+Uq1JIB#lbY6BAkE zf1LjO%@_ZulobiLSN$X3bj953g9JS>ku~me;|n)uyu8#o3AfXC;s>vod%Ge*PfTQu z51;;m&AGo=+AayVSN&i7$K`YHA0+6BiL8-&)Mn^|B-~#0U;DYs=HAaq&=V6`BaIB3 zVJsoxcDk><{?fURS0w0(iL8-ExXmyol5jh%54U>L+{axK^u$Egc*}1-bn|x_+ex^+ z>Ywu7H_ZL~L4ux`$Qn<){(CkT=p04D?N$Gb#YJ;J50aoKCbGu*{J*{GJ37~raC_B1 z?Mbhl`}v#%Ju#6r{_?07UUg8{3?$rM^?&$-7tZ~lQ#43uQ{xHJndLEPpi7%Ejdw zonOrp6Inx70H#60?Rs4z4HCLeFi%Wm4PD8Y1_`(8^_4V8=z7OIF_ATNMP?%$3AgKY z;--#?`Kr$dUALJhCbEXEEO!W}>-DZQNa*_0JTZ|qbcJjhB;2mo?b0Bj>uB@DMAp!i zzMX4HxLxl*q(MUW1Llc|tf4!WtGe_f;dZ@`k_HLg*O(_JvWD)wOoN2mb&V})kkI{^ zd14}K_-{GWbFpn|KMOtmGW(S$9=Awu;LP^;^cB!d?}tFxeELNpx`6o6qb^!}`cW6n zv&Qqze&gbUe}ARfuQ>6kS;OoOzvax&ed~pvYuAg{J?%Z)6qx?EPNe@zKJ=DM`LK6W zL#pPxM9znvCk{EcDCImL{JrCP;cqS1i~sbj_oV19Am}0C?^Vb7Ai*eq+dC%marK;9 zDJdmd=w*;9dWv2lvWA}Ak4l&7{%-qFb56qFzK`?4oHL3kOr>0Z%Nac+vYy^@jPgN( zQPVm1HxmhlIZc z8f(zw@1us&jq*Va68^?)tU-cN{vK~k(Bp3u4>eUJ{GI1mgQ;Rv`TKtDiiE$rjWx=# z7{xZ-wi33uT)LW(X(3C~B6E#W7ff{k=^UJtX`&>|Pqm(~e%N!Q+z9HDiz} z5{%N{gR=5fVb=?+NV~u_>Zk@;A3UyK$&PbQPe26uAi;c0r;46{2sB8@wkVcJTOTYR zTNU`X9+p@3-=nOkK|)7L_YdQ;BEcx7YO_n|%6pzYx*|8bT!lv?wVo|ll%4^YUFs$x z=pmuId!sx2mNR;Ee|{@8Na)Tx&|s<hK$`kV}grfj1DN(TB%k6x%c;(p5O` zO#P|zUU#V_ALag)gg+OLb6yBW`P2F_ajn1gUMR{&A8A|NwE3Wig!Fi7jXJ1cc?OO%(~|V>(sz1Vo@gLbgS*MA}rbd~DZ+*PUVKC?2UL=pmsaow9qz zA;Bo6DkxoEdHEB_dabqH)zBDj9uoeHblk2;FiIoFq{h}fB>Y+LSc4va>OAD59I3;v zj&P$eHJDyT`P2F_;qN@w3xCHljBrt^N((O@68;uwtU-cN{%&eaFundZ<50_r zguibYYp|>s#nhrYQa`7M1l}Qy#u5^YVyU+p^W%>>c*#TlYMxv5%P+jKAD*Nh|B0gx zzWranV}EZ6dPrROmLm^-|JUx6QZ&vvJtRK+q+9y0TyXz@pohe1w|u_;qfdS~NEHc2 z{pth1+CS-#HTazmg&f>B>N>~sCOH_rkMdPto8@Q?Q=%^njF^pJSv zvp(9t?ulOtQbmGM7u@6O{!`z0Y@k68iPLVmrti8h2O1<8b>Q|__GjGV(SZg%B<}i} z0~7fm!KjBm<+A>{2Tl$&=ppgBbKf;lgCrRBw`X0{Kl*n6Inbbo#A&x&KG70MFzRu? ze?kBB`F#TodPsclS#PZUvBPgUBf+R2{>Jb0i-Y;QxN#r6{FcKG{_&;1e_8hY$IA~p zc+I^F}+_?!>FIw0sF@mpX2PTzIs z>_ae$<5-8^az+n{4}AUW{qPP6KpJ;RFp48lOUSd$r7Oa09m(vLpofG~xDUZ7m0>{8 zLqa9J579)GRuT|uCFUWa786`2l4znnb(e!j9{!w&fQJOzbcbKs>jy*=RsJ4a^@%V~ zLrnG$^}*Cm*9-MQD+Tp``#Tbq+7&${)aQ+!CK#o0EYP5bgvPEwg9M{A9tRrqkkA+$ zXpmr(&MSciJtTB42{cGBO6SKwgB}t(Ck7fM7^U-kpg|7_o!bKq5{%N-N1#Cu30>6$ z8XSFeJ!erI$2$C$GkQqq+Ac^H2}Vt)iXIZWwhJ^!Fp4FDY@|MT-47j?j#KU?v{r-V zJg-@l-rbws5?aB^JX&eW?6?2(`F%Qz2ICbyB(#Q9ppm1}8+Y>*y`|Y4B|7|;GkQp9 zRW_pmq@0sr)MsvYQ9cg_1U)3Q#@apvqaO5KuSunTPC(E@LTjw;Lon*ni(lEN>ym(= zhlEyT+lOEjYqrC0IirV!)>sQPNHB`+4HBsawLX{~OY3-4+)K3fd&aiu{XD=dh1IsSPV}fIBW79-4%=YsoIUlA9L#P zbnqjeIO^2liQwn|;Kn-Vvelr6#3`2^d20N0kOZUN(f!jzsu*?hFW#~ko*_;X^pNNu z^wmZDbdUt2?)j4I7xB|UdPqF}HlJI>PX|db>WgQ7bP+%6qld(`Cw+VoKTjmVsCRT9 zTEx%#=ppeh_q=)$KTjmVsAs?Sz(hXiA#wMkuUy2>6G<>?{`_}M)CWBz&ij?i7V+~$ z5{#PeAM}uT;5ip9;^&DZ7{$KX_NaGs=P$}W=j+AozIgs(cyh-XP%S|ZiSCkDF5)M5 zBp6lxUfy{}8uH+{zkk$gQoD+t-0@h9;#}@lLu1r7UzaG#Y#qt$mY|1(^!6bbRgM&0 zQ`1929dn0u6dd zXmkxUNH9vHU7$e^35~9S1_?%Kd<-<`A)(PV&>+Dmjk|#cJtR0Pb@(l3BpCJTZ~o3A zy_E?xe!e^W)Q^7k#<%9)dBu5$ojN>EddHP_J~h3S3GzV?i4%UPJ2ig#L4r|dJnz_3 z(_5K9gB}te`^I+`@lzZUjN;gZqDuD$^pH62n_tgg_5`US!6=Sht%f}FT)HC6){)F^ z33^Bf^E9PZ#g5u zDE&P+57I+|Z5k4(UGc4q-iBJg(>>gF_dG}siMQN*b|SyL55Xwikp%=jyF{cxqSz(s z-A}zS9e*2W(6dWK8YGHcqBx7B!>^r@vP(o7JXWzw6lcRgBGn*0yF{cxqSz%$-<||z zMb9n~X^<#(iQ*M!n-6++iAaM)u}c)sC9MWMB%XBGIccPhG)ORN`W(eO6Gf$Cx8Gfc zshZ~~64JB3PZNw%i39{ayF@gHg@nq=j;optH0aqSA`KF%b33kDXrMvQE)i*vP}{ZR zs;31S^z0Im1_|{+JFZ5IK!cuLBGMqCvBZw6kuT7oXP1aHNN7y7F+G zYTMrdr16T!V$}3p9DT{S&HY2)M4GLdHM`ZIhlIYn4G4W9YaV@TYj!zObYDvk34Jph zXpmr3PGS1uFd&#-eIbifMQ1hUoP@r$4KzqFimC1J8_qbTOi1Vp;7N@_Fp8xPiPTE? zCA_{9wc~2U2sG#+p)XGNAsEFHX;VcH34I3}XpmqO+jOhJ){vvp*MN51L#q!GSx@^C zrZbTL+8Sh3DZ{9>(?cScg7zgGX^>!)zR0#bd7AP(eSIft9-V#6)|a6HK@SOi4H^*o zTGBlF?$Yc+M>(g5MA4oH8YCE{?~((8IoJ2KNYyqVm|GJ1ws#+bQS3Jze#;p>B=nVW zph1FB`t~^>SSI>H)}mO3NK|Si^pMcEwt)r-MzIVdjZ*F;^ab#wMj;qA-4eB~fgMX< z$ePW5)250Z68hFQNEHc2u|!%8dPwLC;6Q@}quA40jkn!=O#jXsPPA`V9{Pwe^+p80OO(!_g_2xHo?6! zJtUUb+`dmsiv$EUm?zS0&glt=Am=1xTNK}5w;J@2n0~8If>G1&=vfEN{r4XjdN|b~&jGiVKr4$B)+OB!- zc-ptNkG{(Rv&$9veyyFQAbPXgKjlf>(WdJDj^( z4d#$h?2j!$4~ZAN?F)Ha32Kl8qo(^g$0$Y3a!Kn*^WBz64+-fR9p=N1#i&DTS0q#l zfd-GoDE9w0Re7(z;chGM4LIDBvkY58yDe^WnP^u;vkMVjw{u>o_DeN_qjsx74~e`Z zUwr39f>G1?poc`>SunnXB*7?_VVe(@XxZIyjV}v z28&*)HSN_I5ZckvJlc8DY|{j$UiFw9Rfc)F;fNK4`Xj zT0qc4Lj8Xqf>E5A+u^sIaqh8d&5o;@ozy6^kVvTh_aPWHT~_pvP^%0yNH9u$B_QZg z%djXOsl%`KD2pPYHfDbZ;C;|MjAH9)3AR3sI7XLLMOXUtkkHs=bgMyvQ6*LLfZ(+= zX|~W-gB}vO)Z^8~NHB{1rqy72bLkE%?oqEL=pm77b67ELnqU-D*b*Ay=6Ph`xKgxB zziA12c8TdaFUMk@%JoX5LC-D`X^`M`5Z9Ax^Fa@Za6OrXE@x`5+gw&WTPlV2_f~_R zT_QTGktlYFQVIhNdUlCOgG8}Q6j#7)^Fa@Z>Gd*>c*`-1;oj+qhuvW@+zIjdT&r=- z7Y@#c``4S!xq3d_*Xk`m`v2qm!AsA&?P9o>)p0HANrxS=818pl4SGnt@1$;#?pT6r z>TkX7)AQk8=E}oAIUk^$smnBvi9Tw;DVaquBCWg8kr2fBJ>_@H~-6Y6*Hs{Q2Q|4#0MwR56PE zrq!T_#PYv>tEO<8VAS;J!;w=XsRpxU_>dme07$z@mpFx zv{R_^apBxG@-_9C&>Ly<_`2RJttt;<+1YQo(Tp7^9nj2$LzB>L2=Z`Uw zXK$2M-dDp+Cul^e;&C;b21LF$7;7-SBs7OSYCA(7e@2}ZHhjaU|LxzQ|?c`g(0!K;Plv)JD)c4_}j8uXB08J5_HV3g+N z%y;X99ujP0tp?kx`idP_{UgwzhlJ)Z?L#n%rQW8B9um0>%iaTVODwH{QS1e+25V6B zh%D`_o0g!5gl1nDJxwr5GcE!`^CZlp84zas2tLj^JtQ<|BGAx067y)*6Evb8RWyo+ zgytFr8dTRzCunp5!F-U=tfzelMrj^UK+vQ4KDQ!OBz!ggz3XGxAAUHi?N_=yuIBy( z`Cxr8iZ$Eex7@I%G{*}$-!D}pavO{LAXCLCju=Q(8WZUuk$XYe|6^RbBpAhWaI4|Z zzgG)gqgc-UIpbJ^9uocpa!lyD#E$FF{Zc-_&yxp@sLq)W68qi&e@=a<8YKJ~`B;Okgi&mvZ4LU{o)y-tY0Ir8 zN{=cf>TjA>3tul|oGKEG^3^s(EQ``|<14AG7QS-JYT+}|#v1gH@Ks~>A{gZ>(~JqG zih90^%b1{tgs%a!7r`iB#br#;L&8^$*^6M5ulq74=po^&#_UBf%GZ+_6ZDYq??Uz> z809O|j0vB)SlVmZuV!fNQ9tMT!{N34h1Z622$FUIe3j2Zk}h z^op3}I$-|FxKsYS+|Wbf+PZ(kSc3$ke7^t@%R$4}&0h`s8>DB`tA(%lKPG(D{nf(P z><1@K}uU-CV{5J-)BZ z@PwtDyQWh`!uPZpYcN%e^1X7#gzwriw7!xO-=}3v&{Nu2A$)I^F+mOASEki#bI#+E z@I7s$u`JxsKT1j%#a<9;bo1Q8N%-64aXxq~MsXx+HCXPxGt8mZISJomW}GV4IipyH zZK~)Y;XB`qHApaOy3T!{u+^|znvHPmU2Up-=Zn?CciI@rs@v|KqjW6uknmkT#`z$@ zDBqoJO!$smtA+39RqgZ^U`+TPZmWgw&Q|j=-z8WkB$OvBx3;WEFp48lOE8DNb6QQ6 zm0?S;tVsBtXycrdU=&juYRq$)kYGvgOIZ1^y|skzcb1;--msddU3=`T=DV7W^Fa>@ z-}`J#Fzvo`+G^O5EvP}ZD-zQhBp4+-(4dC|^JHbUEG4$w@QOvF+9ubHM!xNC+ogwu z#z!Zr1_?%KjB%nXzdE*?hlI~<8P^BL61Ga;H)l-HL!#JtkFy+7wM&#J-(5!@Oj&?pk=`4!8AgztPa&Ibub`R+Pn!gsh?Eqt$>VPuF>#WEq`y9A9jNHA);te9Tk z;pR}wiiGc#GfoxDicw6hs>1%M*NNNQ4@me9K4T3Yi%~4~R>S8&t``1X(O&n1{%zN4 z;a`UBMeu%*gn!|vd@M`a()%b|TfJN@F-m{85^3|nDF1%2rYazKEE4|h;<$84FiLr{ zv8zoLOVq#fs;Qdqj&RI53IE1yB2{)QMzNkORZIJC>gRmc$LD3#F0lha4+;MwX0KE+ zitWvgz8o}Iib}hcC`-M>4g@_UR0=_TkYJQb+KHMfdQ_XYB2^@mbJtL2YHQ!-*1#y0 zwEbPd_RlbLpxYt*YsYbY@K}uUubsw(f9JJY_&0IGm{_#iRQVTYD}3QriTQ48FJofq z=l)IHYT;kkjZ;N}QU3klm|)udYrvW+E5kM)(l8GR|0Zs%L4r~KMctU7hvmj2O{Xd# z=98ss`Cz&6DOIaMPe9CeHAwJT51*s78uSE2pg}^mMezwztHIWw`Zt1kY6*Hs_*bpt z8YICe|B7x*__ubeg@36Ry#H91wAFq-&*e_Sza<=NaCBxA$KW>SI_@TG_?MH1+CND6 zx1HlusjRkHgHaq~+Ei(tj1j!5(F_>-drQzmLNj0jLNj)tQAV|Lqj0>|h<02sFA)y%;0l|D|-jYQzg&lswm1Rjg315LoHMlHTOE8Kh4T*G>K@SN% zFWv5rB_tTNQ-d{CY$ci-W5?x@rc*^ivuyTB6{Ga-J|O5Jp}9Z%5RA%gq3k6z?on)4 zS)+W5I^0KM@y0vR&g&j+CG|bjqia?{Z>I==ISr2Bj3_JYl zEQ=jN^C#@@0DNACc^EaFDtbt0R!5*gf>A7yHdQPi%|f!{@<=T~4++ha*(X(u(kz>R zpvTwu8Rq*$?W&}zcu3?Ul`o6OZI=Y2G@mI*6+N08Wl=m*hu?BT4++i13N%PCD%W87 z_I;d>T+c(l%dMn*b6#gq1{xgCNoWS06U)wiLu)Uk%c$wILCHt{eqpun^(sI`$FtRFv@qX7!&l6 z@ZBo*A{ga6aEu9hNcgTBdl8KCokYe2JtTbhki7^-`Hm=Kf*umS3(8&uquA5hmPii? z-_2#LL4r~2kF5qg~Agl3>(ys(kS;<5sdO3+Q$SvBz#Bsy$DA64((%t9umGI z{9Xj3*h0sxWY`mawIJa;!jCn0EJm>%w;J=~k2zR&WLqt?53jXK?Y3)nOVC3?JM5+} z&&H`D!6^2ER)ZcA+LJfXAi*g1l~#kP@?F_i3zkSr&_lv^fmhC#gn(WkMrR>rmq%FRNZ@h zLc^X}lJGs<_ad68x*z=x0S^h^n|?2XQL3lyZvUW%gzA4Ef>CO3PShG?l-jOE?GRo0 z)wXL>Oz5T)RW~J}uH%cJ^CtNHEHGvmd95 z9ugW+`&xrlg9M{|H~X;$JtQ>F2O1<8<-6IBHRvIs^Hrchf>FMk{aAw@5<2e&8YCFy zyV*;lmM%Rcbp7BOrONZOzGr>3Pdi?2b4@YIce5YogHgKnvExn?^pNnq;>Q{!7^QQU zrB+$6f0i41Nci6LV+|6FVt;Hk=pmu=Zcw@;7&YC`^}NJ#s5?E_TeI6#>8=q`-RaxkOKkb? zazhUZ-^p;?2T3r>cNQGCM0!a0PKIL*5{&Yl1;+$EBzz~sajHl#%6AqVYtTc&cQPDn zkYJSWEI8JnhlKBBIMyJ+DBoFdOwdEZcQV|IV3eK*1?`F+5_%dLj3p!(rDvo8;rsTj z7QRbqeNG*uO3!!AL&EnT9oGj5M)?k+yJcm&OPdA>-?4Nrf>G>`9e&FVQ{_7r)~EHR z4IrHdSym)`hs1HJNHEHGWE>Opkno)z_aYeOyYP((dPw+=m3tA4@*M!j1U)2tpTNBc zM(Id?AEioJZs;N5`yEbb*s&Pp`zwwKdPw-bje8M{@|`8e1U)2t|H-`wM)6Hk*mmdn z8jghTqdC^#u^7eoJFN!abCxTP@{WyHA1y%-39j`sO)$#$dLHM4V;`@aI99eA^pId` zrwK;+F4yB!(L-VwgheT}_B^P>4uo=UQToPxA3|S~ zTa>=^Hd|koo895J+~`|v^XMCHv-$i1K&lUVNa$N+qg#S&km;Lhi`pqGVePD968eTa z(BQEcHC?*&kWh;WG)ORt^`tD=Kg$hkP3s!iae1Vcpoc^*>9RV$#*$^>mKzd`nyzzt zNNBwSOJSQT5{zPdYYDbKMzOuM1U)3QdO?sX5{zQ2G>v6ZT5i}z^&Pz(mu&yQ$>%~MX}>*y_7(M1f#SjOF+=0bzdxsN9ypabDb@Ugw~d^ zzXM34D38UcQif5^=^>#nVgd~kjM7R<0Z~#_+NjnLvM8o@Iv*r_CGhdJ50AwtwuM%M z&)eA_Oa7v@Ch6HFru$$yR-sE2OQcN|JtU@EI|)W0Ipr`bx<*i5+39U^PXfRcbVjJu5TW&blk+U0ltqs7hUQL}ud8*pk z-=_&i9oiK#3EA^{ohYHqU1A-nBnse#IvWP4I(H3OS-w#yUY zQa;R6Ir^YM4+&o(csw$YV3e<0JSKdt`_-@-yFGJYDYU8Lv3xbFK$gNT|c zdVFo|LroP4U!{AmR56M@xRlaRRxCxel6`tDYmkImsMm*t>fG~ru0cj|#As9HEAX!t zzD|EFD?3t4s6Na?!dLtsmzD2Iuv++T1&69Z!gog)*Ev(gD7Kz3AKP43B&25}(KNv* zo>y9eW#W4%9BR%<`2G#!(q+yW#Zqrm<+~E3IYo6(gF3>^bBVMBTOtXy_I+9+qnO%O zgB}vQN*N^~l*uz@6_ssGB%2!ZHyX^4R*dxFo_nn|GL#~vROZc%-jwcF;iD*<_xK&> zah}KbTI;<2_wE1rG>-1$_+GzrzqvN&D$i?s_sHlWQC4avBN!FWggd264~bX}o)WR~ zsB)#=8^84My2U<(*r+u`l-rS7w`ceppGHC=^iGK=`;Vg0TZ_`e>lXXeh!VxGXps$D zA=AU_j=#MBe_py+U;ou-uEpkk{8jye$8*c41GCu_!Kk$Ln@A7%%pKN`|D$hl4SLc( z82BW1nqXAg(s&wI8LmN3+6M#QJD4UIm9{jV z^X$i-^=Us!IwC$_! z>-@uT-WTVg0b-U>t5H-E(s;mKuQ+n2gD1EKJ!#u7V%+6Z!?!-{-k||vmQkxwR1(s- z;>Z5;$X&kkQLaHx+6M!l*N=!iPrCK|hp+h#*PtiugMn`mjEGrAtwvEv zNaG$izu)|!@A-PypeOC|`x7H#mQkzGTNe5Lgf#AT-uKNfdh3l{gPyc^-%bEA%cxcT z;?PI9dqJ+}2LBB|T{$415P+M9ea3HHu0?8c%=tQ|3os|5DeWCvE$x z@hvy~=DVD6FHhl!m}S&z6qSTD9&(fO=Qn!Ntz3hiv=0WpgD@gy8MPWkB_R#{?x6mw zKYG$`8WvYpWQP(S6|~vN#}R0_C!<S#60H)mpm~(F@$3CK#2rG@_ro20dxFvBaWP z=Tk)Vd5=n48ZlnE20dxFF)=izh#0#(Ds5@Rxa%79q}|5$(3m1(4ECtBr4h4%YtWN+ zo1;Qwiio+yqtcc}%xbPdPugv+4UH)x=0uN5TN*Jty9PaJw>3j(Oc61+dsN!eh;@l; z(35ss`-H|65i1#wN?RJSzH$wE(r#CKpBX$$6K~LJ_(*&l8*uD6u zmbNs?Uzv6Ig=E^R`rBttkBN95<(@vVt3e{|`upeOU1~{H*`F0ppV-wPk@hOiFzspV z@0}GzVpoGi+V$5qdm80lM)CBCT@4axuj1FhdK%>}PVw}KT@4axui_W-dK%@KQ1SGM zT@4axw|#V{U1b}s@25$R1T@w&`^)`#>k}Ihp=Wm9@me}TPtqiIHAtl0>Z79(<>Q_{ zv8zEM?bfb38d1;g=@YveB+_oJy`vHB)jfS;SA#^_t)F)^qNlp2PwZ-tNV| z+CTBkXC3+Y*+1tRB+|C;YoGq6;Vr-XVJi`7kf5heNaIOA@;67`b)Cn$28pzF0?p;a z%l_uQp+SP4J|T^d{nbt8pMKN#Mp@;xl5S_cga(Ox8&{=UX%f=-^mXq&*Z-+1Nu+%+ zYZC}q+hk@mrm@9(+>2zvU2G*lNVVQG*^+oCT1wc!bOxx=Q^ISG3D zgf!Hq)Ka8DBJK8u@w#Y`$ajG)hb<)}q@li{J|YPcX{%j5e|Yu>p8lGmL4uw>0gWq7 zVo4(HmMW_=)kkPJ5!ZE3pFmk1lLm>jEvl5lVpLX6(9KV8Xpo?%Pq>EVK`E04iM08RQOtvl$ghu9NC^pPs4i5((jbxc z!I0ldNrMDEeL@;)Q)(&FAd&XLkl%bsg9JT&LK^BD)~ht*%t)kdCv(rP{mp;zsZYGR z%~6e@r%yn`=UNhJw|rQg#XKktC*r#9=@TfcBglsnNw@mgw0Tga>qL}~d-{Ylq6YVf zq+2Tq4H8k$?&%ZKQ2*16Fta}rX}A6n8YH5HyQfdMM(KmDK_czeYpVu`=y&ev6Viy0 z!8J&v-NviXAQ9t-d-{YlVuW)I5^1+lG&D%WIOv`}A&nTRU4um0ZT<)i5-|g~r%y;j z{ZA{unf;MSyUl~4K_ccQ_w)&A{OwB@^V45_rfcv{TG|H#Pcxe)7?rkq?YDjA4)e$T z(YLq;J!y|mWt%2=f>qkmc;54_H=jTD;jTeX+6M#A!kQ)+m9{j_yVKQ2{{99()y=&ka^rU?-@T9S6f>CKp<9B~%dzQUx;2QL#ZKuC~_0`)C z{`tv7ZJdeYuKyKRbC;LN+UrSY8WKW6>9OOE?|PEXqQ{QRjmx$0-$`=UkZA5#RQ z(w2rjsb1T=2ChL*+SczzXSYoeqo_tmfBkPyyp?NYlzCc|Y2bvmLkLDSTN<`4 zU+cgAM^CexhQ(aSR&8)1q2gZHh+Ze4oHMZcz$GNFz$O5G|^em0vgN zCN!o9Mx`x{XeF*ePui{RhQ<^TEzzUWmPWL8E1%hnp0ryZ42>xwdXz_{Esf~su0c=Q zZ7kWA`j{eOWbml8r4i$mYtWN+8xuogiii=;qtcc}jH0eVPugv44~;1zMrw~rTN*JN zxCT9Gw>c^_rihqvJSuHz#60L4^rYS9+R&IHV&?Ryw51WVvun_kc3U%q#uO1N0FO%B z>!Ykoq_LzY?Y8y_jaZj>sxoR-S4bWes~WSV5$h}0peOCNh6@c4vy58RvsgVUR%f9R z>qOU}C+)Tt4Gj>pj9S$dt4GBuGc;no>l*Z=-PY8h0b-U>t9l-?N5yJ6G-BQE8uX;y z_6DH=VwO>>x`XhjSoMcS>_1$Cp0p2ko_T?oWz_h|SUw9=oxc{(yz<<^)sVJ*q0r6> z+$HGg6Pnfj)9x7jb3F4Rk#;-R*+x`pkjOIu?Wt}{2?=RD!k(}ESv>P1k@kV*>Hpp4 zGcOYK^a*Kv((W;wh-Y3T(mojSb*| zibUE6L!L;he2}20Pe>!4F8N(G5^3`+UTKiXGj~@=2?=QEe&Uiu+ASaR(mz7OiAafi z`UJ{K>#HS+v|H&eibj-`6Hz|y=@Zh38r&n2ZtW^GNJPtUPoI!Rv_u~hNu=HSM`)0U z_UfKKA&ux!u0bO0*3UzOMD#oN^a*Li$lw|z(r)8bXpo5U!##aM8ZpAT28p!WC>k0h zVjOf&pO8k3)UH7y?KXde28kHY-P0$e5p$GlkVso)_0FxmqY)Y;=;;%o(Vk$DNc&*O zQ}fl&O`{R?^a*Kv#GXr>h-Y3T(mojC4CBZL33~d3G=9OJue>9kd67t4WmQkjS3XG4 z(X0`FQ3xFYoRQ(4J|T_kUGLuO563ev5@{a{aVAe_kf5heczswN zz7)^ANThu*#Mwf%K0wgZC#3P$Ru}h)XI>=Iwr_?n`n9dS`w=;;&Eu#tLg^PumY zNu+%+#K}$bHnul{o<1QBn{nC`ED~v}UDb2SVjgS+J$(WiKG%{+yXC{i0%$l9*L6>y zKv^A`*&m6tTYYRsW#vSak9+!rG@=Igh@@M)3Jnrb&+h3H()dVeiB_Mp8Hu!8{|F5d z(O%utC!`TQ$~8!&-THZGkcfWgo<1Rs7#UoHMA~h<3Jnr5ez>PkNFzo#*C3I08+Sv4 zM2v&(=@VWbWo&m15^1;jBQ#=ccOu4f_w)&A#Ei2?B;Dr0&>#`>l6(4uG%hXs!S&4k z_}h7DuLl0|>X@LXPpH@G337e+gGAc)zUU`z(S9dzOwiLOr11vZd%QK~K@w@N2L8I| zn4qUmNMmDrsMD_~?|zU-do}R)K*t0<$tDZg~jg^fhx4NRdPfa52GG65w zjU+UFR8OCf#&c{;e0$s@BawC)ck@(75*i1qr%y;D#&$0&5^0zDBY&-#gvRsg=@Zh3 zIm$Iiq^&;qwHA3{v?~(y^a*L4i}y=Nq`ew+=2=bcn4qUmL|N&LM$ZR{v{!@9TdSo$ zezS(2J|PXO!DF?~Nu;f^x?^iSV}hPOAq}p`NTj_Q#=q}Of}TDh4eL>Q2hz)mMB1x? zzZ5+t=;;&Eu#sVH^Pp>xNP9K#_oT-JJ$*tN$81e z+Dg4@W`88oUJX3geN52PC!}$S?Fa91ewm|4q^)*!cZ;m^APIW=5+ND0~X|b)WoKX2xPoI#6)}gDo2S6h2+O8HcUXdvETs(b3 z8qs#ws&f))m;Uj>Ywi;oB-CE3r%y;D`k-r&NW1j&{1tE#>UY)CC%isv9r{V@hspgf~Gu)V>tx;G$^b{Ti;@05=Tjf2(GC#0cusQRJuK_cxkfBe&D zZ?h@uL=qa$tEW#$BjzaAAdz;R2df5&GA|WRpOD78Z9jOC^(y5fPGXuXy=kw88$bB7 zn+M$NO8@sUK~JBM#+z)c`c#w^iL|Y(?ls%K<8fDn1_^rlgfyOEV{W}KN+RvmaOoGX zv;FYduMQ0o^z;d7Tw`;`e?{9Rk@jl%*T;Ru_M)4?U-GOnN0CT-HN57Fr*Gf*;d|LPang7J2zvSiH2f|niL_fjY*vDX6LDSl^a+%e zmBVaCBJEZm*7i_VPDJ^*r%!l3N}cZ!Nw;zL;#~P4k#_4Jp+O?r zt9$x{G@?hj28py=KMxHO(eK>TC!`T0gKLmTyNy?&K_bQv_w)&A#0cjaB+_owPoI!R%u%jEBJEY3uR?d_ngRVg$?bW~& z3_Vqipr=nrTe(Ewv(WzPe|jXwnqHOvg`**q`exx;|uG}zdZcAV;&?y zPoIFsl^WYgq}}piGlu4<&~PHI>z+P=va)ipaw}!xMB1%BtnEo7%F2l-ANTYLX+#a~ z5lOdp6&fU>p54wfm{hY^fQTRrN$^?CDuIB||^(3AGccHjq_uY2H8i;>0@!Kk#Q@yidoV1CB+U*aod zdeUAE-~NS*H_v{_BjPNJDS}aHL&HZOdeUzBu(80)s-$Xa@S3}f)XhbX7BN&yoG|FH3UgqQPe(q*AyUjx5>qFl6T>IZ* z=fA70%HJ-r8WBlHOI%yq^;G@+TVJ!VwrlA<7}8!1r=9nzg|*$xN0(q!+RDfC*XONY z`7h_V20dxpGp`RHEUfKXj8Zj4Fe+`Yj|W|_wzli7gr2ll_NxL1i!-104cT_P1f$Z1 zhW8J8(r)=U(%P;x_J~N8N2QIjGLL;jQOd;ZgIYdLM7hmJWwl2zDs9ilRX?p7bb_9= zSGE2_!`g0_h*siJX-lL0m6P$Jjc%0QXnk(yzfTjbweQd(V#i|bayH{R{b{cTp2j~W z=;;$`iSZ=PHAtkr8pfymlc1+hNW*5%b{~#J+G@Lhv*_Q4qo+?u!&U(8J{*a(R|9_| zVocD}C!}$@?L9sa?l4zj zk$P?Oplgswdo}t+zAV^+|wtd5jD6+B;DFoXpo3{c2A#>2Jfno zNW1lq&>#`*)jfSe8oaAUBJI}CLxV*0JNNVnX~bBvR(+62yNy?&K_bQv_w)&A#F*$B zB+_o#`xxqJGAGc?bX0vvmX=m^ob~|BlR5?5^1jn{+fMTWvtao=;;&E_>}DjFSoIGmq>aw z=vT+bJ$*tN+IiJC0ZF928gB68cek=S zC(4QhJ$<5T)OR3Bq+Rk+-^MSgs)VjvJ$(XYWwYgMMk4J}AN6hgR#r}^e5$8UNWf88ZLgPpE^a*La$Hv4r#WQ*mX_s*~-wP+9 zaj<&&gfzIjBawEQKl1%{5*p8|r%y;D<|wZZ5^3B0_89H@S%eoi9o)$skdze(%OV}hPOA&nQ= zT>d2MhteRC_Ggf~G_!g`4M?b2(lS(4(+O8H+RwPP2 z7f+v%MzqAWHQgDBv`hcUbs`D1*XrpL(uh9j8YI##{XEyZB-HP!r%y=ZaWe(=JD#=e-<%x?3!|NEGT`SlPY%4)P9v=x98 zNw;-LXvCVqa~|u2LkMZaN@kBpx~;E5gG8)%+|wtd5o(4_7X>fN(BJH+r4-FErj&@I>vk#@U(6&fTo ze%L(do<1RsxJTw1B+_p8;X;Fi#zC70-P0$e!QCB+wA=l}&>*21z~({s^a*KjcSj=a zHV=jdiI@l7(cSY>z(#yY`0eL@UVYZ+9#wD_m;? z^a*LiNbMRV(r)(?LxY6I^SUeQ6Vl-BjzrpZ9xQvfF_AmEgL-GvQbIx+`{#I-YsG0K zPQ>Xakq;8|^ob~|wjU&sb~{fd%c>D^zKeVMgf!v=8m|u$X}5E6LW4w{Q{$dKA&odm z$2CZ#ZR^Bxice^epr=nrQ6ViwintV(ok#;*bDl|yMIZp2B6VlL`IO%ripQsvkR+!JVB+@SVsJp&)R+tmIZuRsDl+_U{su_v2OMTQ` zUn^ZFR6fQWl@AhWw{z}7gM`{^-QD#G zX+)254H9XWeqPt8V?zC|disPk;!Hr-Adz-EcQEonLgPo<4>mm#(s+YCAJmRpWkn+G zc79@LkkB|-_k(>x8rJ_bQo9C;wA(q5p+Q39dEFKD32E?DE)r?C^Gia5M4VsZo<1Rs z{d2r-<3!SS_oJM)5*j4v=@U^_Z9hmN?RK6_XvCVqOE=DUaZjI+hSi|Xtl1-yZs+2J z28lSQ#yx#P8gY`2Ymi90o$nJGB;vds_w)&AXbx0AoY^0VwA(pFp+O?f4RTMPkcN#6 zqjS9K$dGh9Zz(iL#Q8_==@Zhhy3mb#yPX>q8YJQzC-?LTuMc}Zs9rU*KN4xT z^RGffZ);T|&ZBZqpO6N3cO=qQyYh3qLW2Z7eWGgA-5rUv+j(TrsD!Rt_k(=`Wp!+3 zeaK50X#A+2J|T@b+t4*g zq}|R>jC_#LI9T_CeL@;BQo9C;w9EWacYR|*<9YS;32E?DE)r?id9dyWN#y?Qz-O|e zM?xCME_vNqPrhaOHax$hwclZF-`cK*JKf>J%?EFJMwAr^disPkPCxB}Bk%b{IrEG} z+IBv}Ltec3=;Oa8G)U0XC!}%z7yS8=YyR{nygo>zZQsh=|K*$SIsF!)L4uw>A&u)^ z^Of_fZ}||{Ad$A+Z-3(}HZQpKO+teNJ$*tN*Z$eBpZ}kq(09i6rYx?N_G)OBG&Fdfi$$5DfhXg%+LK=^~_{sD4pM8;QkVxCkfcTHgHvjzDYeItrJ$*tN zZ+^)6^9P^vRjxrIZTqG9qnB^qapgNhg9JT&LK-*z#0B%$ymI|bR^>AiXwb4^z;d7-0Tw$<5^1l7 zw|)MyMfML8^z;d7SdUuQK1d?%)$r+uzIKuQoCH06LK-$Qtm{}pB5m8(UUTUp$14)_ z^a*L$2)C|dB8jx^e7J*47CG*cpr=nr<9D9=_3OWkv7JQPtKmof@D+=kKS9bUf3d5{D>eL@W z;K?Rww{dq}G)TnA>7G6zjTot2gGAbG{s;{cF`m1pPe>zXoTHdOoJhLOgP}p<<7I|C zgpfweoIZb$NW0DFp+O?%SNHS@X~YV^HAtl0)+M1qBGw7+=@Zh3m5ghUNV~1CHlwwV z6S3ZLPoI!RtjOl74-#p&bz*3ch;^HL`h+xMW$79u(r)YB&>#`(Pxtf*X~YWIHAtl0 z*6pD|BG%FF=@Zh3mA-3`NW1MnLW4x?2i(&qq!Bw7*C3I0+ed{4iP+b;r%y;Dc3!SQ zB5mt~W#1MWB#`xxqJGA zG-Aea4H9X$c`!6c#JuF5J|T^mIbDN9+HF1$4H7ZGx~ES_BUS*eK_cz8E(r}1u}*ML zpO8kZWL$$p+HHLm8YE)9-Nwf5$kC8^a*LiO5f*N5^1;nM`)0U{eXM=gfwEua%^UQ zB+_pCsL&u0`x^K332DU6%QZ-(-Oktw4HB_Gb5Ea;#-HJA!#ug;_?9PyqaO}ir|SSX-nhrb~pHsZmWG}isHI4Qp0s%il*(#~;0aA>OGBr4s>Mr# zp0w4jHjD52+HZ~%{-y{#*MOe1TRx7Iwi_CIM5M~2(neXCr{%-!VuFO8Z&8XHtLSu@E*6vYhy9S<& z(vx=U=T&2Zh+gYaX-gwU2J_5j^rYR!tI(JtV)XH-w51UvoNLgNb{ls?V~U7T)T7dt zMvT<1K~LK4G^@~dY=D%Z%Uc!4qiGmWIu0dP~nW=tDs9)WJSb)AgY=}m8vgg6 z+`z7_UsrLB34&2+OG9;`5|#!%X|IO&|LP5ga;l>=rU*u*Ee#u~=V~d^peJpf0ws+p zf+sYkEe-Vz>s3DE(37^>)s2RmU3#aS2fGBL(uRi5we+Oj@^P%qgVNX|B2^xhHp}KW*^^XR2#2CV~U8;$D`7gMvQQ- zK~LIk+zpK>B1TbgD+Mr+)M3;t{v|%v`mZD<^5>-*Qe5i8J2%#>Jg~ z|IeJxc+2;QU{tOEcQxoC@yxegzOXwV9SstU%9ZS{20bL+`&YlS_>F&fct?W-qjE*Q zt3eNmzx~EnF8;>@{{DzcdR$f{7?nGVU4kAGI&J)Ke&uW%+Ycic71}BY1>-|*GLn6xUBm|?PEp!NaNJRaggkV(kf(}6siD<_sAs7{XvqR8BBKqS=2u8)u zqC?O#Cf>C;_rlXQ`!z`753Ze2v9suC&_m)5uYUjH&mVU4js^)vy8EqMsai<_YZpZ37tQ&n<^5;E>Sr%>=N{l_==BxVIm(S7?m^Jt_D3Me&_eD zH}va+1fz1M-qoOIOx$4Tw<{7qbghia700dyJtUTIx$$5#T&E?HU{tQ0b~WfB@tR9- zKG;0i(ICO7TmkNC&_m*>m)>fyd9b5Ff>F7W-PNFn#Cu%r#1js^)v<%)b)gB}up z^5bU=HV<~@4-$;ZoyD#OJ!9fF!_yvntIj+~;)kx4QK5Zgzt_@3BJ@r|Fe=J$zOO+K zi72;|5R8hp&>`p{5%qr(f>F_?I|Mx>q8*=vU{v(Y4nYrz=#M8M7!_kohoEOn_(-(a zuR#(q`gl}~l^qRwNW}Qq(ICO781p+C^pJ>gzN0~cQ89OQH0aqU^z{&W?NWOK5;3cJ zRLsF04SGn#ygSyINrMEV@{T7`V*Sw3Ai=1-bGxfS&zSI)Q%8eDtd=~AdpJve z`y21>NO0fQ!p&H&GbJasne!9nuIlpsHj17Y?^xDe2jSTx{MV-rBeDihY_rAe61fLF zfnDmUrYdtQqL%Ki2J^uvmdLoQa<_G2o4dPHO%;jUe;$@9MzKW3smguLiEZwqPBm2| za;JA#su;x*8K)|D5GS^|V>#7Sk;pyOVX0yiOJtm?Xs;W!>ZoV8*%rnGJ!7KocMeNc zv@6$OiHtRJRowbSKUK@ZEk}JYdQlQH?JN#Y)xRz5cj7#XB{IX`a-HkX6Wd(xo@xz} z$QAivsbUmM1c|coDpz{e2iuDER8vJF*S?3Picu^PPt~%dZMn`h)roDc;Z8MGByyE` zSgIJs5*eo|S1%{Fxmr5aRFTN_++nF=6iZ~BDvtWOE;-dyk;s+PVX0yiOJp|tb$c%H ziqW0a-9B-=&WW4SqxgjzdrsQNF|KF@Fh%58LPGg?qP>&xu6R!-qc~paUT+ zDs5@#xrCm&t7hm)yWJhO7->uqIjWJ62H$$gs5YPbb#t7T#uUM*v|R&lz0i~P@omlw zt}#I{Ds5?~E>yxQD|*sCURMKAR#QaIOC+SBH#yW&q>)i=mEqUTnOganA{dpnG}O}7 z;-x`P+Q+v!w@YJ+U{u=B@Mnf%A?XoS(&Hh!|b;9aU#laUfOPy z)gHm9w51U>=mb4!w{{g8Q$(~9k4jq_>VJAtrhL$o_VK!M3XLfuTDwQ3?HYLNg`Tuq zudNyrMD$>fN?RH+GMHyJqbKb)UM)sr$sQ4-k4L2~jTqsapeOA%iiXA%5hJQcr7evZ zsa=DfwA*YD8dF5f1|F5RG-Aea4SLe9&++Qsd5Xw=6p7F{%X(Fmm9O+HB{9GH{_Hq* zUh3zj(Is-GCJ|-T-g?QXwtDrP=S(dPE2}QSsI;YFHF(5&mFI(=w2yCdZkNUs!Kk#Q zq5h|*?lb$NC+*{P?Q1d8m?CmzK|&gQ>m{Swn%b|MYb|L^5sXUPHSpF8J!v1`=IYEf zCJ08QEe+L$N?2t@Pue!Cl@)oE)fB;~w56f9Uer>gK~LJpvA$M5riffqlaPk`hFZKd zGK%YVwX3{4JWVhvZD{yhOHbM@RmV!Zid5|pxwYVEmG>*r3yxUw0IC3^&;(w0Vya8A&Z_VI0ukD)O|Fe+_n#7ONL z^rYQpgV2~F^3DVaX~c}<8X48*55I2AaG^0pFe>fP=p5vm5sXS(8nL_ce9)8jYRGk|G^PkfrR^G6Q`3{Soxa!JDRPYof>CKp!|Fo& z!6T|cdeUAExlfSB6v3#prNJEwJ!!9o+!aY zh#GVadeUy~Dm12uXeAz%wlu8&X+LP5)~;MVqgww6jVU5pyGNz%8fACq8uX;y`gzru zAfnfLRNB&rk-;_SNxO|#n^GTBM2tQjm9{iugmVpg(q0WQK8D5=!Kk#Q5hJy0(35tX z4MJmzh;iPd(w2txzcxqFlXiXkQ+FoSKc#oKc?wtcIL}L!%OP z9yIl%qo^dJthBpx4SLdE4Y_`h2Gd zEgwhPJlJ-r8P)RPQISHkQC9Z7cx1CX~K0GQ)+H7e=4Y~$BX}5M2 z8dF5H5|2t-8d`^{S1BL#q}}>QXiO2&jy)=E*C@L?*Ptiu*3YZP1QET~qtcc}j0~

iJlf+$`55a!%a+;xO~RTt_~Rsn?PSJ^%Ny1_?$* z8LrDnO$~ZTM7brgEYxyMf>F^Hk_egQnjR8S|4B3r5{!yAokY{1heWjFB$@^ZMn!K< zqG`}WBKl(zO@joZVpK|^Y0xt!xHquyra>Y`pN;A{#>$QcJtSg$blMc4L4r{+OLR2o zAra$zM}q{T%51kujir*N*?^vXqV73M^ga=@=tgCg-_S%qUlwY)riTRgxFxnnFe<+V z+SQAI_zrDLn6jU zr&B>Q4hcr(HygVe^pKd|tC3(-%yym9rDvbeyEr?kn&(ca-50f}*iHJ^5!!R+Uwruz zp4_W(|9Kb@GpB203U`Uza~!SrDJ{3BnyTCt@t(u3hNmR*k$bgv=hjo0`L;Tr=jxvK zmQFQQx<)BRx-J4W=r0MeQDGhsbqwyQ^mVfm2OYuJn1|@9?s!`AYfs$2j8sK0 zO2WU0*sTwy%I%0^iH!4+>z$+ZnfaGdgSjG8OROu)!&8+}ERk`la%I8ioTu8_bM14q zK0oi&2g@o~WJl{${SJ|H_)$F1KGjs^D&r`gR3BDWx%O##-si_lc$^fbY!w54Gu0v)qcnvAz|quRCX z+^A;TSx8^J&i2D+zdAIg2u7tX4ZEkW_hejyp0roPCm#0|+ly}cqR^Nk7?rj(;;k3g zpeOCsaNi#}ZQDOzG^37h8I`tc;9UcH(q0X}@Xi}pY8H_X1NdNEu+$whU!8k zEP|f2SHrEJf5UD6e9??LzGYO}(ombKCx6kC_G)<0D^K5E{D@z&bZ8AXMKCIDX{e>w z6U^vITkY!fZU21HjItB65S2DG{P`d~X}5gXnnC%9RP7O==TT{+tjuG-a$U;A?Bm3US!(ug{Df}XTny9$jdBI@6x(w0WFMDw(EWp-O_r7evZ+g*d6wA*YD8dF5f1|F5RG-Aea4SLeHlex=G6dF?mqtXtIc3LPsY1`Aj z*L+MfTxxU)Mx`BP)xLtDC+*enycd3GWAk8WSXp%mMx`wctHC4ItGuk}Nn2(0fsM_B zp)o};Ds5?4OKeZ7=}Ft(9lYK9HZ~82#uUM*w51Vmy?8$8NqaTi?!NEd^v@T~sN-8k zrR^Gc*MOe1SHrJA?&?kde9??LzGYO}(okKfgw@aKNqaT?;76|7^v@T~sN-8kr7aD; z^`e#{4SLeHyEt#zY-}F1n3xB<1f$ZHhRrzbv`~7|R=Zkn`sa&g)bTB&(uRiK#hKBQ zcFV`HHV?M*MKkL7HuO9yZIqRHW;1%yZuPMqmDL^*rRz~?OC##s33}3Q?J6{;h^T*$ zN?RK7){A*syE41AL?@z!x;;%WDs9)mR}l21-THaem>{A*dQ{rdh>^iOvl%^UxA7`8 zrid7QJSuHz#0cja^rYR!-O!jKVifhLw51UvwQJCmcAGy!V~U8`z@yTZhRtf4aa@C* zwA(xw8dF5fY95t#XmodX8P(?V&``~lzvVnvFZR9C6*u12^F?#zB#r!A&gmiXZ7bU@{T*>a{gB}vMeDSTf{qsdhFe+E%yBhS6_^L;r zvF)EPN`g_jv)I+3XH1;2?Vm47;?gf>RA}2MxT`@AiO@RhI|;$4 zXbT;J9uiUiCm|RWZMs9yLn7MoNeD(o-|P_dkcj?x5`s~&v*-}?jEU=S`{zKCxb%w| z6+4TL20bJ`@%rm+`{!AbU{vfZIvVtlc=?CFu<4&KN`g^2qVBd`diDvumvIAkB?`qI9Cf>Q}w<{74{6a?Miep!U z9ui-=@aU$0z98T|>W8&gX|9nvr5Bx$# zh4zvCUP}*&&^rmis3^nvz6L!cqTEhGFe=(YhoFZ<)c;8cMn#+M5cH6Uc6<_oQPDR$ z1U)38Kc0kORE#klf}SzqBhg~N21&%|<54kIb~NZA5#wV=g9M{u%Ln6lcjs^)v z#cbEnpl6?`XQa%^-?H>te;(!6idoH5l6MMs#}ax-#JuZt5h(v%&PgyT?|ANN&_g2D z4;>8>jLJK=yBhS2312yNG)Tm1$)mW3D|s&e9q;Z)aNjl})|rwM+sye1y9Z?T6sL%e z33~R3?)jo5vIb9Vv&HB9ERk`latCo@n>&_MO%;jUQyrEn zMzKW3sfzZx(K#$p&u+6Vj0t*3M2m5HnqU-5WK86$xb+FYF14Ll7H+wwCwfs5-Sb6B zxE)a}k#hB_k?YSB+g$ISY7LHwx`scj26NqhV#^X4rz%%^C$_n=Jk?Z@$hGfbsbUmM z#8b7bWtD5H6Wd(FoocGaL|vC2ma1HfHa)v16GTf@u3k=TbG3A;sUnf_dADVnU{u=Dusig4Po`e$#OS&?UTGyWMKCIDY4AN6deT0Q znL!#;M9u~zTmx^tWE5wd*4LU(j+O1uM#uO1P#-q}f2H%sR zC+*hSLt~1FmhVw%y9VBRp(pL}Q=rxd?OL;0MsXERLK-nLI1zo@>@g9e&!X&|rwB%+ zEsYoxU4x#q+qfGVQ$&oS9+kEI8P!&=p7WfkrD0{&B^Z^qG^_^O`J(is zt+J{s0BKASj7nP?))MiaOud%YBGo=#*S=O~(wHK0twll_d`~8$xE48%)tNM=h+L78 za1FdClTlpt9pC2a%rzzmMx`wc8{yjdqV%MFyspTjtfq)u8_arOF|kkG8jLbWmN0ue%%;XHlwj*k6={V(ufhx33}4D zGvY_j?xqMvr7evZsa=DfwA*YD`IsW|&IAc*#Ejz_8P()Q;=x%Pwenf+zdn8@{m-s_tp7?rj(tOncp zqV%M#_mJy7WNAzhj7nP?T#?a}ww-^~?!!uBieOaQ(um!imlZu}uZCQ4N@I#(RNAgl zc6Y8pPui;?*VnEwK`<(9Y1jzY&KIR8?bVR`1ZhkWj7nP?)~2){Jfe0*Pui;?cSzEh zA{dpnG}JfhJV;O4YFB4$`{#>h)X`B?643Bjjh?hyK5ULrJ|b0nMCf@`+9)fZqv%Py z)rXA*D62gpO4p;(mPXW|6ZE9r+Er*w5z$IKDs5@R?#?_j+-Epi+p81NjzeRLU{u@<-_$m{jaQpeA5%n(J|2~}G-8Bv4SLeH z??2joIMw+S!Kk#Q5hJy0(35tX4I&>?M9d5xm9{jj|Ft=ap0w-xqV=qoDI(`S5}~2p zo$|5FsG~#Lt0CuLl@;gOj5<1sN+QZiyF1sQCvAHVxvfj2q0udfSw`7+qKHac8diht zd{KJRR?dCj7WDyQmQl)iMx`wcYl+$qMp@OUF_CLKqqob%Kq+xwS`$5e(OM22)ySjMOKVLMX)Jifc zZD^cj8rDi`)R>4X9clAm+oh6VRN5#jX&1*3#ZD~Xex&}RI zw{{g8Q$*CiN2M)|*xi|DR$GbLttC1UE!6F4f>CL^M%mrD20dx7hUkw~V}f8*+R})T z!8PbfyNy?iHV?MDQ5n@nACHPL#%yWC2MIJ5w5c^3To} z#kYtgn5T@_`z0h8mG6G-YS2T1bu-o=!Ki$PZC8VyG2ye_qO{#qQCa2Ji=&n}`r?p8 zzSlSI6WI%PQ$>PN`4-|XK@SP``An1Qg9M}UZOUB@dPw95cNoE_d@FR9poav<;Bh`k zFe=|}-PNFnM9vb25sb=rZg&ZK#zdVTgIJc_s9ojPi#aFmesP$2x6`c3H0~yqhgFnqG`}GChF>Zzg_uw<=2YwYNL9Nv9hB<4~ZBbo%RGR z{l7MrkYH4d`5g^-@T= z&EXrBF88=4wns23zXjT@L3&7VuRhiw!KnPEX?MJ$XH3-hXAUDqcP2(B&}6!n>-^4Z ze2;|pPBLEgL4r~FRoZT<=pn&-Kw}LOjLNU;b~WfBk$1cfBN&xm3GNc~kl;PJaXv^e zD!+Ez)u4w2?=6lsNH8kD!Q9oLXH4+kYpN{QBzPw^w0)hI|;$4XgwW*9uiUiCm|RWZMs9yLn7MoNeD*ed-}U|P7jIbj~xvXjLL5Wb~Wf3 z6MR;b?L_U$Pv3I&7_Szp=ls@TSA!lBF+Mt-3TlZY7?s~_>}t?MBF6cS1_?&RY}YAW zdiIIl`J%ZKYWGDgCEBak?x`e97dEBDkXfnxJ%@o<0$T5oNB6a zSHyb`yBf?#?(W*1TTfx;+vf-LV{&Dn_wH#;M8`YfJn3)Kisf>Q+`xk2P3>xzcZS(;;$g*y?$6>Z!`r zYin0dPp2x^)U6$NQkAQ))+fGO4*kJuFpqz1#YHCm*@q;WMvOZCAM>({t6j zvOKI^F^VNJ&PT2+j@GBsUq-viwGW?19+s+HksYm1^*c3~bNEp_&py?%%2fuRK_8Z? zT>CUV@AKob%Gt7|eSYe#J?HaQR!)yK*avf!(dwo{ z-r8}dYFW7D`WXjbJv{H3zqYZj)3;Zh`?WUbUFh~r&%L492X1@p(*J8K01^N6SGnU*-m)>m?J;qizq@qvihEys zA>#hu|Ju##AN@(cZV+yd33^Ce_dhS&{PSn8=@3j6Q}W`MU$%MM{VwXH>dZfU&E|!7 zc#eA_%C8&$-qGj~d-OOTye?D16iyS2iu`p_MGuLvPmS=XsLc*R53jpdAIp-P<@()! zf3W$w2OhP(jM~q^=8Q*P_tmoF->siVyJ`f>{lP!`s?F7B-Op3PQXiKUJtW53$t>3- z7!~xor7EE1njR8+`Dnz4?s(zmgSR|mp=ud-*Ro9MeS?W z+84EdSif1+egnXIEw8&e^7761oPGa~I|7f!$G*1f%TVH~q4rhlJTilu>&xRqa}gVhbG;HbyOMwDf*w#${=L(qcwHM;7B+vJM1$%iZ1h?5X9E(9V(%K~BceRLq2YF1sgnKB5`x+g|aw{@jaJ_=y@poc_^+D=EX|Ie6URLl|` zB1Sm(#F*%|X)h*I)jT9(40d{kzcQ=UYcVRu{0>1+%q1SBRP|Su^pJ>t-mk%SEk?2b zdp4H--<)ebB{6ck&3Y=am7s@2jKNM%6O2;+Y8mbk%|pU$`*%Gn>d!c(=P-&r%{7+( zU(5M#f7e;VGcH~(bgd`Pj|{){hM#hK{oMNxcl}xE?5^SHA@MI?y6pr-`AYei2lq;qU?mqDolEpee|hL&+unY z$*}t=`=~O%ZqL2XcvrM6*mBLZKkNB7vfb8Vq4MFCAYr9T4~f(6c$49U*WAbHX@XJz z__a43Zu_~rcL=8adS8Frw$t0oM+hy~^pJS{@!JnybZPJ7Xr9fF=$ ztj=s{=anKs{y*bXk@)$`{?|lV@mh@f(l_6=)y-Igo-3btx7HGQr7=MdiD%#W?yXHv z6O7vHAAv2`^pMz|dw0u6Y58Lf5{wdE`^}hOpC~P+^pCikuxS0frHY;peBu_vzu)** zJ&ISF)*x}!xi=r4{s+(NXz*H$Qfq(WGoPKrvM4Rr><1!h>tjzVv6Y~Qgi_dV?Iak* z`zT`#mb+R>9dTGsV}c$MrG+jR`}IMBQU7Os@8R@!{#J*ehlKjdAO8BYPC_v1)gQXY z@ZaBkNr#|^gnIC(2504OxhBD=5B>bzhC4jvwH*z5NN9}dw<{8iy3_BSIc$FG^&Jg* zNNBXHEkCm0|Fc|^VANR`-F|rb*Zp2(?ddIu-(y1q5w93kYE&hum>*-vRu=% zPh7azZ&xIWU830k%hjs}d#C28+LqXx#{@kj%ADA1?IakrH=i$Ssw`@Y8F^dxvZl8k z&9#l7$MhOu`P=sATI=WAI=)yt%Wp%KvcW#-&F~KMsueNnmnaM?W*7oXKe2eGLHI_wbxn}uTA8aX^E-QLSSnq13P_AAzNHEI!N-OCx!FFY>Z;RDy zYcXSjWktf)sN1>@o+cP&Yv0z!#sobgYO9oXe}zmB38k>kSFW)vN?MU+3s=jpY2T~C zNZN8u4+)#$TDe8A|Ie6U6zgeB&_lvzILrBB(fVLu%QXo`v2TtwSSF?Z%NWHn924}A z&=^z4$7zC5>QViflOFZKI`>g~T7!i8e1BHswHReH!$iAcKezqhw(cM~R*q9e4+-0g zZtGrjnqZXbf7EsZTdwILVY}DuXkXhU7*$$KssC}R=pkV%we4sp+%!lqN-eS9O6VbB zYrAcK)klI+8eRMCiXIZSQrq@deIyvAF}SwMaaqwr!d7bA{;H1zqcm#w+b%sMY^ApC zulh(ZO0z+KMMe(^Td8eFtG-s}Bp6kC)WnL+`dabq6RXAk2*+!&r)p);&j&pu*yqPJ zsF9(rslxVqZ!x;&eYj=emTS(bMWd{0I3ABR=pjMvX<{68-|cN5_SbjXFDv`C#^xch zmyZxC`M?u*)y+oN6>b0P_Bd7alzbE-NX(WziK%o5p#*t(*&bp?&=WCx$js^)v#o8{3<;?%e zTGU2M_ryr#c8pzaduaT}_q7@=-9sYAm=3`*i4}lHu{PuK{y*dTAQ3B$js~yAsOeV1 zGLeSuom#3+ULPcsKifx5q^e$vQED-^|L71g)c6|;7Spoc`v z)F&Yr73-A_5u>Pk)Rt^_=l1k?MGpzJ%6{pRV3bO|UxW0hq-!hTm1g*Bt8kwuNR%>M zc%B?s7Hmu~Ds~x36u?F}M#bL1qoxUZNW|_XHI_xB?O5Eys8|OlQ2x->PGg`|sS)GNj1{eQ+9 zB&?)$f48H-Yca}d(==8c!dkeVLAl4qE{iJTU_5ooHMOTnZ*owhT(_(&Sqc&C|I_Zb zy9NoXP2F|&f1f58Wvxf|!aIcWVf%3R*vOz~P;OhV)idD^K@SNVyQ~z>ISIk2>9V4S zg!JkvbB4e64ARS;QLHBimIYg`ZT;DDYip`j3alqcSPiliZLZZ5jE%Lx?Wxva5;h0x z8H>|n4PJ{;wnovjq7Fe137e^PfBz%|qgb=!RMA7CwESg9g9M}4-o_d>o)2{fu$f_~ z>mAicU2%>HTkp1hry8vNahjlqgxW&CU6Ejv?R_R%JM%%><`O;O@01mDYisJEuG>hD zb50KlTf+}^JvU7-ie>1;vT)^{i8?Zrs8Y|;KKZyyLVEp{$ZIi5dFuBMj1l#d>hrZ#Iz>{%pYXYV4}L zizPBn6+I+0m-O2%2}UWk{a#BCi890W`UeR{P4_5UQ|o=GjYel%$?82Rw{1N?*wa3@ z$2q5mgzYj0d*;<47-ef;y>sPJ(*!*vI985RMS@Yb;vDQ5WM`E@4++-OScAkk>b}EQ z{PLe(sxow9S-9moN_Qbol$+b3=XQxL{~f<4Ln88*#Ii>)DpELasVacY&h(Io{GEgt zNA2XiY49ET^7dc3rz_i9dq;yF5~Vly?g*1$RP=(520bKVj#})O6$wVg441^RWPQ25 z=RM!PIQw<)_#IvA2_Js@;?AFZn!ooPsa;QMxaY#}`_ke!f9$nx-}9c=8E$@$-|7(b zT|LWxcathy!>TSQ5-S6&X=X;mut4_$j4f> z#$GUPCG?Ppa&vl`U{uso5-nBq{M>#2X)*l#>dQzK3Hu!!>*sGujYwMiiY`1E#a21a z$Jmp^bKm(NErrtrqd5DF3AXAO8N8m^3&sRJBw|#WAKnKU6|+x=peJTEkD~T;sz}6) z+R@;(7!_sJA?S(H{W4NTB3emDgQ;Q^d)heXV~@8Izizb3js^)vaU2_K@XHtWN7+{2 zoBcYcheYIWeK^4=*?kRqNKD_EAi*f!2^;6!qHOJdj&d2#%*%?^uGHQr7!&l!u5Ywi zDOfr6*1IGaC3|vB-8>}XYc5aiI90qBqvFf34q+qprmjD1HrUkFOI)d6gG!ZqNZ8D< zscRHZ)v}~*xwi3RTRk>1Y^z3;NJqnFmW{1ge2ikAY?Zm`uS@75v6qjQst(~P3GHL8 z?KXlQUUx6&CF8bNv$14T*9^BXs14gm+L~u#m+D0;!t`oKb*woz?>t;;Q zL&8=Zo4N~|CK$zjGbUJ5Hp6YLcg^d#((mW2DH73FoE~eCU=-Uzm+-Q(8OQp0S-r4C z#>Ci@gv}+Jx^kK(7{z)T6YS^Fi}w2bn21z)nUIK)s8d!X7!@^`#Ih*a8NV2#qCULb z*rvy+qK8DZ1*fM8Mn#`bqNR$S7+1cGRFSYX%0vw^ALFR3|8YK8iqSvjYV9obF+mTB z=#NfM6O4*>)gkDKmiT3)ibV94jt29=DE7^9KE@s|QNM1KbVq{(qd2dOHDV>R!HBc2 zw*9aF`pU{{h7**|}agSeo_mSWJr=N5Uda5mrc=snX zrU*t=yJ&pZB~Lr@zK1@|HR!3fG~#Wc(3m0^Rqdkjjw7!*>(*a)fosrHZE3^^9vV{w zqpICBuB;j{;wYDazGYYr=`E@7qHqN-gqtOk$O zI;W@F(y;o+S1D5jqpDprtR=2%+oh-4(y(@nuWP0VMpe6LSdUuQK1ffsrD6RMUkObS zjH-6gu#sV1#}ay~Ee#u2@U_zv!Ki8%4IAOsbxfqE+S0J`5npXh5sa#K(Xf$vUB`BM zsx1v0=kfK~6v3!!7Y&}b zQv{=`T{LXXu#Po@=5xQ6Jk^$ltqkxD?-aqPYL7I09t_V$o@yf>8`-`tQL6TcNR>xb zyJ$qtkIw9mo@(p5QEs6zMKG$`MI-9`m^A3Awlt#tLt~0yRJDsnv_#jSr`pnpb{ra0 z1f!~5G@?hj20hi5M)b$fm?9We?V=GQ!`g~U>k^F_Ugy=8MvN<=F-0({+C?KqIM<-3 z+R}*eF*K$KMpe6L#7ONL^i*3KG0um^6v3!!7mb*4T!Wr!OC#p1(3m0^Rqdh?GpB3N zQ*CL)yc-%*1f!~5G-3td8uV0K8nJ!|jVXdr)h-&B+AquN7X@ebS3DPbyQ;P{>Y)M-&bG&ghavwH2jO(EHm(g9JT2qG-I;>U?Ft{%%#iBvEZe zmD*f{1_^q4MA3+rxRwTqYAZ^uQtu>}e2}20M-&bGe(jP(wH2k_r8k$01_^q4MA7)T z^}kQXFZYtDwxTpj=w0Wi4-oY9h@$Zm*8l#*e*Il#MWWh@(rBl5l8XijdU{0Bh>_Yg zNK{)<8nyN2a?v0`Pmd@XG2^%fiE1mV%sy3v1U)^XXq<~*wkA<+Mb$6SNv%!Le2}QNqU`;WHcR-gPB(&{9#J%G zR$Ir6Gb2%LMb+m!rOrvv(<4%&&b1_}UGtIixil)F>sC*XC>l{#zGfg%ZAGaRa$Q1# zo*q#&Y$dazbNGwH2jNBG>IC=;;wf<2g1azCHE^B&w|_jdr>JAVE)$C>k+R zds&gFwxTp@=RS%AJw2jm#Ejz_B&w~bGW(Q0+-ydIo*vOOxE~yJmY({v(QZdR^d*x2 zyK6MUuG>64qG(vok65p&`DjF?6=kKMZ>2(m1U)^XXxOZFM5{~n4-(Z@l+~ubB?}D_ z^z?|L5o~aS*z3+ZlOVfo*q#&tVhlDf651mYAecmm%hOZ4HES9h@xR5!`$XU z*C0`CMcF7}^}h%W67=+lqM^F5dCvw6_>gCwf0D4Tt(tj-Ay67=+l)Ua9YO3Q|=+w)r0uKBRp4jPrv zb*raG6pbh=tr?ais;wxMg3W{DvT}l+9#J%6N54l@T2ZAom!Uy|o*q#&q9v}C4-(Z@ zlv<_DgP}o!o*q#&qDQ#~iE1lKz02mo&>%rik0=^(r^q!(R9jIRC2SrH4HES9h@xS$ z+7X)vU4ulm6{XS6=E2Y)K~Ik;8ZlD428n7bN~5;TgP}o!o*q#&Y*y2Z;~FHYt*A2l zTo@W8=;;wf!*-BYhKB8N{CC3qTGdvR?Iw{A67=+lqG362`#}=bR+R0EQ6D7e=@CW4 z?s6Wp`=Tl<-4|`ws($gb~M(n&aN6ko7TTym5ay$=eujT|jJt8&gTuY+b zH6J;jD^-=yb*raG6pbjWBQ+nDsI;O~3b`&JK~Ik;8nL5y4HDH>RH@Cnz9Kt z#5_oXo*q#&V&;spD!-SR`@su0ii%luQ||kapeN?R5m7WO=cD~#-6L08QL!2b4HES9 zh@ufI8P5laYAY&MHK9R*o*q#&Vnr5ZRZbu&WtFFq#Of?GNYGRDblv*zMZ%rik0=`2-QfLA1&vDRy4BMo zibmx8m`xwPAFM>B6{S+h`_v@p=@CUEcJ!`6qS}fowOQ}Clc1+Z6bxhcOpUMa}5&JR#dFc zLW2Z7J)&sD%F;DRR9jK8$_xz>^z?|L!QCB+YAY&M%b`Jno*q#&Vx_M!v98Ip7xQbwxVM95*j4v=@CUEc3y2iSm%#QD=Kzjp+SP49+4V#t|d|J znvXgM&t}r7gsxjXJ)&qt&V9{5qS}g5DfFKY($gb~M(pTagG99zRcf>Me2|_VQ8c)_ zBT;Qdsa59lK@#-zh@ufaYOc0RqS}g5@2YFm*^C4|J)&sDog&vDQEf$Ol$d%xn4TU{ zG~$kzYw%jtR+L7&d_G8mo*q#&Vx)Er64h3eM(w)y@wX;*chCuXdPLFS?v6yY6;)=R z`h1WCJw2jm#FsB?t8!b5mXmpNKUlu!v-eYR#xIDtle+Q|fKk;hJIMHg$2I7wwo+p6 z*|t-NXEPA98l`J7s@g@v-uTtGORhmrwWVS23%65`XEPA98l`J7s@g@v-dxryJ*%rik0=^8JGXmFB&w|_o2m8A zU1*S?r$-bGTV;&iJ+IfQw4!XqVKrCpg_EGCM-+{?Yv65{M70%VD<{2k7x^GTPmd@X znwiy7)JjNHTT!+G)H`>zK0wgZBZ`LZ6ya$`yH=$YWh+@Lt8+qw1U)?>HR7qvl0>y@ zKI$6|TTyoB z7X6$AJw2jm*j?w*yXSSxsI;Q&4z#s}I$n{Wr$-cxxX++5vA!ehV_&5eWp~ms?vkLV zM-+{?U*Z}hs;ww{BG6`u@w*1}^oXJncX9mQ5{YUn%ARbD=fU=_0X;n;HR@bTqS`ed zIiD+4mC$vor$-cxD61o?4-(Z@lu9AjB_!zS5k({J4!Q=3YAdSLW?f&Apr=O^jcAGU zY**!4l~$BmWnJ6NW+dq85k(_!x@2u_Shii)+n}FRE=(L;Z~a{rhZ2f}S2BdNzB@PhK#8 z%AKC;V+o0BE9zl4xbHCB=!Hj$#`?t<%zx%$EzSVx>mIn74&+f;RHQBqG&{&pQZ7NM70$aWq7P; zM4g}Y!H4})EnWAJ7}rPCpr7M4zE+lQ{rA$YdPMOg0S&AFsPnUySG=mW#A7=|?H}v% z?@{NYoKF!}3Z@Y?I4WHc$oWu9x?G6_Jw2jm#GNAb^VUk_3EKO7+-GvTf3BJcMpe6L z#2qiM4|=Mtw8#Cj(3m0^Rqdh?_xil7=&80e;*MTuOc9K#cF~ACkgh>bwWSevCPQP2 zU{tk>M%+nt4SK3AjkpgR8dC(Ls$DeVjvkHwVf>G5j8XD7W7%BPq;NNcQwVrUr_1u2y z`@duOlRN!Sx1aK|Z!xX%R|t9@eVsda)Z4E3rr}Pw(wLx!#Qi>c7pFh*L-*d%Ai=2m z?`6hesx0jb<>R^UT5K(aZvV;)?zc6#YgQ|NCFk^zxWRMZ z;2O7o;e!t$76b1&BuwvEP2o6IwT(tk-6~49)s1WH*Eu~_|Ba~jetq-^MOodfrMF+_ z^zgcI_UmF_g9M|jHeF-C&gmh+G8~r`2}W64aE)#&X&w^O^}!xhZPiEZ|FXxa;)rvD z=jzwwSBwAaU3Y6ETz4$-D0xU!`|P84uv#sDrAO6PLPAlsZuT|k;dN_juk$^60z?fG zjH>@`bv{AJL!yq_-7#^a@{z|zIJY(Ko|*=U+NL#vM>b-P;SrZGj4++!rQCle-r>gcfwQ8%)LD!XSb>mmsuXB1xRC_hh47u8+EsQLnXr?scH? zgY`6BgCuMua=JUhxhF=r7F9L&$6b1O-D+zL?x#xEViam~hoFZ<&C~u`lmw${8EQ2+ zo7pOS@8n@?KUy1Z)%uh|Tf_S)#3kob1f#00EBPB+dnXUeQ=@cU+l%-q#6`pQA6)M{m&nhk&Qv{=`T{LWWw|7>tJT*$!wY{OARa`Wt2u4-AXxJ`w z@2p~ZYLu>Pdt5)OxM)lfjH-6gu-*3FS;g|yC|%d~>V8&n(U>9_Rqdi-cMbN=Dwd~4 z>AH5$!Oto#8dC(Ls$Def?#JF)#q!iBUDxiN_*un8V~Su@wTniaLhJWS=&81@YxjWs ztm2|EMKG$`MZ@k!?VVLDPmR)b?Ov9jFI+UH2u4-AX!K4VmZwJPx^_>_&nhk&Qv{=` zT{P_O;M(r#ds&5NgX?Y-Wp@g<`X%L}L4ux2lPDT?e|K&7^y^*DcCAV)%I>{x?Vf(z zFSYx-YrCg^R@~EX9uju%b$i=~{q>!ShTW}Q+dchyf432g`u{0=7pU8^s=o6mua-g~ zwAw;TQ;1LmMTiJ0TKAk!JB-K(q5;zwU)5rv81d1HN(|I7FhD><31|cwxhnD$C`GXx zQumw#11Mjl5{(Z;L1l=ju>};xJm~qKkG+2T+iRV3>l?wExpV&3f3LOId#|&1X~cZD zM}&vzPPX-|w!gcxJ^ib5Pv14p5!ws){Kdc9{_f89^k+FA5ta|r=#{RBN>@=;(vcDg zdV0i6!`76mRT4f!DqB%WuV)%g(9 zqsk5qt4>?{f3A_cHG8e@Y)!Sd^@l$n&fS*1_Gc^}1U)2j?_@t)pSwn`GcE0lXSpxB z*M4iRIrrMRbq&cBVbSqxm)tejYd0cyDfY8n11Fd+^@><(&_lxP(mr=p=ZGmPcV70h z9Z0__Bdo`^615!Wn%twPXPNfDDd(Ha`HaYw{(iQTDvd4EVpQ%R?5BIKV81GQNZdPi zKlZa7Vb>tRD63aiMt+~pl@&cCa_40~+u8Q3BEcxDZ(bs^r%QfStQoj#swH0PQ!Uw6 z&gmh6GCWu@`CpXPIbu__vhL=z!?G<6wux$Ynjwwb2R$UpwmTSCHEHw+MOjH($=tA? z?O%E6(!+G^&RW{h(jwcH4-$;B8si$X{VUg?hXhM{u0euP)uNWAOAiUVPc|0c(0Ycc ztdQH~>r$G;i zx=)K%yCT6Tl-oHCdPvlLTJ%0E5{#<*wCodeCvC4CIx9E3f*bsP>qlO5|a>!`^3AX=&sHQG2BO*)x_|KI9=$cC4d#Rh17C zimEc4?WATK^gY&nJ|FVZ6=AjA^S9JsT8yfHpY5d1H1avuly1?>7R9s}RXLxCE!v=` zo6m~e&SyoQC%c=6RsO{tthD5*yC%Zgiqp$^2?<77yBTQEL*m{!axVK_5{$BT<5#uJ z2R$ULb*)uHm;EjYMlHrDE3c`x@0C{W>ARhK`fe|4iQToyW3_T3?9RHqtcfHTRsTNS z^Hp6HJtWFr*2Er>{fgC&!MtShFx|@2viGrCG7*g8C^7$PPY~BzxzwKi_1?qfFI4>B z=L9`Pt9{H0B5kf5hWghu{K$Tdimt*HFPP->8%r$>ZF z{yxezNR+Lp{N+<>kf5hWgod3~pZ(TS??}-7C|XhZ3$D~4K~Ike4gPYHMA?eUU!tW3 z33_@&XymWxY(Cq*^P_wet*HD(U22e^r$>ZF{(jIkNR+Lp{AFNjkf5hWgogc^V|tGl ziLw=yzi> zg9JT2A~f>XvaUg*Y(>T0+@uBxdU`}?@RyS$%2t$WrQYKe`5-}0j|h!yQ9G3tiLw=? z)}{A&g$49vs-(b48Wh*LwF_ao4=;;xmk-v6w4H9K5 zDu4Nu8YJlH5usr%YI?6TiLw=yzu-y@67=+l(BLm8NtCUq{3Tjykf5hWghu{~PJLqj z)-w9Oq7{|Ds7nnJ^z?|(u%3E)j~9uu6_vjXObrtB^oY=~QBA*U^ruTC%2rhV!Z9^S z(9lFDFTqttiz>y~iu^L4uwh5gOT|)+_rXQMRJgx@wL(e~%YEJt8#n zSJA|E8^=@Frkzb1DL5@jn&y`A3U6&fVy=@FrkeYTB6KlBscYc(^9x-X~-8(kdymBML(seuYq4#q7zxTiMGa^DG zX8>MSb|q6O1&ighsCD7evvDio3Z@4HES9h|tKIxKlnzl&vV$O1(!T@09uXSZqFjSS z*@{x@(z|y;g9JT2A~bTR$Tdimttj;pdiPFfkf5hWgocf3i|_m>t)dmB-cIk{2@MkT z^oY>Np4#(4qHIN}*VcPxLW2Z7Jt8!09Ml-)8YIeARE$^Grv?dndPHd03X<>MvGyEk z6|E>+O(Gv8=;;xmVL6{xcO=SIl&y+!KS8nr7_c}*fMJvj7ztHcJpr=QKMy^;~gGAYivR%Asl$gJJhn^l08oBcF z^&p9|6=l1T^Ko!`_YOThqG{AvOQP(`M;p&|RYfS>^7M$%$g;Yi`$3{?MX40pyo3Zj zJt8!6MeiCU%2rg|&CMqIL=yD$h|tKIxK=($l&vV$$~I3VK~Ikejcie_L85F$sdcsa zE(v;iL}=trk!z4BTT$vI+Ps|vJv|~cp3wQukIKDhMX9%I>kkt2^oY>Np4#(4qHIN} z*KX@567=+l(8v+THAs}Ls2F{&%z8zFo*oez-;Z~(u2z4&fAE9fu!}l6*@tJp{qOc? z|K^7LcM@|?mpIJd#YzJ9;rf5^(fyBp!z)w6%IbnCC0bv^NwH^8o+geIjMFRHWV;+C|!*@LVS*bySo&jMRAGPO$@3a3& zg9PluJMQ;!hudBA_|zal&wwzE|7LmkgZ%C*3D}2Ed;AqvUJp(U67&oR)6nYfwRTUG z4-&8s&%e{hA3k!wzqN5p&%8*`GayXkeO5zm_w;xdD+$<#e|G0jIQ-)ed~a%ypl3js z#!uMF>-qWJR}!!fkAM6p93K9fx4ta$L4uwE(KIyHZb`tdd{}v^tWv{?OxHaFqLr1E z!)i+ccHNKE$g*-G%f~$f!Zh*@E(p+7udIIKo;#8E**ycoG_odIy)nBCsiR?ezGayVOdpOr10lWI$)F6@l zpnC>{X=G3B8YE!X_>meUvOjmvfG~|5aa@B0Y>V>ICpAdWGa!uqF{}qkz&?D>=lz++ z!PFoz_e@tp!ZiM;tq1?ip5<8GU6Fu&_>R}UN8?~>kf3Kkn8vj>_xZK_?kfq{hZnu@ z_x3gprUnUm283x?P2AZy==mT4`|!~R|K{Gt!PFo@&wwzE|IgNge`o(wS&@K!c--rL zV{hYNYLK93K$wR03_BYKU4sPd!!JMhS8Pu7;M5>N&wwzEx7)q=Ub`pC2MO4RcmC;H z_cjiC?>Z;w84#vnJ@wAULDwJw`|xdl^p?GigQ-D+o&jMR+K>5RYa_}B3E0+Oy=DJh zn-|D~Bl`PJpiaks4W6PGtEUBTOUj z`GNpl^~&m=@w-MME# zm`3&tu0aBJ^;fAuBKr^b3<%T69?msLz^;BbHArMX=$-*#8rf631_{_T8l(n^?9bgZ zAWS1i9M>QL+oGmb*x8(*XFwR8JE^XbJDYpe(XzE_%w1Lg_c=jNkBBuVS9c`JR#ff| zrv?dndPHdC&bH@+MA?eUUGCH%K~IkejohKnvYNj2TKnyOwl;U`Q-cIOrKfc3-$TQ8 zSf=x$<ZF=G;cI_T5+2tD+U9Qs|!-rKd-PhSq~O#N1~~qHIOQ-HbC+v4Sjuo*oez zeA-8%Y(=S7w)3JS=;;xmku7ScvLaEoqSU(j=SAu15uuSM2V8?h*@{vxF*+~WJUt>b z@&tryFs-r`rQWWc7bQVYj|dH}?nsoaDD~R?^P=?hh|u8EJ`!asDtAA#4U(XzM}!8S z_K_%CQMs#{8YJlH5ussaHG4i-Wm2@Fa(6g2NYK+GLL+y!bCC9uXRR+DD>nMdj0z)F44mj|dIx z6L;Ce)pHzAt7t{#Q=rr!K~Ike4eQ&d^P(imR#ZOCN(~b9^oY>NCvmE zkf5hWG>tm_Nuun^N1Y1ofA>|RT8{{g%(>4QbS0Hm*@{vr^v{dZ(<4G7pYXZ{iLwTBQ|CoV(9`EdJfs&;YSwT8t_?H0eHFo|vO~k(I<)xi>v_W7S>)e+4Gj=0rp2hTL&M&lwD|6;JQbyM z?cGcM-Ph0nF@5({1f$9h4SNgJ`u86FdA^RKr);Hb?~wBEzJ>;fRYfT+MwJ~J_BN}< zcVEvF_AV^{?rUg(STQX|l^q)SZ4Mu!=qX$2+B?1cyRV@!A{bS6XxRSMboShKqc%8e zP`38SHtnndiMeN@N!b3C?W$d{XDr_Dl7OwfzD+x8K!TnDVH&nOc)^~rxCRN>+OyoW zvj!yS84#vnyPVTm0}`;c_qyqyHK1oen1=1vuI(9%=Ys_7gYDdI+F1h<^b82ouwCcr ztN{tw+6%Y)-#cqS&wwxu+dW^~GZwGABw%Y#f78wykf3Kkm_|MgcMTG-^=x9(KWjkG zfG`bvnz6QLEcG;FN(;1}v25B|0}}KMh^C==`<4Xk%7^7OpRwqwoXB+DGay=7U6KX~ z*mXZrBTLtbEFbp_2-Croo z2-CzndB)vLAHM zfG~~hsa=Bv>>3SHgGBb{?imoKkt2?4kbrGbKKi5v33>*E(RMmvI(tq6w$4mw983)o zbI)`oBus-lMI>PB?1#p|)F466fG`a^Epo}u+^MW|N^eRFw$8AewX+5!=ot{Ekx%Lo_MMQ)xR5gPWyH0*T3v>qf;wxaB$0`ftE zo*oezIRj8WRwT++l%2T1{UAY4j|h!t+1leRxgI1@wxaCh2X6^XJHWhdR{ zr$>Ya&l->@TTv>7HZLJTPmc%L!xX& z#oes=6$yHJL}+A9T(^1^X%(#~)yg(cBtcJ)2#st}u0f(~MX7bQ`7Q~1dPHdCDJ0h* zQMRJgOSE}A33_@&XxIt5OPXD(tVootDD`%2{Xv4B9uXSZQ@aL(E|C``fN>`wy?$ zzyI&w<(@Bi%q#al^SBSVZS;OfY>e0`Eh9EYxGg;++-?fi6I*(pcXo$o{JMRa*}q

U^u{I!`;+ zpofIbeR1NqschFI7{&axc-=wf*47`>scWV*C+HzzE2Qc4_n2T5YtNjZhlH*4?A~0n zU*2;Pj1pZZ>*g9Z0!;VWdg|%^tNr)eAk$LL>tr6a=Nj~oh*GaJca531C`Q!@m}SoC zA)$NT&fHOh1f#}vmmU(TW9`fxHApau?WV=6CfX|Htj?rauWk1x&W=TYd~v_bIXxt- zpPy2iYmi`+jXqNgo)fGYHr7tDMcIqIE?LXG-I%B4IPYsdbGBM%lb{(9UgEJoOohs$Zz+s`~Am9um@P zze;J>6?2A4i&5-jTD)pI@2zTLoxrE|oS=t9)ch;={q|8;#VGdRa}9b(sBP92jtNF_ zw3`!=Zk*-h2}@)6kc#ogNd6vXa*KwmXE~K~s+!XEjl?dykTK)wiWac}Q3* z(E6jR;j3!*Xw6w;IP*8xU|QD0Y3=0n+Q6<>s%GnVwClKT61;?daO6Fa@*XB zt0H0jiq_{H4PF(aRBqMVt?;*9+e~IE(cC@vbZzFW?>l!i=pkYAd40vTL)biFDifOl zOeLCMboI3eF3S2uM%g@Jx`Sha9un662la{sqpZzO^>}_&tbHoon)QuqB0VJHZf-ke zMS@YPJ;Skf@~9@(7|xXD`Jjh{YJSZh#ss6((%LT+8snqd#Cp44Z70Df+YdN==6654qd^Y|TT@N#ab8v= z7-jnbho`=@cUAO|U|%`cAi*fxXE?n0b>Gs-2R$U%yUsP(*NUkAeBAHSLqd7#j~^r$ z#lCWWRrHXEdlMtvm|zq~i8+yd)JC;B`$4y($GE}mIg#U?dvY9{2%CNQe%Y8%x)oJB z>B|-s{YR*0U*a0scey>+U_N;5*`sy{<~BzIk0L$Spoc_`J{=7bjLOljLonyeEmIm_ z6^R@_IvPxiQRA}WeU6;R69J`EcXN4FGI;PY`i8W5+z_J{^KJocBM+#126ZiCj&bAQ+V+YKNeQM6O;=5RA%k zw?oiFBG*(W2u9_&+ac&7k#mL<1fz1??GW^k$Z`Gz!KkQX+YUhwi5%xo5RA%kw?nY4 zsW+%6W0%*?N#r`QqrtQorM{~@!CFm!zGpeD8nQ+0HD+*poWjl6uIV9>+MQJqiFwrL z9q#p&zkStmjIw7%lZOQJH@~V5;e8bQm^ncY(;b%;2}WfpY?k?8zoa%_Pb!(x_^L># zHCK%p6O2;Z?Dy^LYjf`7*FNrd=^>G`vrf)QFe>MX9fBSbIe$DsFe>M$9fBSb(yNno zEBtNOBp8)5=Z*$FB*r}h2}b1#prb(#3HC(DhP7H7^|j~iX<1LC9doy>=AYSDbvqh% z?b?rakCl~0UE{WC=-0~~g6Ud+r9FL*8f(x)!ul>f&FE;5V3f7N%g6_>-O5cn^c@Z6 zR;5sbjE#wU+UGX4=L9_@ ztYJl*K6@AD|$#+ ze>`2`m|&F6ob>L5js`s>tk)jYT@sA4nUmg~(9xiWgziVRu6aI4Fv@05dUrxcgB}vP z|J6&(HApbZW=?u{LPvuh5~`KeE6p`XFp4dBPS8UlT2yb=M}kq~oN$6O76yjhp36hCP64V&$AY#$1CQ z5^5_|hGT+JmzQ%A(dMu0z>z0Chh)sP7jID=(P_LjN)8kepMVfdH>nc<^(+?Y=%6Y5E~PWvKgn|u(4UzU3zSm zsds&N6t%}1By2XQw~=%-m=>dKrl$9>bO?G#*lbX5Rp}7#zVG$>-@n^E_sZdGANwQw zKY8M(x~)@s_HS;l@V8ylL*j-DFWP_Eoj>IS!Kl~#!jJEN=pJ|N5LdqQr#CuRwtpXJkeH%adsg`K)1T8>PFo)h$tNR1N&qn`fKS8qQ2h@a~a_q*{Go9BIcd_U$# zUi7NXFF))hJKcl)_c7rf5@~k`sxylD8|Rz^^-dC=58j(D;ZaOCuh##4OfYJE&wuR? zFK+Jhh&Nq`T77Zz)Tcbi&+_KK+b<=~pJHXXKl;0WYV)?MALb>>`!v5QdPvN*8?#-L zU{unboYO;MoR91WH_Bo5qHf#$*!RcU>qq5vOS49tr zv@ehFs4TY*K@Za%-*fB3_cli5SaflJ&#%4heO0>o?>Tn0((>^`_ruj~WZ2snnA zi`U)~JtXGZjhPdSN_wp;Z1K{dhr~D^eCo|-|F(uZ^m_(+&J)%1&991t?26L8>1)t) zo+x^*K_c(DmrwQ*n`K$iLn3>LPU+g)TJ-HauMPGd7JF|=e4~h0IKL`-NZ9*Q4(-iG zjoGg0u{WORyM}%xOsU1|p3_6Z-esaMFLv@lf>HKn5_|`%sZ3Y3Qz>RX+|HETZt=LP z1(9W#Ev+%zH9hw3o#_jLm#0C(-VTIs15$%&F^VP9;*pQFa!w-kIz0o^Viar7T*KZX zH+@sf-deY>dc|5fC+Hzz@72Rsts1jk+gttgEh;bfr2XF58wK(GC=&FLpmvK_S#=06 zx76;G6+KM%^74^Ui#*M*iq}pe%gsw+OfV|%Q-@&7v3KuGU#w$Ym}}5O!rtOz_x}xE zZexN`EVnr^_q25FEqT)wjtNHDyZZ(`13mT@!RZ@!bM2-QYlG^;N!WW1@%6e9!6>$y z7O$GfJC%grHP(eWK@W+%!p=P>!Kf^e4w1FQJ=yQNopqr@&_g2o`4a@Aa$M;UyxzR$ z9>x5P%ZfzS%8tf7t@gDn=5MYs_cS8gN=JhPqgd*54b6S(RB6s+_Uh-E(wv~@JYl5M zV?uOA%}b;)Q~U57o+pZK@v7}iOLj$ZeKjZOA(3l!rEqR$X+5Xjn0p#Auc3|cRy(yEM#=84is&I>J&_UDY?iH-1f%#Auw9dCB3n+@C9fsan-lbq z$Xe<2m|#@a{0>1+wys-oRV4DBcQlv}MzNQe=Ob&$4z0*-zKL;8(33UBiPTQIF?#z& zd*36Y@;-G4dPt0W2IeDMt*6T?Y}b?{j_R&Qk;q=6b5%@>QQ0eX2zqifxD{7LB1fN& z2Cs@yIofsl5_cQ#1+L ztJO1iPu_j-FRpP75@jo@cD6%<1U)?>G@kLu>vs3N;y>J^e2^$RqT-1_Xpk_kKP!-@ zN6a+*t#u^IR#eiLW*Sb+J&R`(KKe{$Wj+0r4^OLTX=EwvW@Y6BJv~D7bO#qi(Td8u znHqV|ouH>jgodu)W*An>R;zr9xYzaOGsv0~=sSzVF_iLw=yrLYc-EGsAI z=@Frk_k2MVt*E@4sX>CC9uXRL{mO#%eO`C>R^v9h-g+9Iw*UK>kmnq+QA#9M_P1SI zZvCmH(zUDdXOOb96tZ3^HvXKLY6*$VQ`Yv1mqz6l8eTrBo%ftXoeC0R&xidq73jXk zbnPUnb%|~Yc~uj^sBu2(oJ3xU+N0+qdkMc!a}9b}3akrbf>FGibAoqpe%IQ#GAFDS zaKxGJrv3ZWn#TmA#&>Y;Y3b$_cJ4U|MzP%HS5@l)-H%#X9IqvH)<98tZ}zgSr2R>} z?70R#B=UYZeU#W(yYnc^$5h|u1h1;jHk`l0Il(I-QKuG``5?ilI?vE0rfbjhHz)GJ z9FnNhtxF9OjLMT-ozmrfwrlsZqe_=4&C7}&5>^U+!u0r6F^av?TqB?Nd%u)t0{q%* zk9?_-r`S9yPj9(Bz900E$X=;aRwNk3x-id2Ms0Mxso}Pj;ndsB33^D>DZORRNieF; z_$>)~vP5siRguVhRy^j$(jq6ct|8os`NZ1wnFD;h& zAi=0?!JVsO=~}(g9M10=@9g}l=pn({GbR{iC9=_bq?h@ihs3xhvNl)`=jW-FF7r3P zDtbudn7CP96$wV=EF+1R*!%RQ^cMU6(w(0DSsU$gJ^W3den@*G`(c0b8UF9L`7*sf ziUd6!ViSbkTrZ6e+V_`8r0r3UyUnM&#(#R{gH3}3Jsn~b#LfAwiSM*;jgUy&qki?O z|IIa?`9lvg4HEQph)ob5vF|h}AMdtr7LiEXqrUCuZ|54%zIkIBB~6ZoR7)m;o(_@q%4(w3nbk^lmqgkgWwp{ZrrJIc^mK@9AJ(FrP#YwXwntg(+N-Rl zRyz^&bck%{)-yPvzJx^D9%a3RYfQb*M9|YAvcIw(&I$F2B+~XM>+M`)>P07lo(_@y zuJzPTsBb5cwntg7?Hbc)FcI{0h#WuEE>`xZF^WXm9%ZACYiPXkF=`^{=@34`DfQT? zm6ape{z*&uIuzh^&6C61~q(+ zbcjt5@5=s4UqK~NJ%ggEAG`PS9&H*V=;;ufAokhszR~7DB&vr~RQ1PK{K~&H4HEQp zh)odRm*dAj*j$c8_0)>0apj}?$C?HSdOE}=h#$yN?Zq}HB~c@eqVD_5jr~gVhW*cf z^H-V%33@ujW+LHY(k)pRQ^m=;;ud56k%_X{fA7r0r2w3f4p2u%AkI zBIxN5c|Yt9I-z?`B5jYdyXhKJEtv>3IvL4O}^@$|X z_9*M^Tx04*CxV_1k^Qdq)J~{xCy};CS+DIH(`Yae^mK?EKWvP0B1fDlt)xAQ<6~P7 z=BVaGj%2b)_;|IlzjziUtH!|`Irk!9`xvaaCBcysL~8ualb*bL=igoHHU5_#`S<&; zzv>yb;(gDi?2mr*-TUu<`rqy!cdzgAe_yRg(9JQ%ik^MJ*=>Dlef}S1`8jt<&->`eeU%uBhNR+Lp-~87f-QVHOpO_jX z=;;xmaj(CAg{gk!xL85F$ede{dIsDsSU!?{KdU`}?{ExRiXm`i^f4*ywC|glK z|3`N?{P|CC9uXR!bJy>^^q;@(dtHM>*^2t5U;328 z6JGpNsX>CC9uXSP{n_W=^wnPx>jM&HE9$B5|3402dWVatL4uwh5gPBf_itSNjcn{8Re<>K+3LnP%a62NYr~SCt_Py^>5D}tt&NJNpv)z$k6tA|$i=c-@y?1oV$8=RB7{xN2 zYus@7%)>jM`x9P&SU!g@xc}k%ZvXPESB=^3=pkY6CiC~QF0YCNqt0G&)!|=#)+;(1 z_O>s5`M^u@#uvPQ|GGbXjobFdEPbt@Q@Zq!c){KNYJcs`uRK98>i2K|!Tq!T{$(A4 zW%W7td*I>!{IeG>%B_`@?jXyD#KXVtpB#SYi=NxbISEGH{jm=|y!ubSzeCXT%-cQW z@cys-hFft}B>u0je(2%b|Hr1I!K-2v>)Sl%^pJS*qd)iX@h`i3M}q{T*elI7Sbtcr z*z?T^dPvwi@BF>a%eqT~QPra^33^DxDQ2C3(&*g&wmTAxs*zzy&_lxBzBkAR2}acj zx747AguQ)n(9TIPsz&Oi20bL~U4iqSI*V(&Bf+SeaV$0HA)!7-?;t!*Fsf!wOM)H} z>Xr1S!s7&^Y6iF@=pkWm6g=onx5o)a)l7Ct&_lxBb2u2)NHD5qzg)1gx~8K+f>E_XT58ZkLV9|m^pH@w=}nc#2}WK0tdH!! z<=;N1L(oGa?*H}#!Ki2d&PVoN{GsbR1jp3-tp9fZ%I944D302#N7Tqk4~fUV`tSCC z{F5*4XpmqOuW+tG4~c*I(2wl@``7y@r3MK`X%?loO)m+0NYuALjuVX1tVVBqUlR0?sBfAaCm5w!jowebBZFe+v>y}pE=C2>RNs;>I|-`i_{PwF54sCVx_`v+d{cBIrJ=pk{B7rl4?C7=Gf zjs^)vaV;{hS6t(0UQ#trsQCBJ z9n^d1Z4|y?qaBEfl3ny{XTo&0>ly*%sj)px2}V^J&IrG% z>hM5;MZDs@6F2)DDa6TH`E<+P{#eR`If#k|jO;P2ZJSpC@WRV5z~h7*#tK zOM*FM&M)tNkf?EYsll`u#kw$M+YJA{fz_+)QLmzoRj;(vpog`x`jz7ZqpEjZ67-O$ z{_!}$s2U}f1U)3GpFd78s>ZG*K@W)5$BKAM!VZT!QGfRRV66`VN`5?il+R<5R z&_iO}C$f*yJ|S zQG1z74HAsf{jV~dmo7adYAYE&i#8ug8sZ_ou;~A=dWCYMA?e6xz?GT zze)`f^z?|(u+vmm+xaWkAW^oWY|eOQ=dV(O1U)?>H0(6hO?LiD8Y>cIE6V1+XLkN7 zHAv9YBSJ%I$KO_`sq`&6ucNlQJF_R1ZrjT8%)Ygjb+_WJvhV02VXIet!>vQuEZow) z!98JL@3!qs=^LOOf*umK%Fs7JPY{fkGskf*umK z^J2AUdxBt;t@QQXz79bT3EL0QR~SzajI#X)ed(`5&_jYPt+gk$C=!gaofmzvu%kf_ z3AW9-M&x$mY1xjKzR&3Whpy1}vN{^{kQldf5{%Ln>K)(9Cvo(UV81fYhwadv*?G}R zO3R*RoY{F%w|Rwg!d9tMJFuOQjh*ZBE3uX3pzhK`!k*A<>|9?bA0!xM^Z7yDrH6z) zY1-IHz>Wqz_B>)^=NUYTDa~_E4+(p+v9a?E9SstUvZp5-JDt!W=&@DG#?E5gimM`F z>z$3A7U^j4su*Q!xIwF>heXYBKQ5T{go0keNJfNYwm#sX>BK>XqyyU`K-<5;ebGYLH-*?E#+I9zaKf9uhUbUTTnFlw!+rSyqf<4V_;VJtXW|@tOU4prb*8QJkZ?#x|6;JI+Pb zqt+U5TvqguP+!?!rIKJ2@6$Zz^pH?r**_zW15rJZ>?*^>&cvD? z617fP5{#;~h@!>>JtS&fveY2Ks9Jd~33^D>8s|8{s9NM%7-;lAwn~?Y0~z z7*%^tOM)H}>MPX~9VZx7duL069ugXZ)n6Sa7*%_KOM)H}wTpM0U{v*EOM;#yaeXHr zB&r`&y464SG-6gHPmPJPYiwT<^wgX|Q8n5v33^D>eC0U7sG3DBiQ0#er^Y_n?7`=w z0X-yY6kTeNU{sCNOM)W~>6(`=33^D3HApaur9RI&JtS&Yv%D%2jAD(MYt#%tY1NEO zHf!jdpoc`w0DD&zd;0P)s%D%^f_16p)QTF{D|$%OtbeINf>E_vS`ze-sCCJ4f>BY1 zR}OoI@Q|pL-b`a_vv8eOw;iD%7*(s+8DY0_yQYUktyqr}jH*@mlAwn~t-OyDjH=y) zB|#5~+Cex@FsgP%mIOT{YA574!Km8ZSrYV+s2!c-1fyz~YDv&TqIRZ^6O5|ewk1Ii ziP~X1PB5x=4VMHxBxC0wf#9YJtS)9cBw&vQ7ZNRoSGgI zwFAA>Ai=1pJ-rz+JtS%;eW_7T7v!nu6tdL{^n7qh&_kl0g&Zds#nEm)s&VF3>sqDD z(QZ!AGbduLzPu_DwLVwW_^Rk3QF{YR4HArE8P4;;J5|qElrHb=oS=t9J>OYg6$wU- zuZkWL^`vR3L4r}NZ?k;tat*lAu57N=+|E^>+jAo4i6Ay^=L~SY+~1`qG=j*zfsO{% zc~!Zx>=5*j$hF}Kf>F7$>=5*j$hF}Kf>F7$>=5*j(5$w8eK@}#Bp8(|%Z>&;Bs3fB z|3;AnqjF{0G`4YV+Z{b5a&6d%%*>o%RQ4E+m^A2F5}jW))^4q*6?8;p&(}1jtIEE_ zJvq|{eM5)fRguV9{|SOoxi;t!Y(;9p^){n%i=u}_?yz+ zpX(6xkjNdj69l7jf38E&LxO!}RuKQsbRxymVpQ(Wbu{Q9!JaP?52fj;jHi_=FYjw} zMb^=vheWQaT2H+#4HArsI(=nFgB}vOrs`;rU{tQin#Och^pMCkRnv%U*i#u2jLH>R z)0hZ)NaUKTqd|gExgzUm&_g2ER2>ZxjLH>RM}r;`xu)u9kYJSN68-n$&_g2ERGq6L z!Kj!M#cUvNh5u)}qlZMUsX7`Y7?mrs4nYrzTvMGO7?mrs4nYrzTvMGO7?mrs4nYrz zTvMGO7?ta*4nYrzTvMGO7?ta*4nYrzTvMGO7?pGF4nYrzTmf{5+)s2*?jd?B%Dv@I zi=rp@kUfei&1*Y7Bytb1X>5a=p1Au}F)DZTI{Bc7MD7$ejl8t^h{Gt3CG&jb&bGgi zGWV(L?UXt}+0o$IfJE+DpCA~OyTcuVv%6fSdiijsHqQq=bHdlPozf+dt5lET{Bf>9 z4~bl{b~H#ZDp!4t*oM+}$F&+uI``olk(ajJ(L-WUx|0S8MzKz3^8TNB-6fH`^_@G& zv>3(qIM-l%&h@$HmhFE|&_g0u-kq`{!KlUkNFje?miBi%EfTp_?`SYBM&*jWL(r2u zMIObJ<~gT_MD7}OG)ORtHFT!2u6eZfENb2^yVeZLy$pIt)VgFzRQbqLr7OGc(~_tj zN1p1tWLM2!64YS2Rq9Kk)@tX|tyS2Ppodp7&N&H2snqqJ+@%IRBv{h(J6NkxrB$m` z+12wcHRvHxtK#DXqpDsl3D%NY8!C$RZJrN$NYtutsX>BKwQgGy^pL1k-*JLbwU@Od z=pj)n$m0Z~YABx>*MIKime%UTlj zkf^=0;{>B>FKbEAL!x%ujuVWEwi)kXnzs*nmPEY$W=_;xMCxp*HA*b6iXIX*mK-M- z#Xfj`RrHXk5pJnLf>GnXojI>L-1$qiE2O0cJ+)T5d<_z{PF!m6 zsu)%C-6cU!&5$qusz}s~e5t{!VifPw_@0xfb=y*dX)%g3wYdgodNprXx@^sJf*umJ zW>{Vo2}ae9#gd?hMC~~oCm2;bFH3?R618`7oM2S#AT0@cNYozCae`60+WuUW9ul>e zwbUTND3yA>X>5Ma=^;^ja!U;ojEcH2crT8fLJALw+FM*|FfB%Dd>p>tXY!D!J<_EH z(_)myF1=fQNzg;0_Ii&KjM4}iN!+poc^~(>YEsievD+4bnrR_7j&HBpAh! zdbP?oI;^Eu>FN|h*-E$a6sHqN(9NEv`YLY(-Vy z6&fVy=@FrkZ=i7v5@jo@`ryzYK~IkejeL`izYB>(*@~*MBs56S(<4G7-w5OyB+6D) zjftT_f}S1`8u?};f8P>`vK3WhduWiLr$>ZFzM+ZlTk^fhq7_whl+YkSPmc%<`_iA@ zP37-GB2l)YYOWO;B3b_X;H&=3J=3~)|f`5OFbJ` z1{(B`usw%E|1CEp7-gfxVfNd;DIfHZu)UK*|1CEp7-egpL;d>jeCak13EKlY^xtyB zv>0V;Tz%i5-H#OVr!td=gzaS=`fs^mT8y%l_o4p=8hS|Bp4_4TmKzd`iW<|ayY!H- zy+wU*qLXtHjItfp!|V+-(>=HS5`Bxz)3QBeeG9;C*0J+0Xk`-kBhfhG?L>DBwa=4HjS z7-jqWhvA!zCJ%{4-Ay4sM>Y|Rvi<$T@C{9qhXmWoJRj`!ZM`$~oUGGxf}T0yZ)xt_ z4-&R+n|jW1O{9l}twpDvZ+=xI7{ylL#5OoTQ)Klg`X!FF3nGQ4FC2LeN!U|Bec`B+ zbEd^8w*O4t|Kq1D4)q2KTjS_!i#yE*G};Z{eldAS*y=^!8FhND!L%3^_vy+`KIkD~ zs~3GQwWC3TQL1nKe9%L}RxkSQYe$0wqf{%a4CgtghlH(O^!?h71_?%~R?gnZkwQAp z&^#n;^`h_ab~H#ZO7*z^rVx5a*y=^!6Ygk`V3cZT%^&AwMGpyEz398homxVIQ89bn zbO?G#*y=^!cRoQd%J%1`@oJtAdPvynMc=9JXpmr(?K93twdtPIL&8=s`rdX&g9M{& zhjlQj(L=&kFZynHM}q{Tq}?CY=pkXN7k&S{X>23w+Z_o;sSIZ`vZ<`-Az`Z}eS5v5 zL4r}^RS`WTZ0}v))N2~kRgqv6S7aIN|Jm;B8H>K}>TS)Q%INE`Zfib2>lwDeZFhF2 zL|ErYGYy@;@*Y4t5H;VGT{GutXCkrfx@w<1RgYy?DJ%)5 zMU7ekEQwlwoKLq_7E6L2UddR41fx_UTCprO=pn&8%}bX#uXTdbWvR~zdPvl2qJLHO zJ6cB7tba++L!wp_#|cK&Dtt-ML!#Cn#|cK&Zo-nFheYil948o6yCO@19ul<^a-3k4 z+GhXlF!Ye99i62H2}ac})smoxMD0u+Cm2<`ZA*e461Bs2oM2R}83u2M@%==lwIpun zv|9Ehsxg}5ie@h{Z-exZs2+To4-$;3{&-2$NG1=XYP?z!^pL30?l{4y8V8pIud2rL z^H(@8D_#kSnoBG-NHD6#s3pPcWj<>Cxg_WzQS05~1fy#Gxg_WzQS05~1fy#Gxg_Wz zQS05~1fy#Gxg_WzQS05~1fy#Gxg_WzQS05~1fy#Gxg_WzQS05~1fy#Gxg_WzQS05~ z1fy#Gxg_WzQ7h!*1fy#Gxg_WzQS05~1fy#Gxg_WzQS05~1fy#Gxg_WzQS05~1fy#G zxg_WzQS05~1fy#Gxg_WzQS05~1fy!jx+Lf!QS05~1fyytyd=~n^rT9j+J}{`dOUo8 z$>bqX&ncD~Op8(VEM!S=WT{n=qBs(bM>P_)3R`M0EkFxQ}mM6K1A8YCFS71>;a zWl}rMN|$9gC+Hzjd)CXVBEcxun7IZ$Bx)ypsX>BK};5iIW|pXm6fK4~cs6 zx4bG6jAA{W=bY_BV^pmN#sobiG>Z1$14)8WyxRFy(L+MB0i6Rlo^wV;N;Pk{(^OaI zH+Z%+BhwR%vXySlqTZ_ou=C5x3*R!%2rg(qC$fNJv|~c>@?LbzZte7QMRIL78M#K=;;xmVW+8f`R%h6 ziLw<{v#8J@K~Ike4LeP>%Wt@?NR+Lpnni^M33_@&XxM40U4DyhMWSp))hsGBNYK+G zLc>l|?dqF)B+6D)&7wks1U)?>H0(6huD%UOqHIOgEGjfe(9E=p5HAV!Z$_|b9eA3rkden!X z>>BixEsb31r^bk2RN0~N?_O}zr9b+OC%OhbWlJOX15#r|Fskg(c*}pe&F)9O-N;k6G;)@?iF}L*MwJ~Jcl<~H?$TXf^gVvh=_y<3 z=DajDMg*hE4vp`A&Tn0M_@920YtU1+G;+q78Y6;HWrxPU_{O{Je(38T?HcryEsb31 zrN)S0RN0~Nwnu&T?)|U-T-TtdY-!|bsqV*sU{u+m@t3Pd?LP97Pj(G@%9cj1sZwJ^ zFskg(_@tLzyL;9@`(tk(^pq`)TvMgSh+tINp>cTblXh=^@U0x(o?oHa&?y)BZ5(7hsN_>c-`)2|NI+tE__8#+0w{ek<=Iwj4C@c zp7||L-aX*OkG~`hddikY&OTCOL@=uCEUTE8?4-e!P}z#g`9nSv&Y8@DU{u+qsk7AoMpHMJ!MNH=MSkdA{bS6Xyh!zHRvf@8aaPRjS<19vO^tddikY&V5s3L@=uC(8yW1YtU1+G;$7~8Y6;HW#|2f^@nTF zQ?@j?N4{F+`eQ*bs_aSQYFp!o*qX=sqxdaZ*_jXjTApmzC}LGnO3SWliYj|5s|&Wq zaSeLPR=QSh{!P8mu(B#*RZ&WdQDujQ-N6gC#&HdL%2v8||NV={p#fr5QA&$ZWrv2< z#I>z)T!Wsnm9Eue|1NT9fLK+O(qdHEpr5Ywgj$iyRstRu!eR7*%#? zSkJJwHI8f0Q?}Bze#O7492y{26{WNoRd#4t54W~8j{3wcJ!LCh>mU8w%b@{cRZ&Wd zQDujQ_0(%y-J5LhRrN}1oU{79O4&-+)*}90)6lRrPM2U**`Z-8maA>=)$1-j zWh-4KgQvt#oZI;@?gU4G^n}Qd*2EJ2Y&?vbMcf*Py3trE6;u|H5i$fLK+O(qdHEp)*}9e)zAR3swkz!sIo)DRxE4Vd-eW`p0bs$twsC`tDym6RZ&Wd zQDujQt#Q`2_v#w-l&y4aEpnz`D})A!RYfT+MwJ~JwqjY^-mCYC^pvf1ZN+k?Uq^%n zh*d=?Ek>0c8rd_f(UDtiXkpr>qUWNS{15y7akLnC_z z*Py3tX=H0ojS<19vO^<#2G^jcY-wa`PK^=4sIo&Ndj{8_r)+6tYfg<3!KkuBBYOtd zpr>qUWNS{15y7akLnC_z*Py3tX=H0ojS<19vO^<#2G^jcY-wa`PK^=4sIo&Ndj=oR z=_y+p*_u;hL@=uC(8!*_HRvf@8rhotP2j#?qTXjgFskg($ezLHKJ=6=jqDjxV?;2j z?9j-WjQ5E-WAW!WWh*M@L7N4k9Tv@soM2Shy28~eXJp1>8HksU{u+8KdyYeb|zedp0cHpI~H|6 z1_YzZ4vp*H{H?n;yzxe_yZ5{C75nFX`m=Vc)s2T{UpzeeyMJo`wyPiJ|Grw0pr=n< zv|q+NbNA%k2mc~^Q4-C*c=)wHytu#5Bi>|v+KuN3disPkp7F@*cK5vEKX_k4qS=bN zxWDJu-uC68L4uw>0S)zu_Q$l!p7LSkseGh{6Pa#$dIZYK%3-x4(d_AdSiL}5Ig#b# zo<1Rsyn_p((HHCfrv{0<&+h3H(ulvUMXgpZeaEx+tJReoE3<>y_TS0Qe^)-@?>uqi zd14c^2)nAa)m_hrUDd|wu3uHNy{tA?cUwLt!mfSt^ohJ5Ypc6eRuj=^zvmmPyBDVW zF%fnTCQqM`hSid_)!nKk6VYfzUEDnNDG$2ORIet2o<0E$ZyzL@J>|plnsrwiPGq|2 zsVgCYva)jUx~qIR(dg-Z>}F-mJ!MSHf=n78|c~u_867g%=#+7Y%SHAP7H$VQ6kKL%2e8FR0 zx%rvLec;6XuzRqtyOuS^X)9^XK00@h9uiqgoL=E?yE{i%ghm{%`GZ=*tFk(_uR2CO zNVK}^>5{m(d-eXUH@&@+52nSa+y29=_V54ucXbH1!Ph?aNA`d6#82IyZ;$h<$~wAJ z6p0%yylDSrcm5Qo#{{EZ^9w(||Dk)_wL{SJw3qzk{;S_|M~|ZRSc8Psp1swcjt0|W zl-04l)iKZCT!Wr0QIBFubAlccd2c!zBp8+VzeCWIb?jDL6^X3V9SvR;qwL@3qro=v zZ*LciUewdFd~B?~x^1Pfv6|S?$acP0y|O#Fse5jE7;9VkdK;WPB&_yq`t^!wG0JM? zW>$Bne6RT-CK#1>wnJq5a8I_VP2NqlV7KQQ*&Dbg`x3Xat#mZ#A(8!9M}q{T*jM^hZT*7fEDJtXpOb_mw$tXF&GgZZ0l&_g2YvD0IM zQQ2-9u?=p!W3A3MxY1QzUfm^;ZQkify)>8>qw+p=2-aOAruxd-GuNPpgk7OVwT=b} zMzIyx`r{{GbJKU;&7arSx^}Pf$@*&cMfEE=bM_U>fM8U!HMjfGJ6?C`t$*d`OIGwW z`y$46X^e<$gML-bmd0=X;4POv^y^QsdbwKB)9j0f%(>HJf>F(u#slB=@w->u?JHb^ zo@QS>WJ#ySh+tH+rSYaGJ#csF30g0$R`fLcqQfyKi}Q$DR*}b zdYXMvy-&_$q%k5G)of|}&0QY1yYc_|%S*}!JSRbr8eCA_BFsj*+kMG+(?Z>|8f;8x9_QgY+okc$S1f!ZQjo*0fx9wi^ zCvR{KdYV1$!(~23gpCYZJ9$*Iq2c!%5!q@zs@c-Wp20QfY4+4#ZQ`Dfi0pkls@c-W9?sOK{>q|m ztbWjm>>u486O3xMG_t354SJeAjUTBoB62kFsAfweM;zCnr`gjum>MG@M>UUXwls3A zbq#u&J&ot7F(Ptw_NZn{BWD1vK~J-%c}Z%Fh@543RI{a#b062Br`f*axsTlz^(7;s z&F)D^!+M`}^@*JCHrxBFob_ja)g`R=nWCC44eNc@)wk2rZ11nM&$x^BF(RywnxdL5 z4eNc@HAd0XY##@6<*j^-2NC9LwVTW zXP~Fq-d}0oFUx8~Sno4MHCr0i`>bp3Lr=54ztTRV)h*>?L|7j+MKxO*)?ck_4o6S3 zeV&;68qydM*85CR&6bAsKI@u`($j43uX6W88Y9AbpDC)@(y-oVU2|%Bn(h5n?w3eo zL|E@LMKxO**85zjwE;cN_WnxyC3!zag!MjCRI{aFz0ZYOt( z+0wAy=jvLk(bH@`p;1|lh_+rP0S)gHGisCTLHln!=S)5O|3hOzFsj)oD<|k__H;i| zBg<+*Wa)ZTv!#)D&;nK?f=xO#eFPZYuCvukIQO%Y{&V5{io@P(awo_w7q6S5kw0dqpWNMwJ~J z7;(1rlr4?yS5gCncD#ICQd*2EJ2WtIZs{po8riR;28dNfDJ@2o9U7PcZ0RXm8riR; z1_I85PubGIe9meK2<>?JyiI8_ zs_f9f%yLUl+0w{mm2UPcsR3eDQA&$ZWrqf5`t+17 zjqF!aV?;2j?8--5f(NlKbkJ?YPeB}O>k7^aAw5)WesIo)D?%=d%Nl)3* zu=}r*1MQx72}YG&`DlBu^pq_PtD!n;Fx~S$!KkuB!`k4qhfGh|(y*3R`_$0}y9A@k z4h`!WroC`_%9e)p7`5MS8Y6;HWrv3KaMPYXJ!MP7dcJyYU>YNWQDujQ_0-d|33|$w zhV|fj9@YBxF2Sg>L&HX#=@|<>WlO_GqCESdK5;}as_f9Pk#l-hL{Hh$un~2i>p{~P z5sWH3G;9ViJ@cZcY-!lcpq{Il#)x24*`blUQC9a?({nX>DoPqQ!?AmDW!{ew!Kkul z8f$5!XCqJ9$j3&u&#&}EaY5u&c~seC9MM)q(%;?PsJG_rrR>rlNK5sWH3G_r4Z4SLE}y4laC#)x24*`Z;xB|RT>4SLF! zMvhmhF(MdMc4*{STkAoMsrH*OpOLvOjU0DVV?;2j?8--bf<;f+(#V;?l#f2asIo&N zXEK*o_D4_I(#UyGYK#a*l|5-__gorV^XSBumsQ!B5ACEkjUrYRrL^p-rl_)~veJIL zYtU16-Vg1hx3VfiIrnsxmX+=lRd#6P3|aSlOHbL-uv(&>^wa<`t>~2&qsp#)`0lya zU3$uvhSg*3q)++i6O1Z5G;)pO8uXMc4Qr3NSA#Xqf?!nHpDHr)+6hzoHe{ zM)tH;TM&#YJ2b3^(|)^^gN>${mON!EUF#pUlb#wQf>C9MMy`ZigPyXbVg0;T$f+?R z7*%#?*odS3cGsY%Y-!kdrJeND7!iyrJ2Y(M)PB2b&{MWFY~0n3MQV%)MwJ~JHUrRp zyKB%>wlr-1pq=#87!iyrJ2Y}{$u;OHTN*YGvh=S^jS<19vO{BK?fbib^uN7ACo^yV ztq(Z7@=u;*Y2AGG^bdZ{;nFv6-Tsn|zBC`U#e<-S#QPrbU?YCO=`q2mx4iuRhhO~R zr*{Z?NWApz4>~;mo&Wv>!KnAW*1xgdA?P9T7617GhpXQDf)fOzuDI5}0M;SsnG^ad z`wLGHS6tho{`L?2oA(`p9unXDqWc~`aQBy-AQ<(fpLwst4?gX=9fBSbfBoD~JAC;+ zed!5;QCD26Z?9k9A?R5W7f%pDN7T(P`QHcmpoheLA9nXaK1eX?UVrJ|Y3N)PJtThS zfuB6MA0!xc#kKw=iH-(6b3)%^>DQ~4))m*bs0V$jf7zv@K@W*H|J^4H+6M_nJ^J2v z9kg?LNPO?d-f7UzNigai&$`Q?zoLi41OMNT8}wHs7{_osj z>QTo8qyFhn`Imb)>W}9HJtQ9Y=Gz}$@S1NwK``oyYyAtv9fF=YaeFJPYfcbXT-%~_ zwIBN9$8-pKNJ#Hn9`mRZ1fx{ykNwm~bO?G#sN9}*|MdxiQBfB*9fBSbasMB5f?$;D z^bf!5p&f!A5~|1Ve8i`nAQ+{#X8;B zl2~;#NQ50x8nyfRpofIU-F`kuFiNwJ{{5hbgys+Z`$2+HnnjK3RrAb=`%g7yrN61C zW?GspRlU+|u-`uDA))zPzkQHklxDU4c1{lo%}e|3oCKp{cE0J<5_(9){JPg)kzkb8 z4E=tW9uit7^!r^BjQUUa{j9wU2*Ma4M(-+nG+Aa4C0DwTa>iz zE6$z!K@SP(^~ZA(jN%$jmA%z=dPs2H=ETa@gI5{2ZmsB+v({>FIg4K6n$2o;%h{Zu zXGy3hI!3hK=a#e9+npy`eZA$ZwU5iasyR_@{=5eB(c1YfXDpF<&Rfm6#n;YJ!!P%$ zTHU?nthJS6SH&on$o#6>y}jkE-Sf-6syR{h_}Epox*K{ihdWQ`9>l8pmNQ*@tl}^C zsz^jBXrJM{2JaxFSR(VXQhkl}Yux8pFJJCesb(~y*6PQus;$qX9#@IXud1!+qD|Bl zGJkV|9<`!5aq&c11szc=k-0`&JKb{D)@qkqR&%1(pU2CpMX^NYSJhT2x16c)z(p=7vslyqRqT-Icqch%e^WRZ7p(M zgEf&+ERlIxvDa^N>dU>VIZ^9`V^`JI22qb=4kzL_p89h)z2x@St*`lse|SZ|P2B8b zVzsW->c2ki>6iZe;or0V!`po56>K@pzS+l*whuQVT3%5A=B{fW1I z?<-mq`>UI6bgte73su_SZMg*gp4UL;jt^$8@!61W=E@S>)LFC3!=@bNk}7mhMn~#SG6e4 z+oQj#mG_uX?^99DmPYn)JL?m#qNmx>i?)4+5z%J%B&3l&_0IbCt6CJ-12G!3{gM%( z(V(K5EsY#;b~fT%MNhL;R(fKhb(GrRh+tH+Q{!s2DrwNu?3=OjN{uejMrsmSRu|N& zR8}pDE4rJ{+DI)8^=>_aQO%Zy`dqat-E(@Ht+J{afHXz~qna%ZjU8%Ls=M?w`(~f} zw)Qb1+FXl-G&BaPRjCcOD9%N0#_UY_7!hqoM#430ELS^JU(%vD>$~}^&CXn7KrpJ= z(y)86R;yB%I6I9G&@SSp72j)wIEc| z71eBMBD^+Q*1!I};?Np?RokyjET5*(}B>?+)C|GE69pcT8t_?G_3vY{@mK(SK4}zp0bs0JuwN5 z5y7akXBsz|hOGzNGnTR|A38ZO(^wF?s){OmR#rY|pr>r5s}j)@tkB4^S`dsXJ2dhR zUb1_B6+LAu-MIgo)EE(rDmyf?Chn~6UPVvY(oj9t6UE5Kh+tINp^+`h=c4qKt#s8M z^<*?OMg*hE&ifI4$8fAR6W-9szGOi#s_f9n9&TrSqRrdeGvTt8uKGtk zsSb@1!KkuBBl~t=6zE-2BY^59HRcTm@)u^^07*+P9 zac*^YrH^VAC5<}g5cyEAP#P7bv=~+PR94gKj-IlWZk^W%4fR!Ohgv~al+t2U*`c96 zSFK9-oSw3kZk;;`jS<19vO_~-hgy~DEDD=* z&=?VnDmyeR4{Nn5^(FL_t#s==Q)r9`MwJ~Jb}!ayRq7MzDO>5*xvbC_5sWH3?+4a{ z^pvf1>wH;gXf~#Hs1;;IDJ@2o9U4~C*J@Q7qv$DH>DD>9&=?VnDto5kV=X;pS3Y!d zV5YGkbX65q_N=UY20%~QN>?SK)8CmJ!LE1xc}SK7!iyrJ2bK; z`W%j)vZbMVtdr!Cj}gJBvO^5PJ%0PsejqhQ1f$B%`w@MK&#CDtTN>(D zzVD6CsrxY?7*%#?WDna zMJX*tm7QgU^&mZEM_I*5^3cdJ%2$vTrL`CL?dN5XZ6{U1F?zViaaI!}E zsM&<{YSa(@|pJuf>BvRI|Mx> z@;Ubjf>BYY^==XE(A(d+x*MJ)u{uFSx)GJLvkpNIiG1dLf?!n6mO2DIB=o$+&NG}K z7?rcL4nfbH@aN|z2t8f0a~U3$bH)xq4~cx{eS%novb=RFe-N`Is`p)!k?d?Ao6Lr zN9FvwL(oGapL3re7?tzg4nYrze9nD>U{ubpI|Mx>@;Ubjf>Al^?-2Bm$miTA2u9^B zyhG4KBA??rH732=zod zy`#UiwLL3L~G~M?=(6@s~Pe8 z!KmStr&Cwe>hAR0gN_Evs+M=R{qz!AFY-sA646r-@z8e5}9l0 z9@wc{zY^WenB8A)S&@iR(7gTFRWXVsGQTR-S3BA5X|;9j={$WW zA8kc9oxt{}%e#YZ%~|`xJnB`<=Z;-f zTN_MgdGo6Bw;BEnvfn1AUyLM?CxrZ2DqBvor(dNQk!NeC6Q(U{`c;ZYv0s^fD>MCm zF!qqaO#mEsFi%^!upP7!hqWAmJM4ehpZo42d=}sI2sB5uMwvUmO;}sAfyUO7`6E2V*R1 zQS+VjG10~)64J;Mjee4&MNMxh@bYORwem3{7}acP=tP)KVb|{mV-JaQ20eYRv0WM? zf>F(ehW|E$o@U4I2iv?oH5NphS&%?k`3a#GHT@3K%SvU~)*o3`3xZM2mPX$5>Gy** z(`!-n`@vdAjfkiv5!GyIWKG2H2cv&&QPZzwt9?Y>T@b46wQ6j(YeXCLvugA-J6dg9 z*Jc}B5N%FPLK@jKOurwDv^Z~9y=p7(F~O*2OCx(Y|1B9k&7OXRonT3L08HlCA^M*i}}?|F;joIz#9{lpQ$sAfw; zBZ1ms{eG}!6D?}`l~CqmM6|gU32A5yRI94r4_5mi(dJq{Mhyr?HQP1fH(1^?(9`Vc zcV3wfjs9x6^^3!r8@4$d32A7Cp;py?KN$TLi8c>bK1Kwink|hy(da!jJnIY^$eOs;jI2e~nj_LxJ#Nnj zM+Bpq?HbXdd@f2)v!m6EJ|@3!-PjEJ_vCLs-;7j03|@7D8d_4BchqOuwhjB2(ta>VhK7d_3cad4IS7!hsV zMj|!NoflPFH4a9)ZAGShokPUDwVxl-O*FFh&rzkC!KQ6;48?AQd*2E z`~Pp;43ArfVHliII!Z@*qhy4R)X^#k{AAEMp5H&-5g=^Yro@D_hI;hXh0Xln>SEnj z1xj)0JF&*ZNEEg;YJz9?I;RI)ap|A2#>7Yzwl(Txxxc9NU@ILhRT zgR8f8uN5f8rJuzNtHb3~iH9#pYzr$N&Vk8Q?p2uw(aCP8r4N!{9{|VN} zdJvRiB?{XbI`OFsoB6@j@w+uZDK7tuSYu)&3cG3S*^KmHb04eI@waJwFmzR*u-jVg zGedf?6;~^=Iw(sc>p@V8l_+d$)Dt}OgNk)$`1!v}V`3x<+Zy#I#{A$r-Ydt|d#ryH zy;c(=QP|d~FKVAf(}S(J`X2Sqs5K@=qOh$|nc++W@-HhW#Z_L>KfKnM7>UBRMrF7& zKghqupcGg6QU6q1V`3x<+ZtKjr3YJamBH7%L1|2kL}Axj-KGH*OCC_t@DBIGS`Cau zVIPfKb@#J1KuLo>2d`DlW<)(`MxwCKTAk`HJ=ls%zlJsH%&@C%P>Pi(Y-_A1*yac6 zLI9<>^qp8^Vk8Q?*2)t+XMXT{uXY#weg^c9{qOh&8zNk|VrUzSb=>xLH z#7GpjHCAS5^MiCDfKpugnXEA}5`}GzmEmslgU(l=6qmj%YfOwpVb}AxO#_m5K`Ac% zW!A`g5R_si3fmg02X*peeo(v2ok5?RH6}))u$#u-Ytw_xeP|DE8XpW@J1A^x)Sd6@ zED!nQ`ei7`Lu^A#v*=snii&i64f z5`}Gz`l9w(G(FggtM75mW0l6lNECKG4`+rmKd4ypfRcu?&zi^Lc?^t1VOygz+?gL# zEO|glL-|oPgV$AyG zjKV$|w|ej^_CYhW?_T%uiq0C{EvE@x6}!GQ{?(l)BR!uC_VbBhwo!Q+SopXqy|0`H z^#knn4q%)LpIIAl&aPm&=&PY!({LQ}~RyR?(B3&bMROZCg z?u_(w#-0p(xTx~a z*HB%{If35;t}ObLuac3!Yjlmgk3{8)bOu$mu7t|_|F5bu_GIAWT3x7Ik$zQKnPw%N q_tzQeNd^_Y?rCNuDp#a4GV5o}ncAI^p3cZ>dvS(u@IvK^yk37w(d$D1 literal 0 HcmV?d00001 diff --git "a/yard/EWei/STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\351\203\250\345\210\206.STL" "b/assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\351\203\250\345\210\206.STL" similarity index 100% rename from "yard/EWei/STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\351\203\250\345\210\206.STL" rename to "assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\255\351\227\264\351\203\250\345\210\206.STL" diff --git "a/yard/EWei/STL/\350\243\205\351\205\215\344\275\223-\344\270\273\345\212\250-\351\232\217\345\212\250.STL" "b/assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\273\345\212\250-\351\232\217\345\212\250.STL" similarity index 100% rename from "yard/EWei/STL/\350\243\205\351\205\215\344\275\223-\344\270\273\345\212\250-\351\232\217\345\212\250.STL" rename to "assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\344\270\273\345\212\250-\351\232\217\345\212\250.STL" diff --git "a/assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\347\224\265\346\234\272.STL" "b/assets/EWei_STL/\350\243\205\351\205\215\344\275\223-\347\224\265\346\234\272.STL" new file mode 100644 index 0000000000000000000000000000000000000000..3b4d8ba168af146b913a5a0295d8e2eed44b05f6 GIT binary patch literal 1443984 zcmbrn3%K=FRqwy@hN4_FH6fK(ON;*KNqtPE!@JgRtFKD&APR|ziG`YnG!*j!DhowV z5+Z_%pvV$M6UCO7$Q$ok+q{qg=Dnj-3aChm2uYA0`_D1vm~(vQZ;jvHo9C?O;blB~ zjL-be`|rBOI`+^1?72s6`^NmUS6}+w2mS5$KlxwV{@*^AA2Y&dI{t$%Kfk-?=55Q- zXx^QD)(g7PDBG7_dQ7rM`gZ`M>G)rcd{OsTuYLoF)6~wyG9W}F5fj%qO>HC89^sQU zQmxcuwNl$^r8a<6s{YoMT}xG0`?5>#TTZms-*=!KknP=Uvu*`HEi)G|oC} zx3yi*_)Ycv)Bm^o+Wl^MutjZ4HH>PN>Rmk~q!&)V;&%cK5{$}yI0*=P{`qNptUcx4 z2i}TWk+}28d#v4X<)MKFYt=?c`|_+D;WHg`%sER$?|oPOMWDfQ&pu0L%#ju~q>*ct z)k#Q6yWQvLK!XIM4*SwRYj1l0EFkD1G29LkjQZ4$eb!$7wRxaH4+-|$2%qVgt4QY6 zF|YnhEq9ophlI@O<1hNFpjIRpHN4L0At5X3rn{aRXpmr(tjDtRq2X!w$;9)hh~)}#>^<(e_O6q!v%fo2G%~@c`QGHTXGDX9*g5JePyJ~+s+DmfK~JVh zL>eTroul@9&)EYS^sEw*28nFvsC*oZ+Ck4M5owUfc8=_@oz?#4QLmkx_l?gjRvCHp#=$l&G zmY|2k^B-{La`*in6=;xP)cwBqlf|pMYXS{=NOW&HaJl37F3=#ss4sry{)-Fl|KmV| z9uil7>T`<|j@=PxkZ7Zh+c#ddqmg?^{Os}%9q^f7JTA~6!KkD?9&AVTka*u`uNZgt z9B4-+7?t{PJUAZJL*iKnA2xaRrzb%>SQewwT$l{btLh=~fgNw3T)g)q0}YnNsNpq8 z4~ab=_K%a-K6bxAg9M|v{@eBO=ASN?kG?1$xBuv%uP=Aq>u{ZY_qk=i^#@;eNiY++ zGjKf)6ZDYy#Gdb2{`@f)1{x$7#oD&*IPpXOx_sNs51q(Pw#&9|{a0^1SnXfD{o3Wp zlP`={cQ|@T?6qUZ`sttk(k29>-hIiBm(RK7yzQ$R^pF^h9>2c-$FF?f#ss6DzWa5{ zOaJZI#VXNyyj;`UgkaQ_$9;FX=c#uI#)BRb(r@>^@!(AeMsbdf@R^S3A#w7%AG!YD z7o8PokYE&N4GC@l96ym>v?#SXds>1X5~ip0Fu^F!v6iqSXD7A#`e)y= zJn0jk&~ojVsDEz>dPw~ASN_-X=dbya(k;Q3AH45Jm*0BBJ2Z-IY6*HsP;Z!El^^mY* zd!WIx7&SZ|^pN;+KKBVUNHB_Xp=}5Ignea4gFu5G5@~EEWmdKtBp799nSlmtWk)rQ z;>fld^pLRQZlFPeQE4uW%UozR=pkX}4}k`WHtM*vuU|h|-Ko>rQuUCq^PoV31fw{o zSK3i$I|)0V3p7|3qd4d~!Ad&4HW!Im9 z20g1pq(LIvB}%Vr0}Z=>r5?LSqBdvG2%mN)lCZliN&`se46R4+;%L;?G)5yQ><&_( z!Lk_Dt~9ULG@YI5U1u#z?kA=@!fM-{;y}ah2&%{KEvn5v9N{w^(?i1U`zj3}^%V(5 z+1<~8pofIrBi)2x)S>zQZa~mO!tV8MLbOqOpE@AyuCsbb*gfk_h&IYcc7#tm<|ITf z-P0e`7^#O*oH39{Bgpw<&nB$gt<;KyJqy{SR*bS|F9DIC_ME03yKk&E*Ubo@cAb;3 zJJ3o4NG)esjN+Vb33^D_eepnp1f#e%TMhP!Xr!lBT5hgw9@&ppT6vC>kBOt@>bcJs?tjM=HC4~kzOhSvKE%7jBYdV~8#N_t{MEK` zQX7De;0hs68aH~g==bH1Jf0o@dM7j#Eo;oMrsWQ^Z`WXw2y$A>;2)FkMB~ptK{G#i(4X$#QjGk&u2X z&u(o_hlD(9&Ke|SY~p9aEQ?Wmf}KjNpXr$OmEJASfmz!co{YBTBxE%G8MHGk!6>%L z<3+=wCen+hp|;gZ?Ut~0t{z*pAeI5aJ;VCP2<`QN;O;}hdU_LrQN!(^hlKT2sG&1a zJ&a->j_{d|*`qf8N>dwvkGV#Xu$ixaA0`-Ot1BQlg1IJn)NC~egtRa{YgUi6JUuy9 zoAd~uG80R=PDoFuXTnMYs4dR~qik;v34QZKJtS-o-h^Nj&n4Pgafavdm}Sj&mR5JbjB~w=x)FEogME{o9m_}9`R5)B2P5x8SmO< z?Z(4yy9vRvNL+BuE^Fr=@tWYyHVH=A-H{s|0)W$=|yD+BtVW<5u()iSyrjhqbqU^~FlJ<6*U$h&rP9q}j6!G}wz)_r=ynkc9Pu(rwE*f{e1B4hU<9)x^&qtPcZ% z9_ydw#_ebcKYy^<6KK%GHVwDq^tauT*7roqdi2L{?$WANJKqD!=PPYr(L>?`55Boe zt2S64=F#M*2}W6uELUecJtV9b z0u2(3;<{;T_2Mg!@5=erlfLzeuAC?EE^bTEL*k!bbV6FK`5dJs{^r7ISMCTMc*wLX zcL#GxqseN^=^>FdCYun9k{YJ#oq%9{MI*fmFu^DpoAPdbOI-PsXVtaMCmToX{F8xIOAm>6oc70ct+X0DpZJ{GqoP;VU8bX! z(?cR_PbRB70|`b+t;)XA)`~5c8kXITZE6X6NSuAva|dQ32}W@hv>Nn~_?vBiwuKeN zD1HN@)nK1|^&8KudocU3CFmh>_F2yy*nLPaiaio(EGIIyBt$RXMOhZ3hG!zbS7P6S zQ9Z7-wpR3zke=Rr4Kj*7(rVB{LdHMdOGq$^E3MVw`?TpPP#U%TCNbZ|Yl+t5g!TGz zbq$hWRC+gV62C!54~g^!-K4zl*VZb%t2QZbv88v)Cgp82>ye;V^pHqzi%sJ9$Vf1X zHEe4|4~g{d*QC6wI7~2VxaH~Xrb&4p%Je2O27I5T)u4xjjla^v1fz!ElS%I5a5WdDF4gpoc_TLuaPrRU+>a>20w|c~8#cSmz>)@;J{Dmb^lFw zeMfitufJ}*N^m?_uIU8?JpmE4g9O_#Tq}A4BG4dVwnni>+VNojj7GEW+Be->?-a14 zmS{arSV?*xWtd=;)hg)SzkKmex_3PMHcJ_)Bj0;{cf{ZCs&>AzT&mq_JpQJ4b>G@+ zAN73gedl#oJ@4LX=dpV8?}d?g>FeH6`*4_G)bKjz7#w}!k88_^$AcacA9%xc1HDUvQTzSD zkLqal+5yks-RXyQ{8>^<&_m*{KXPq4N7=Sq-5E$QinFKHpohfazkmLK1_?%SPPZC1 z9uujrtrfL%ZSyg)CFmis$31S4y**fi^qlz08|qPpB@JtkxaMzes7JVAf>Gao?+x|% z*b?T^UCju!tyasS5zOm@gw;^#R)b|R%6cRq+Plkszm+8oYm7!K#AM@ka173W_6>66 z9Iq1ekQnaWH~-7^a^%#qKKzL5<;bb~`L5UfM2?(6%Q+rwt!W1YJpnP?4lRpq8m<*R z0TF1BFk7S8Bkc&Xf710$_q?l*)*~lNYKhk4gq5V{D8mG!tXA41Ey43a+t0NfcKn#E z&Jub^*pXoqf>E}Q4HEf0nuHy%0)iepa%$ApG)UM{JJ4WRjIy(VfUsjmu1P-nsGa9= zZr=!>@}wbq>`11B9pTglkdEgpi&1tI4G7lPju{%o_O%-Hkg%gqph1FBtZl174+%Ra z1{x$7#a?eU>|W?nX0_c_RXf)<@A)l34+*UNJ^qu9O?KIP0Z_X!ERTOVk!EJm@0kf`UPOD&6pJwq7O$ONN?Th1IZcBfg( zwR>lQ20bL~p7kaKqu3)OeA?b6VRzC44VJ|y&S^-b-sQZKsFM9+YvVye^y2InEQ?XO z5A!&+wW5cF^g^8df&`=NnNHAGb{AMZc0XBdyQ32j^pLQ-^_vikvL^xoVNbBsWB0$+ zX8T6?Ovm()usi8W14v^|f>Cy#DIn+}VfXg~f*yO)piwNTtra~a>?uc}L4r}ar>6ly zkKJRx6}2K^ck2TU){0U2@1sE?dq~(bgiQ!WaZZo$nT|Q*>>j(8yR}-8u)Fn})=KaE zYgC?ZQOoIJx%Lbp&>+Dmd$JJ_e6yc#Y^7`SwNZKzX!Y!s9uj=ND3SHkeq*GKQjO)H zhI&ZYHwiW&7-j7X2z$>`J@$U8>B+kv%Yex5mt@Z>5se@TdpkwTwezk(gPv6)(jbxT z9K}0&BYdV~dPodkZS&1uzO!pJoUD!@J*z}MJ4dC`zDpw8Im&7nXwb7tL>eTrouhbn zr>zw|B!;gIxCS5d@o9a7?gI~=4!jTdsU2t5sOKN`mUPc5zkkQ`m9|z-d%{We9XRTZ zMz5{!$+ZMMB%b))|1EE91=qFny-<T&GL9x8k~XG;-qni_VbRD&5wqZJ`oc6VncA z#g<=m`K#)?d~8#zK@W-3-*#f{>0yFV9L<)n-qjXbkE(6jlhyUXK6%1J-Yo4y!N2>nePs-6=hT@vyrSqKVXJn$ILov-BODa^@|ze$z_-K9bK=|4kbHuF4GW#>_g;0n^u@$KRQmb)H+M zPoyZze>6jerdj8ig8GE#VVQNFxnHApaueV9k0 zj0gL~GbZWS)IMwp_AUv}A=IxG2}Y&bTBfN!K@SPfS+o(ss5DNNhpA66%Cjfwm=6#v zi-c#n>1&W+l;_Lo6ZDYqtU4PJZB)q=)F(V6(5xfjxqdbx7{ztd&Jub^c+R4}1_?%S zb*aWQD@_-iSDsz0UGr_NJRjMtBjK6N`n4j#D9_5)C+H#JS>QGz80FdC`UE{BJRjjk z1fx8oV4t9egl81&6ZDYq42ByKjPm?|eS%S*wQ$xA6ZDYqe1v@s5{&YUf_;J>5}sYq zh&p#Y3uT?JOF4?J5H^9Q3wmr;Dq-_YZ4I94zv);@f>Eq(OW0ebOR0&!lRWGE-Qj-A zlgIM!&N|zv*M+ttgW9=1`QPb+E%&^fZ7;M0TT6o4!vv%3Xt$Iawgf#SR@yPmTs@P~ z7TWPu?L=EXSbc;y;(%tHhBO0iEsBP24Nqj)W9!TP`H!hZ#!t%?64LVsS-!x~!dt!3@2X;x}AEMK2S zkXMnu0>BpB89x~ohVmJ>{CV%hi9UTKFx(*->wEU%u@7Oekk2}b#^ zmGs*|4++bw7if@Rl>dfGUxOYJmRB#(Akjw2bI#KOB0o#b9uoc=GyPhTXrs!r)R>TG zf^rw9{MyZ|vrK%0waNseEMH$h&||s#ENUyYB4N4v0*&1ATq{Od?!JKVd~LJN^SHGu zc!W>8mynPr%K6Qje(!QcF^a1I66u_p9uk&`FK7n|MsaPn8vfLK*7?)$((>GgEs@)i zJtQm>Ur;L&jI!KY0bwh3A~Vr;2DPnyYLD=lE<6+0tn-{+wH*OrwNeiWt6@Oc>{E}; zV~f(c8xS@VR|s1xn-Fc3?hFCJzGDB_P81L}YU;7^x2U0ZFv?cZCInkf!q#I@D-w)i zuaEGVF4#YwUsTrJP+!qQLQ2ZtEVflU%|g=!2}XI2*8V!Dhs4TwR1Ff0@?5k1TG2y- z_Cb=ZZRUK<&5B2<= znT-j3Dx>Av8FHYJR#aM{MMHmO$_TOJ@o zcD)l2^pLP?oJ|Nu*%eYi`1@D0&ND8`_{-Rg0)ieAp5bwI%)Kl|c}B@TL62vo+-j{z zcy7zS2HU}?Jdfj+Yi2a<6B3?rb5+9$M)B+;^>Y2ld7`fgdlPUX>yEXp;mIgOt}h9H zH*U37J|2wXTxd18TiUs=)yj9imf&tc!ZTH_*2>Fb6nmtv;eAEI^JkjIG;`AhJ)Zls z^zL#J?QpI^!t+_Kw!;ZVc{a>`t?2PAn_I0F3D5AkQLPxo8PoPIpN4Y}PEWS%w^I5V zt!G^{`o?&Cwc}9=E1_?&l--B7gD1U!KMo^AK z@m}H{66x8LWyKh%m8vr;Yec1)`0T}n;(oPxBLKg}w#i|RSU3gLNX`Whq{HC!wE&d)?@ z#bdjDV@&^^>y!VTF6bd)->3=*`!1P!GLdIrE@=`F^pLP`)CGinCrUl}+$U?;_pt(k z9ul5aso%S7hke6M%ViBm_)Hh{knjw4eGL+f%74$R01|1o(?i0(?WQ#xCKxq5f}ADx zJufYn+QS+o>>FI0)QV9&t8F#tAz|P73N%PCitm248k|?6kuzA8wUXypOK=29NH63} zd>f59qgH17G%HOP_MNDStXliFliIfa)y}c`-@2EmhlG6#%86+q_zs-CO{Y=p!yH=( zdPvx}#FQQ;7`3%_kg)HV1sW`iQS8IER`$&)Ez7>!r*FcA56{Lu>pZWw^p#$bEv4VALi#@$ zLHCgGJnI_~j2gazWR&NKueAzV-j-Ez#Lqe_DZRNqP%ABqQP!sPc66WcT;8+J^LN); zEmsNl6$#I1-q#?(D2|g3g#9Dqp;xJ@?%9;LS}PKs-F%~3wNd&z1nG`gpI|Rq-L*&C zaq^bbc{P!;NLVifput)(YHN2UNZ8nf z8an1$t2XL3YdL4XjmI>%CLIlO&UP)!bCS=H@x4ESo}p)!zW-4&$yZ{zI_CNAS-yfK z;W_F18YCFy8Q=TuVBI|%d##oBNN#g!xoN0}glB>usFf0o@@(^cg7vi;E~J0hzOYtH zi6Y^d^7|Sri&36oyia%@@>%Cu%w@Lwj?vbN9ul5sy{|!nQQTKlW15ww3oBP=qGy$_ zeKi@JSLz|*dGGtR;+Qjvt032>)QY|9-@;ArL*^`CI+`uvIhJOfXP4S)J4kpIu#MWm zD9<$3Cs<$4{8ekU9PC~7knk*5eGT>%qdd!1pYYsGv(9rm%{tFIWyCc1@pRFywUR5W zwqr8b4)d%K%Z&-Pi6fiqlmAU`2-Un}wI*8baLY+BYNh2SG+odW5W!3&VYWuG*V}e* z3_OolFdkv8NLWe1`4wx$D9;vL2+s-G*PzFLKCzS^DF_y@YGt^IZ1VIXxt@owcnA`oHO7mB>+^4YOY>*4J~$l-`Xr z*e4`BQ)OR+1fx6~X20d0k#g2~Zp*SWM73g{knpUY{aTS=)No(1zMheCt9?bnb6fUn z#lB(`Yuk=FJtREiW?zE@quA?tLS?1t!rs_f%38DcJ=AWmcXPD-+unyGVQ-Eo?eTqr zQCTCO&qYM`kg&HC1~oFlD0{adAn37oCNyemwIX5fYXllBi&6F-NI=kI@0Z+)T9L4K zTLKN%ic$HFUOXQ9E{>K(!rrn8HJo6Sz55do_71grgh;!k+4?$McKI4ySLuIgtT9 z%Ww|~&w$$RD|?c!W!XCcYG;jTJm?`|?`U|frX&62cR$J=ZcoECYHRHvVNc(c&ZXyn z<^0N9&M14@@5Hna^w`@18pV=wY$50&;W=#ky-R{o`R|+cE(v=ZLTeb+DwoA5j%-VC zr0ks%Eq80RB4KZ*Y*H&mamQ$DMGpykXC}}f!6X9VK&Mx@Va)$7)Y&@zX3aU3dmWdE&0QYW2QYTT+gef9o-7BK0Mae3rX$ z<63!?X)J5Yr%51v(v>jk>-iJ6+E*kzcjHF2VibEM*C+og-@)>_dk(@{t7UD6VYRQ+ zL&7vti37D#f>Bn(fZ!_f46)@d&S_wX;+M_Eou@dxxVUP&2(fIzm{(Ac^fA<2_pvUbtr|>YrOs8&(#{TCVy#3oBJWe&}al2-)vvv#- z%&h9RXzcjJn+~|?NhhcVJ#NoBW^x@S80EHT{O5(oT>P0+vj#nGw;5@N3FfVJTQr_{ zLAP`5na688=y7}2F|+P4!6>&yM`ik5jbL@>&2 z)%fji@BG8xc(!WL0zotkJ~k?r?q2UTe0HRy4>X6#Mv=qe2-|%$%5BlG9Zogqal7ujrZGg= zE~-&(i-zsgszHz2vyM4ahY3cxEgE*jQ4M9?y%$ z0AWXGjdEKw?3_V0=yAKAmzc&7VP_c{<+f}o=z+!hVH#!(G=+^*MArZGg=Rgp%yEgE*^r5g0OU9SgCV~DV; zJB@N%H0%meHRy3$jcRWwMn zomZqyE&OB)b<4H9mb=LV66 z%_Y@{iM|F2x69MMNWcuZn4H9nix3)xsg#Xso z95o@K?YR2OJ0H8_xvD|JZT@DMwgZI!a@M^0)i3|MXq@GpTf(z(z5AF{abmmjGbB;3~DE}DGn4eziqC*ir<=FRV``QN1->t8--apj}# zr5f&;%WooCxwFpmkx4s9&=V7)@rAb>wb=W_@9Fg*3AfWV&WHYW^0u2FYV9CFPfUo$ z;h%re;+sEwvucoVd)9eYHfaY5dSXH}e)~tSSp0O)+o%Q!x6}H#BH?z*y>#4n zCwrcHmt}4T33_5eG=BZ$=Phpk{hg{o!fj@)lXj5staWqLgoJ2(@&7(`aob1TVJz(+ z;r6Wa{BWW{f}WTVjl1qQS=@5Jd_R$d+q2H|(TN5LdSXH}ZugaKiz6QNIBf?Bx0zQ@ zG)Q>Hy*X+^LNp%ukz00t^A*of4H9n8I{*D2(I7!jOo+xoZ@ggV(MRUzA0*tKb^iN5 zqCtY5m=KLKc7M>$Cm-^1Z3hXrXPy84k7$sfCniMWn6E$R;RenoIGzxLk zXCC%$dSb#f4iJq*{5lD@wH@|bLZ+dF%=T0+Jf$Witgp70z9Qkaj)(o0ko8q1QvXy> zOo&Dr!R=+tNw}@^%6>~oG)SazuAZ0>jWiRtm$^&AZJq7*>tmupBF)$8i3!n2D{5TU zAPKj1oiBg>m5&kPbf!Np*9Iiq*6R=Z#aq!Jk*)`-CniMWlUILvd%4CT;WmH2Ry0WXuhHri zOa1L#|GQ|UE3fV4TFpIrRaAc$H(j?a4mjn9Hs&Pgaayk+jnH;{@WKPiH75zTC8}Ia zYCAyC6B9z8|H=1<2iE}x;^jgyE&;HeS)5tkXl{$>XUX}yW=H#&OpNLdB^wO zTY{dL5RDH$^PhKq;@sMg9JS>AsWB9 z?Vm1AKJuUS8i$12^Ul7hX&NNxi3!n2b83<1mTHi2d*0bM4o!muJux8~r{Cd(#fM(? zVZG)g;kMj+ouEdNa{__gqbeUIE(;$(@IeTJ4G;Ag=q#Y#O&gB~ zNXUFGo|q5~TT!Y(!tK1yk9qZ9ng$73cf}JEqA^c<$=)A5L^Vjbo%gHs?M%}kA^S)1 z#Dr+PF71hbpVndOsu2md^S+yY_02R$$Uay+F(DeZx2pyTxAXDiuU`EI(;y-HdGW-A zXxK4IHAuKUPrv&2f)sh0X^@~NCPd>oul(=<={TqwB;1~N_MJG>AVE(|SYK_I9cYw3 zB-~ExeA}PZUf15O1U)e!8fgT#moX>dw)E9=>+ER>dSXH}zLkz0KTpRHX$J|n=be4S zagxs&NYE1#q9MmXSyiGz!tHeT>nYEwtGOlUi3!n2JHt2~2UUZF+w;!8oonqNK~GGG z#?Ew3a&B6O(hd@C&pZ2;scDd)CniKg&aGrsi3SO`=be44)ig-Z6BD9wUOGp7$Sd+O ziiF!Tub!DA%W;qdJuy)tR>-gZpRH*9%}6njY3Gd#S;_gtL@TPB;3y9@sxWX z*!GnY(m%x$6QUvKq4Ts3MT3OfWnN88gG3(Z?1>4{u$ed(4H9nW^^r1qm<9=%uf-D+ zqG4-LHAuLf*SY_`0SQ@m#S;@c9%(Q6Nm_@}4iawX{i^%|Lz?X%WdA6hm=KM0ZLqyu z8<222@4G2;i}e)=*$0a!CPYKdLuFM-J4m>lj~^+wjA@XN{k(W$LNx4%qZ%aKF2}*5 zK_VZQvL_});~&%Y;5l|Z$ZW%I&$~ABFp1Wq-(6YA9S{GzXnZ8?RX12)xo6fywK>p9 z(Bt&H^S_J6E7P9)S-T!|&#V{4-0CElhu&!^w-91qk&Ycdv$^XYxkmOV=A>_l))Nt; z@s)H8{N>x{>p>E3&pT$ZZwY#0LNxwoIuAX;t_MlDJums<(`ZWjNHA}HOo+zo(|PEh z|8d?ENw__4ejTAD_$vr8AsWB(xR)%>eO105B;oeF{8~XeR!Tca@D~wcLfetf5zjm+ zAEQXPEm8jK2&o+)=!pqv*xS)8tJt+2=@=vJFbyTFT=PT(`YQFqXhg#8Iv#1iL0>6h z{iB|k(01f8Um={X^U5@AmMCH4te%(<4V#GzX$J|n>-sPa5;kAe6BD9gYfv>vxIHhw zR$&?>Y~86RCPc&b64fB#wnXVJVHzapi3y=?hf@s_Zr5GZG)UM!Xr59N5~5){wQ7)X zyB-a!Boeltt0yKz!;UzrLBef`;x{Kr&=V7;aX>l_ss;(S=OyF6wIgX%g5T$i3DNki zlTO-xrCkq_aC_b{8-GjC6BDA5MsRyN4r)6{xIOQfzrQ8ui3!n2GjW`bgQ`Ko?R372 zU&m+(dSXH}(ux|VaCPd?Q>E7-a?Rt=e+w+dUZ_yI;#Dr*k zGM$rLVAq2r+@5#*MU0l9CniMWmUM3QO1mB;;r6`z-pKa6x0B%S0>p%9yfvL8UOCOz zgCyLRDF2OsmY^plprQ9(Nw{6xk&YO0jIvrOVda{q)Pw~3D)qx?M8fSl9%=50hV_*a z)<5cr3DK}IUm={X^U5?x*f^^vCPc&L?pWGE!tJ^~OoN2YSM|h%XxNHU4H9nGb#59Y zY~86RCPc&b64fB#cHOT`gM{rL>WK-_usu;VNVr}1UDF_8`=EMaLNsh|R}B(w*W-t2 zkg)w+Jux8~cEnK)5^hUWxeAlHOM;%55c;*Be*WUri$0cC(P+e9zHocq`LAGXL@>&2 zsnyFCFI!yw!y{FL9=GTCO%u@=BK%i3NQlO34?1D7&z;ZIGh~nAZ>31N*LTmm`sm-v z&*+DUHmVTNu>FdjV%J)wy+Hda*J_3EU-KY=zS6zKqiQ>}TgbTdl@v?rJ-jd*1Ci za@}u4cvg85(vDLWFB`w}-;Y!ck75q}dCA6~Vnkzz@NE1fbUY3^VVvf!&JvHRIs2{L zlKo%XF+fNk<=+U9sA5Ay*GKCqQMFb(>)e%Etq`7dp9K0U@##&sOU~^caNwtsUE87M zdM4M6r>ARM zS?46&o|o)mX`RZvBEdXoF(Df1$Lg(hjSY z5>~ExA_9Gt`e8I8;dUL5G{4bTN?8A>CniM0#(afvy3Q-pAYtRIo|q5~n~4i)2MM?9 z`Y;U=Heb~f6QW^jP&G)nUDvs3kg#>9o|q5~+Zj}YgxeCOyM$?wpeH7TwmnfbNVr}1 zUDF_8`=EJBO-P7_?d_^T!tHuAu#!mFey*OF5Dnf{BjL70F*_v*dSb#f>RmMwZqGaB znyuG3+Va*@YC^*Ls=j4G!tHs!K&dYLI?w6dHA}6Lnf}WTV zjkLp!({WJuL=tY#yEZp233_5eG}2LRoQ{L4LBegh8#V3DJ>oUn>)u`odSXH}_9yN*X% zLv|dLzEZ;aM?Eni8a9F}gwu6inFa|PXZ6H{Xz;EY3AgL|FbxtmU)2*6qQSdrB;2m+ z+%!nox>HX~h=%P9V;K(;Zc7w%{F0z2CWN*>9kWbTrnCnkixHm&iQy_aFXS2U4z;C8w*@q2fX-!9U> zw*);gVSTl;yu(7m?ezZDf8IrY;m9=XoMD_M$%vkq5RDtsvyThxy$lj=%X_c8$uAt4 z1_^p%LNxCF^}8*;YVT!`aC_cawoua`K~GGG#@Xq;jDzgG3=(e7yE|U6yZoY(X^@~N zCPd?R(|Z|HdoP28+w<G(;{$k&4;+)n4z-`J(@t}Q`NOo&E04vy1tPHT7ySgUy-0ECW=Nm){<~Lx5JO;qEQGbw|HU#eWllGB;3y9 z;pZjRyGls^6i-Zu#-r1i|H(7*JEDPl|*W> z5^mS?cGDnX=h5nk3DK}KeceS#xLvP5OoN1752z<5M5BK_n66lqaJpVcnFa~FuGxSP z4Y|5Y$3eXVNy6=VJ!l#v?D|YSF;O(qQBCi?l5o3T*FvKZQf@j9swXDUS9;Ds!tHu} zZW`8CN=T2U<6vz^)*~Srb`M~MaJtN^iD{6?2ri3Agipm5z3%K|=PA;)w~-usdF=LBj2N zAI>yL$j+ILgX)P1(db_f7Q*RzKhZQu$PpkN2h|f3qQR>>5^mSyplOh>}9YH%!P)|&VhMmc*5Khv_9rkg)S; z^~8i|*qOfWi6q>v*B_=q!mbC@6BD9gS1hVQ!tHt;Wf~;xx<)-QAsTk&rN<}|ZrAHU z(;#8jXX=TGqEU{uB;2mowa_Spl$)-2)e{rwtL>xoA>nqtJ~s{PDS_p5aG(=mW?FUz2;%Dc95{VDC&s` z>#KS_NW$%!PsaPI5|-aZJux8~mVrjcgM{1CSDO9CG)T}B6QW_6bX0?c+cm$BX^^md zJL-uE(YP_)6HWiA1_`%oo+8sAVR?hp6BDA5GCDMQyvjOvI-Tji=!6tm_A3(f#Dr*A zh9=z;Nw{6}Mp-*ZSRN)+?I0&$>X)nG)T}B6QaSaTqNACd00$?gylt1 zPfS=})$2hLZr6M=-dB~d{4VN=3DHO+C^>6%%t^Q{eWlrNOoIeHF(De3Nk=tExLx!6 zm<9>Ux1*kz5Dhs7%BmWr4+*zxo+8sAVR?hp6BDA5c7`U8SJ@eyuKAWsgM{TjQcp~X zMj8vr>7;ui3AbzBDAOQed7RV}6FMI0`Jk+-QTmW@JKgumS*}b&-qtDvJux8~yt*Ud zw#+Nd<7FBo=!uD zXrw#alDln%aJtN^a(+c3k8}3KglO1I97{V$xLxzySvyF`d@W~vF(DeZqEv%~+cjUG zX^@b0SFQ(RLNqMHpK6eBJMUNJs;?zv|0tfA5RG)EFS!j>gM{08-z`^tEg}10@x+8^ zq}3!lwQ7)XyXJwkz9J#}dAS~p3DICyE)s5+<6yZSB$1Cx*%K3@vGct5UwrIdIj=Ln zU+ea~`@1{+u>00t`&c_j&=V7)vB$0_?7aNC+*c&rPWLkY;78q6&%3v2kf0|fMB{f~ z|4%!wxb(R?9wgjOZ<4>^y6%a4+{-jb&=V7)al0#aTYPS>!&HNW+v#5Tg+K0If1kUV z1_^p%LNspk;{UOD`E&PI4H9n8yCdIweRss)?`j$(=!pr@c+UNPf3epq_ErrNZqK{F zeDP1ZcRc(yra^+9m=KNc?D;2)Upn@Ox+juwd*1DFj~luV{K-!i`CS|m^u&Z{{OP&J zF21_s9MvG<_Pjgsl{a)hxcLgxAVE(|h{oR@_KL-mkNjoTAmR4ByXJ3h=stV#=S_nI zJux8~cfBtCUeP-jpBkkP3Ag9nx8Hk1chi9%HVqQ=#Dr*k^|0d?zk24{PSGIYcKS}- zvv24=x&Jw)L4ux`5REG?{PV@*ulk5;kZ`+xyWccOc&3OMYC^&^#zn)wc|B{stNpaI z&OtkpMkVNRI^7YjglK%|u;a(qo|XH`J+mfipTp0=c#xpS>3QdW7ma&dcf$CHlk=Fn zXVygB>xt)JUXh^3>3QdW7mY6-_KNY#o}TBfduC142`8R|^+AFjr{|sjT{O~)8kaTb zo>>$1lWWhxIwwJo)AP>%E*fcP7?-`oJ+mh2rLTJj_A3(fI6d$D@1l`*xN+GN-7{;V z&OQ8G?7JlBaeChQ-$moyfAK%YU$MR2J+mh2%}<))_(6gmr&CsyN{GfEUa{Nw^>&PM zPx?(9L>+p}J8>K&K~GGG#{86j+Ws>;){=00-hJ(T=izuxf}WTVjlbXZgzcZUa|RM_ z&%4Lp^e&v2kf0|fM58hXhw+x2*E8YJxas-Bn-4Lbu+4H9nG^Agh_Vdn|zi3!oLGa1z&;dVX0nl$G=O4#|1 zdSXH}?2K$7<3YmhdY)(+B<#FRJux8~c4ny>B;2m&yQV?H&Og-?6QW^f$f`lY?RwsB z8YJvIT0Jo#8g{0y8YJAV*B_=q!mbC@6BD9gS1hVQ!tHt;Wf~;xx<)-QAsTk&r5YsM z?&p&s!AvtTAsV*BsRlF6xLx;MYX=G2In@&rqG3C=YLIZd9zRTjgze|*i3!oLBaUj2 za69GX$j3p`AVE(|h=v_GRfB}v_2_IGB<%RAo|q5~I|EP+5^mSC4AUTC=LzbG3DK}K z8Py=+c0F4%4H9;~qn?-$4Lc*#9gc+C^{j7P_e44CQ^L;M)Dsh;VP}>rgwyrx)ig-h z`KNkfLNx3QSv5$wUC+WzgM^(&t0yKz!_M^eSWCj~dNpAhBy5J_U`#eXH##9@Xd(LdzZc{p?+5@2gtwMCyL% zm-bnE)B9&?4-<@XTS}5#7Jqb7{thoaZqHKQsD0L6{CaZ#y_TKMfbBDTlBa+>kfR#ebyfMx0jj55Wy(7MdPmNJ8@sL zcR%QHJKYJn=vUVcKKcKc#t^|Mw?*SS>H9c0+jrdQaa-~X?7jAaU%SdQhKM$*5TfzI zbie%)yWj3n;we$HlppS1Ygaw|TGJRJ80EH<#JlJ8xIIgG?(Vtvu9L4bjUj?jZi~ig z`L~_YE;Aa@_AtRHw@b#8 zv&y!&a1P(BroBm98k$7$VxJLWqWc zrek?BW^bgd`DcG%Y~9z#Z2huJ<$Lr|t^9jevvvQTS4%@8wOrmREq&$Rf+!kM zUuE^|A>rTC==UxOM)|i#`hrTV*@$42f5)g#(Bt2B+G?#x z_&2!v8f-@!RgNWnf@98EB6{|oLvJRsT>ti2X-A&t|FON_BKSb9$SKCk&roU?>Y4PiUgyE*Eu~T zWJTF~4m}MLjFRDDKC@eMS1ROMfZt)TIxdnU3jMCF0)ovND~czVg(ccCiLMt3;$hBHKA?zxSLy zph3?n5owUfc8_61=??1ZB`ZIs9TOpP)!Kf1- zal`WbefQafNb0pL5??y%bIUhg@F1nVPI9(Hf>F=A=&{T1eCV56+m@h*#Pc6;=5qJ_ z9u;ViVATD-_mjn|yK4dsdPsC{I⁢_%6^O!Kg2O<^GEc?*HRJgB}uBf9i9K6OP>x zXpm^5j@vh0wWE=HNc`;b4;}ECUpy|*Ai=1lJsxaF^^kbqXRjD{_Z(wwoV1ksWTAZQc5>-gvOuzj*t#%abQx7|Y*Vf*ulk z?bxw?`lr9N3Bjm$U-IMSb8b0r`>F;#Bu1mhukZiyE8n**l^$@bgP zdc0iI+k{}$mB)Q|x#y{OS*~i(LqhuP-Zvh+3Bf4Nv35M@A#w7%AG!YD7o8PokYE&N zPpk1CPrr2eoePeiNDD1WZO)#SpofI%DLqUuigTewfy;OzNBwMIzfd%C06u4Y^8Ps%MpmHAv_+uF`fj z8EDXB*U=y%4HDVTQFb*MXwb7tL>eTroulk(GSHxBm54M*WIIRM^=F_#&ngjVkjQq4 z((Bql!|q?H$L^7+&Dk@;r=5u;>~4$F0Ma#Q>(RS78nrbIJhfc6J4k^B%VJc!(!5^N zbatxuqqQu#pJ;g}*X>Smpka3e)noS-)n*@#@R^S3Az}A@l?IUdiUgzV?q@*IL&ENn zZbC2$?*#PrU3y5^z1~2BL>r~|!UMwYI;)3--Lu|=Xrp{&NBFd3PD1q3clZZ2M(SY{ zXAC6L2y*_|vk5DAE43nF&q6k-6{GCgOF&pQ67|@9W3{<%M)RT9^o?`d)}bgy5}h>M7e+I$aHL@re)dqt8L??w#UoeL3&7d{+j-^GYLlV zo^@YC&lyymgy-Q|)o_AQo*k%9(BpZEHtH+ZmxO0h>T8f-6vwG;ImcPX-?D~mFy@>M zBxL+8A4qSfCc&s&tBLk{TPqUMZ-%n z%r(iQW~(_Mq=ohi6=`p;zXf1(HyZP{TqmTb(=*{fg9M{&KMo1Mf+S&k@FoPK?8p!h zoZ)#qrW(cCj_{Eqj_&OmMMCC6%8;Oc2T;d6_adX%>n(BkZns8HEaobNaPthnyj|GC447J-_%O8 zXBlX)7p?Bvqr+oP4+-l9rQ3FpV3hTAKv+AhCfbgrwAT7CAn39FQG(iSty;q8n9ZI* zgC3SU+>X=Vc1xF5t(NuZkKf#-RjYQs2UJ#p*K0bahr|aSe6#$zW3WEVqfe@g7)xJS zNt4xC@=K#%bZN)YnjGkmCmQlky z13e^m{B$(1`;cg(hV~M!THA3JQbVpsZ$&;D_}V66dP)xyjN%M!33^CaF9aGS7{ztd zYDmVta(*Ql{>pg*@8Y%uJtT4t!s%pn)moNC^;kAUwR1_)(SRNjmgg|gAi*fhS{M+l zuV|!qL{Y0{K(OT`q1{ENhv1_+-N}rUe8&BrK0xKuFfIbay~KqL=P7Krd=} zE;oBfWbH|yL4r|ItMb%ggwJ%$mRnvm)M`1Xkv$|VW7;MJqqquCsk8>^Az>NQ0u2(3 z;x{l_4fcs-_$zni*@rDb4++ab7}Sacqw?Q3>s=C-gK$tIm&K^znP}g3(X#AYFluw% zjPNPrF7{wa4wW5badiQHm-c=kX7&YAT^mfyvyboo16Bz@(&(dnpL&C;i>0yFV!|%zY z_Y)`O&Bd&dXMTDkZBpKJY&Ga1(bmwJ>3EgMYd*a#HYxAPdAyv3)5CJvhb`gX=%1~7 z27z=38s}XtK@SPfanQf-V^Mm3ZuC+{(1_r?ogNaN(`zFQYtxEe*bc1;3D4u!*I-Q; z#U5!jj=ul7-RBP2Uu$yECFgbzIPgkB6#BKICm@2}CBb$K*NUEi z2sB8Ttx@cewy)SfX?AqizUkh2r+_83MC)zrd?S)jDs;qjn{gynY%YDI!kmaQou=&^iDx1v@gJhN_powHVq;y8`)Dc8<<#*sia zyWZ}@vKYlV4T*Hb@oZnSb~@t7bU?c>ydzH?=JiOR+cnetI=qMn5^!JEX!<-@{EH0 zzM_Z3aPPkPU#^!Ur|!rfe#G^1JpmDD zkT6@L*duMN*gxs|rhDGiN9&Q3CACEBal%T{bCh9%QC6#YOIkvWXW=X=cfc58< z9g8M1M;T@NnEt(O2R$S_n^|9j9?z>*+L6!5hc!re=C{5EYsDzfN7pAjt6!=~&Zn-e z&GR^_6+I+8&tYGK1fx9rVxM4rJzw8e`-+5T6zprTuNcMJw&Ot$31ms^?Ik1_#a?eU z>|W?nW}@9yRXf)z; zLqd8X&VE6HQT9wH(6GC}>aqLDYTF&1fS`wj-L2n*V3a)(2nc(Er5?Ngtv1^?!l&Hd z&AR~!yOXXofHZ?uc}L4r}ar>6lykKJRx z6}2K^ck2TU){0U2?|J7N;UjOiNzRJwAz{xD1~oFlD9&j}q%r4=vwQ4XF11^N9uju9 ze$!gjUoYDrD_5S0r5#S#GlW2c1f%R(NI>w-etSb`lCOle@=Xg8e7|UfPy3CLHcB;u zTIKJtdhGpFwe!0l%YdL~mB_Un;ZxttM7cT2&btB)diWMf z{(GcBf>FGqhf1Z{P7jIUt8Kp7%XfCIhLhE6XL?qN=)9dowsVx#Fwmf9m54M*WIIRk z?oQiR^pF_7HsBh3%*Uto4Z06JcslSt+^2S&S)-nR)LYVSm*2nR`AS=>r#<1M`VJiR zMx)o(_vBiF9uiOd?*EoIwu0;0`QE4DU9QumT)jTGS_R|LdYm}_qBEqnO1HIYTd0KA z#I%E2vE>(C{;K*eAKTPw&_m+%x1CsfdYE7oN3$iYceRDqqiUP>WOaS8PoD6QH%mK| zX#3Dr%9;L1%OYVjMrn_ir(`UPQ8wQKf}TUabf(N#y&J`nhBZixMsMx@TNHEIQd_d4+dx=J|q_E`^Q72*hSfIhO+9=)I1A;q__3o{x6$u;vK!den zl&u17U)%E5qq9WIwOJWxkYH4MByyGMxIL!&jIr7-2glqzE5u}Dg1x{i0IySiN7%1e z0wU00S!Qb#--c;5=pn)PH5y{!SHJU;v3Hp=b0f#^e7z;??!ZK%{N2$?=-*qya~aG_ zhER>l=kRi_)z`@9ZStD9e8|M~0^Px@QXN6P|}^FT45{zOW z=8-7l!9MYfNjf&Q4_ku0OTu#q^=n0fQK`0;X{t}qL&9?wZA36Cjg#eJ>JyCe>`6N2 z0|d(=;aP6_8YCFy`EvRMJtRD<&PGHVRWb$j3C{>LUnk+Yel{W)#dXup5_(8@&Z52s z2}W^ssm3%bO&6S3o?Wb6^KGp>AK84Jgl9JE*NOzAJS$tDpofHKf!l~+lxKVE6ZDYq ze1sbjjPi_veS#hmo>8z*&_lvA7;Z!`%JT#E2}XI=!uk3zK@SPfN7&aO!6?rt*eB>A z;n@X^sB_n|P}cdnl%wbhVH0?|pvPvV5;ot|*5IlBn~t?47{%JQgui<{M~>h5y1zTz zZ+Y@q{@wYy?bPW!WWH`k2DNj2O0C#(&&%2NLQAleN{aq>_{E-70Y6j=Yj2O&_lw`9|8>$jPiW8eGPg@*iId2kYJSO z`0Z=ZL&A;>fd+{-s$?YYYk212`8o+ZUb#jca}tb7+Lm*=MRAf2}Y&4U^%e+8uXB`^PoV31f#gR@>(h@iXIZ4bGu(F5{%+b)M{{t%U53V ztU#__+xfnm0At_!qJvnUVhnOUNZc-MwUp&bJoOvNn*a<_PT|q|4kQ`6HLpp?0agjw8Nn3 zf*ul@_w4&%CVVU@Xc938c z*Ji8XPrc{s{xrO_JojNsap>+ zsG)W+%2v@P1Y1tR)?-jB5{zQ6kMNl;*gu|MRMy>4U(rKCO3L{eY}HP)&~!n9QJ!(N zzs~6)u`(W2g9M{I*KEI5^pN2AqpQ+h!c}Cu!9-TqFhLIq+gFrsHApbZcD{h1hlK5R zn-Gk$Jvboj+)zE9pSbJ{@skEUgIpmz({X>yTTjWkyj2a)xjbL@?9F`*_7$V}BxQt; z%-xdfysb$tNpe-k8refVe`jW6qGXp7J+UK=w4&tdN7e0m2X;Ija=ny2B<#8*Y=;w! zvg@6IpofHAmux~X%C2_;f*ulfjk5{CD7!)m2!H=-u6b*7#)~o@qkzaGl|7!LalY;u z9#_X)GaG4HjPi_eGRsQQF$K6E!WIw+71$)adTC}2}bekV}y^K zC;FPOHvv_TwFRJ8Uf#PT{N1?KS~P zjA>iWr{Ua#(~~Xxt(3k->*?>>QSXwl`&Sb=%6PVgz6L!cJa0q4cXL#}{_qSN^L5YY z(bpisDEqtCu|+7oL@5-_U=pkX> zs0#@DPLz7`xlh)x?_&i7JtRDkS9`Whq{mH(bs0VL9~ zmL3xJZ8xpqFu|zd5#%hf?|Est)E?F#Vc+1|q*jdLS#7I94+;CuSD-!FS;7Z90u&ALiIX&_lw$C8qQ+!KkgZgM@v@EYM(CjA9?QwX$zcX<7E&KDBd6 z81rf7rVI9>eKQP1v}#!^684=hrE}>;g9M{iYGqg%^ITsNo{z3S6Im9c*duMN*gv@! zCKH*JEU6{vAz|N2Q+k+SlzkH|Anbc->alNzshwviM$m+&3wlV{cgX?`5{w!?et0(S zdC3uhY^#v|Pe#x^o(X)u?s?WXA{aG%1<5GS5npQ+w7e~=vTdro7c!k?`#1 z8`Y|f(%&J_8G}ltGXVCY)qRY4H5u$H^^mY$P`cINm@~?HIv`q4`3;5ISDVzzeuWV!NdK^XBYdU{dPsPt{JsVWMtO$uKH+)D=j)!uTxPrP7^sxrBU?({NqC<1zD8S? z&OU89_Z8KcW~J%E%GH_ZS>Ndz6L#>opP%hBs?=_UxT$`lxN)R6Q29A%<$Y=&-U0S z=*crN6Q1F*Pf)|NQ?`0-@3LGHo*A>RL4r|SE0IP%XCUDj5=>*7x%SA(DDK*=2K(Lf zOKx?{NqDBpe#<%LjADB+TBV<&5Hd z)6%C!BYmsa@+{BSJ^ymG{rFJ{&zfALc1r(v2Ic;kv+ka;dA`oslj~DzMGuK#4HAqp zJLoHVNU#^$TJh}8cD1pz+;-7Poh8%K4thw~{^&#o(o7`5DBEKOiKTi-cz%}tcyKS_ ztn@sW{dGzN0lxM^2*NXM^95SVMBMtTm3C~p7*C4?t&xYA=xo4!D zuX}FGvNJ@rVxN%kte*W^kzmwtU$MTPk#ehjMZ$Ai_G`tyViarJjyXLfJmY3xg9M}4 z>v=+DrRl=n*jdV2v-dsJZm)N9wEWxNha+KcjwtQ%eS%S0BRb!uhlIVIFsPBsVwAnx z5D@g(I};j3?Wi4DgM_`W5ooY1M%jBH0YQ(wUvevIMZ(@~2{c$MM&&zt@p$OFI9e77 zd&?%&aDq|x?oUA2JJjkC;+mVcsm(jZBYfIB^dzK)`IoKx>w{%6D)-1p^&ruk?Ifh9 z^KWmjYWQ6zM#;$LU$!=4nw6#tdSsU5U(ep^{VNiAR!%l)2cx+D+m_oib1loBzN?-0 zn5eJlAz^P61hpc;D0})E5cWJSDNJt;%jJ@#)=CT;YRWQP*9YK4`1})FC z2S6Hgjv5Jjma6nH!6%=s3(}g|NRgdQ_l^ssshjStWy6?J&gl9nQ_mw@#*Rt%L z0JXD5G#>Pjuy-`PR@0Gw^1B~p54We`8nv}{kg%ukO6St^zj9RbmNUwp_B$~x1U>e) zfJU*T99sx_NO%t0e(#cCRQ~&By-UL0hR_;DwaR5NiX+<+94ULJM9bY;tw`A0DVx-a zQC$CRt>__P@5}@mBp79H@&p9mzp(W&k#l$(C$&fT)On>I61M&~AsEHE0EynJC1Lim zUeOy?Yo#7WamQ#i=pnJP`&13jH7Va$(yXU?pTUkLlhs<;aZo*sVw>7p(L=&B*!5Qw z2}XIAyguQXRp;xT&#+`k!`?p4b(=0&mgnxPgtl+E9V9&OXuno%J4)ujbpJAEj@6!4 zjcHbzE<6LGJaN}twR&HyEy?Ruk5LmDDH7@G(sDO$Tq}< zk?`D&8`X+Y?2%lbQY*I5a}d^AEo(art9_*&5~dN{xnrL&%4!%8Tt%KCw%o-TO;&5g zH9^9&)Asv{L>pD|{q~8`$UUCPajUf=;W;7u8mv_tb&7n)%x8NY5B8$X675m;x&`b1 z+7TpSGc*_vmeod;EY1CPc)nNhl&r9|ua<)&XdWj#zieNF9?x65RSgoJGqVhrhxoQoz9)+#r$P0(f!2z| z@SP%-#VEV)YwcsL=pm8q=$v|$$Wi(4Q3e`%SZ=mAASN;%7NxdntL?3j`@8gzFug4i z`ObeXDLQ`8!*a8|H6lmxy{xt!^t9#n-ZnIBx?rvcW<}t;k*x+jByygBs2wC2#e12d z#xk!c=44RY{_aeBC)G4G%JMb@MC2j`_j=< zcF`e%-#&C(N?LyMx5iIjZdVO@-0o-W9U_={)@{)^d$Q;FXD@%UYS82Me4ROLhY3cx zEgC;~!}qrDe#TL%L66(%+;_*@Cl~Mi$S(KQ5Wy(7MdSPL`s?kx{M`#wgC4iroWjEd zGo89E8vCDf@b+(i@Ho|=$L*TI&e}0VFte)LqOs!>Z#v+nC!L@g^te4=XC~KSf>CaZ z#(!RT%*CHMHEYo0cAJrQm|)&ow?*TL7j!$&&b>OfbrA(Rk}M@7(!= zD_*D?^thd_iXU+1a`*in)#Z6LL@>&2)%fji@BG8xc(!WLj5zNx;wrD*3uD`jsbni|z=yAJd3pI@)g4w3s7L7};8!t|L z&c3QakK6t1-$MlRVY@9F`@a0p#f6{WT{Y-&yXG*RASSTq_dgw;x;+(uvR6a{+R&f{_K8xLMKeYHYJ@0KXHMZ?Bi33}YF^U5@a2%9Au z<+fP9?Hc8_XxNHMy;#>rikg)y|4P_;RC}0Ul-r_VJA-P_<96Mz zQnbvmA;NYajdEKwY==_~dfcx2u4xPrwu@?%+oEARwQA7g_I#Z=Q-=vgxh)!Y#8C}; z+^)w#YsU~_M>UOdTQ%~rRyF8xyB^Pr#sFbQXN_`OH0+!~HRy4>o|l-$5MgH-8s)ZV z*tw5t(BpPJzcP&>!p@d7%5BlGb2!zY$L)HaXc|L=o%Lyy+oEA-ma0LI+x2|cG=>N} zd(|knMZ?aiRf8V4>v_9r3=wt~u2F7_hMnoF20d=q>krcyBJ65Hqudq^yT(xsdfcwp zQKm6O*j156xh)!Y<)s?*xLvOYO=F0#t2>QyTQuwnQZ?vtTlPV{{1Z5a=Fb{}cb6BB(6 z5^hUWnTaxwIj`u63DbCQn!97n-AVo}s(!XV$+6cbY%Xm;SgooC3AcG~aaBWSpK8R! zss@Q-m-lz0cGz4pjfm)LkZ`*^H;6QBE~!RL^fgGhU7q$u8a9_yBPRM9B-}1<4n!I@ zmsBGr`WhtMmZ);yuRrGW#DvhF{NRNbU-Qc+*uGnSGf2uR_I%xcn@9dmqV+_CXgvD1 zC+>Xe#V=6}5^nRiwnT%3|JK$FH6fwxxcbXGAG_nZszJhS{$`lA1BCx_)~xx}FaNt} zocM=(EPiLNLsi2)v*x$RJl~pVkf6uu_IJ?IxzGI{vbgV;AE_E7+-B}J(IDZu+h)!0 ztNGuh9qV5{XmRDE?xh;;nKe1#JRg~8kf6uu`MUpIG`{ebqZWIg_&vQIbkD4b^89C_ zL4qEq(^b)j{&n)Un;)9ijc6SH`4=s|`NKD>hI?jBlxJlV4HEP?Jzw{~i^gyN=oO2f z?s*&4aL=rX^6YY=L4qEq(~7#}$CKyWa^CjbjvGI7!s5MOe~{kGa8H`;i1Pe*qCtY5 zn2>ht(H*xq{8LX!ilY$;w^Qz=5dTHAuKEQRTOUM57Qledb~BrY9y$;{ee}#IKWZTiap3C1e^($ZSvL z!c%HO!uo1^=_?X$>v-6230YrNBK1%8#Dr+15!_zJoP^stuk5#kM1w>c=jw?G(MU6K zdzrf=+}7D{zdj}!B+`7Xo|q7gw4%mk4U%wM*ZK12kGXJ}_e2tDrB+W&h(_8O#$_)d z;kNEq%ST^ys%el&`$zS}glME4Zd~?65^nRC<)p7jqt2VedQ6B$+NsB7Zztil z9zT|T{2-Bz0M!!{qLGd`<8q85;kM?KU0(Wc$1dtIsuJnAR6Q{v8nXV%v6h6}dURgq zqqFoCiFACeo|yRmDLW4+E2^w*mjp!=1JI3Pz&z?G2)4k8eTy!|I0h86ju^+pXBY(o z2xc*&n2&Mx^ByqFu@*lWf|MGC=x!#-|FP;K!UD6 zXDq(!Vdowu*n_T+W4oqC!pHcFx9ougU3u$o;kqki^+SR^=t@7fxd9SBcJmMY#as43 zg60F65+>MV`seQyY>tD3kMZ|w*#imxYqW00lKu9s|2uoo%&TB?HLti?QTDsIG;d35 zZ(pIu90^oB?Piclxb2uQzSicPNcfnuY&Pk(0|->Y1k;aQGr9iZ^<_NA8iqbDmi5~l z+Kz?7D-iUTf!pgpZ45{U%bk0|`{Z1bh6^^xX8;zKh%(2MHe+%lf6JdLV&Hm|zb&r&2n% zoCgv{5RSzUk2@~c~zHYL68jggI zWjp-u{IG`+yj)Yl1njF)ME{WRu^f-5mR+9TSB~KQV@jA{k0#B|O|R^`s1f05JFkYQ z2NH6eMF|t^p=V;s+ku3SrF}eq_YLZS1fQ>_gbDW07UevU@UgV>i?6>$J&@pbXG)l0 zkBQWmw4d7Bc_86q>96SPO!Yv5`wvsX1bYmnKJjI0hqS9ABz!FWF8%78dLY65pebR3 zJ+yCk9!U6D#*f>sze_!k;Qri{Fu@)=MmY~8d|aeo{kx=&et%FskU%9&u*cu8nOsZb zpz}b&$HlUK6Q>?Xpb{o@Ulq6qis&B_KBjiQ-G$j+cY8M@Pze+4K}WD)#~cYC^S(MS zJA3j3Dq(^>7Sq_Vmc|g?4kUbBEbAAJJ>{AK2~@%ad+->@t%^O6@G;%}I{xgeHRlOb z!UTIz&k)l%=sb|{aj~pl=jwJKfl8QQj}l#zJVNb|w*v_u7t8vUsd^xRN|;~|zP934 z#U4obxLDS&TGayyRKf&%jHYYE&Vyu(Lc+&2mPX_ zZU=i9!OJxzOu)V>@V-LA$8tRE*Qc_*>j>UIri2Oh;Oo$d)DGDL2_M^e)w8Fx4u?JCN|P zj2~26Mm><={@j!>!5%u|I1eOzY~!GLAR*(DC}Dy<=Fog_l+Fk9HHoeAaIu`PJd8wM z2@&iuh5D)=bYCIi$DHMV9f7t32vouZc<9^FxGama?VvG+@5!i#BXqf{gb3JICGM|~@NsrL zsJ~$k-B*s#{o|A{;kHALc_YHp*?FZNdX_jskF!(41bgV2nDTZY;p41*s0R{yzB(mL zu!pum=YfQevv#f?NNBrrN|;~|?Ms{o5qK_q-!EaNX?{&>6C_|?(SC>` zBz&A54?6eQL-&;(@;df=+c2pqzFO(p`9`yA<_MSfe(n9!m8rUOD z(DmnEAFHExxMy(h>|`h|KA8-RUQf6j@#2K<9~hI*LnCXtf61D zYW$SL9+e1RjUNejJPscm)4A);5}%dT?APU5^?$b=6$n}b{fz+5vKTyE`^YPnm914t zwu9OSuT>+$SKUVf_7(B;rrT?e)a`ueOB83@;g;)b`NO_yL|~SW-FD3UA3o-eK*h&J z__YGJuPPA!cLxEMo}^W6tt5z48PqVS;I$JL|r}Wm!!30HzJE z8`XArD%WsGUJQ3 zHORsQdwfH4!7uf_3?zJ9EMuLrJb_A>V2{N#r#+SCw%pE<@Nvp~ zJ+<>d!pGTYpi4qR`*Wv+3HHFdYDoB)v#>fP5~zd;^~mn3A>rd<8EegEa~!wjdBxTQ z3EfxOTNX(8xM)>x{l3ZwtW_H(*h6QKZmp2;F=zQ2ws``TFu^pPiP?QPBz#m`b&v0GcgA4lWzCr?(Fu@-A`*40)p62@{*VaW*PxU|ol`z2`)WgLz z4!S-O2_F~B`P#Thpb{q7gGRNO#zE(Sgpc`d)R4MIPPws=_3asfN|;~|eglHWK{w(c z;bYG7RfzKhDq#XVYPoMm!pGTm(6;J0$ZO>YU9Kv&CP=`(qW!@4;oLrPgpaf1L2XFK zLEcx6(Ea0-Fu@*r1RD{a&dw|KKthkRQ^Ev$;9WH&e4Mop^*}<;SEqyt_Q1PpNccEw z=jwrkwmYYU3HH#QA?D+OgpWB3Yy2XCN|<0;`$Xq~gpad+SGNNR?FUt{H9>+sXjIGI z%Rs`%*=V3kLPGmav`+J^1B~0kPD%m?MNcfoEzxsJ&{)Hp;&})X6PLc?fFu@)_(6f)R`d$VSKIZpc zTk$U(sRt6MgbDU&yRdb-K;O$i!pFt3Rtr@RBv1(x?C}u2mvOkhmw|+ji{%z$H{oAY zQV%3h2@~wmgWk&+qVHuO;p1ZYyv;UEXdF}zBv1(x>_P8ErS`5G52FHfKnCfI{#UiKy+5>WrXd@S2xZ{y2a8NtgnB}~A+qOmWEknph_4|^Lw+gFa@{bNd)U=Mo3G_`k9k?^sd zS3`7PAtA?ElrX^_dL~lO8AV9=SlWlZjh`p@d^IIZu!puN=YfQerJdW`_<4fcohf00 zJ(^Qr@`*m%M#9I^U)kIEd4l^7Q^Ev$yhVND6n#dIgpZ})wYTx}1owlcgbDV**&Px- zmhr>h#?KSnpPLdU*h9xCcRY~rG4Cs`O=a)tBY{eoV2@?+mIV?%E|&FI|Mc8N0+leK z`zo8=A>m_sH;R7g&-QwDmEpD=l`z2`bj%BO%#rXh_g5QcXHT9$B}}l#DKvKU(QizU z@Nu!Mzxt^A3JFxg1bgrp$nB8ZITAjm8e81+LAc0DlV2^{Eof{v0n#>20@G)IezrR7&yXFa0!UTKJI2hA7=z3}-d|Y(DgleNi zp3vVGbz2xF*n{VTHsT=RV?M7opf=c7_Z1STgbDMou@(s*%XawjoIQ--<(d*EU|+ep z8WKL1_*mMxy^WtIxZRl&CfMTw>PrsQZ(ot{vGiB|x*ZAbKTHV| z>_J!h1)Ccn;bZA{{rm$7?gvc?6YPPrJ0yH8D^uXp|n!5(@I=RA<`adw@k9!ThQn^VFBd*JL22_I+IyXt|2 zUVl0zOt1&e?vU_tcHOQXNa%I6Q^Ev$=#{?fMUn7vHvdo$By>LDlrX^_4d;V2V{wG1 zvw4(yAffY`|3a__&+cd(bax<;@NqUDR1YL{e&&=gVIDN9xqGij_&A%_f`<{jTp96LfdrqgG!8l?Ot448`JfS=&hGoD2NK-wXdHA(m|zdRQL~ zuVfk#p3bhX)B_2<-f>EpU=O__a~??eIJ-_%4Y@9}5xjrwDkDs=hu#BdM0ncHt0C%vgdAs4!UTKZ><$SZXZK6g0|`D~=}wAM z!UTIXoDUk|>FmCbdLY5=j_!*(B}}k~-YJSB`iF#%rN5%PpXz}G_aCN&3HH!?WX=N# zA7}UB)B_3b2W|clCfGxJYUhE3kF)!U>VX9J=Qb+}6YPPrJ0yH;z>tN(d|G&>!LU%Oz6JK=7UK1IIAb)_f~2NGJx$thuiJ?NQpu8x=W z)Sk}jU#SNYT93*pVS+uhVwRf^BH`n#j+c5Mp>?&K5+=-pYK6J676~8AcG#>>*2)N8 zt|?&x_EjmOe@OT^tE;Blq5H}aynk#y7$(@`4|*0wwc8pIp0@LUJQ({h-b6!UTKZ><$SZXLTUe0}1ZWZB`T}*aNF_ zA>m`bX5czr+o=Zq8>L~E9p27Bz&CJ_fZcdwBC+W!UTKp7|5+EqJK#E zIIB~n9!O~2Ag6>0_Mo02SI5hG22W@8med0Yt$*Z{Fu@*lEV!nV>l2aiaaK1t|?&x_EmxR6%szq>Z;}Ul_Pln*i}ZDU=O;p&9&Pa5uUd5%C4`F zkmD>$m|zb*6Jy>EBz&CJxzp`Hg3njG>I)O>p)JaJAmQVzUY~j(!R^lGgJFU_w8EeB zK*Gn;U)iiLPjLTXN|;~|y3*&`hRy>CA4|V$v%WmR{h%pff<34;aZl|$knnL<2U7PH z65OBLd@xL~2Ug`m!pAla+I$cR8J9!}6YNnM{dE05wv@Wg_$kOfAc0DlV2>Vm%qx8~_dItzknl0RNq*PL zx}!GTLOqZ`B}}kKvyWP(uWos)^FYGKbT54T_jPw{(^@@{KqXADN0a`Y(t+pg>pYO~ zak1R@iB)x{yxdYfkU%9&u*cuG|7*JCp!UuK2_F~BxAb3K_wYVV)B_1r!UTJKw%M8K zdjDAA`a~prTr6)|^+VmbGgqhbE)Ei?gbDUI_mO|33l1FRJdp4){dUncKh%Bm%SY;g z1S(;IJ)S*wP@G*T8cg_!W)At>v9!Q`PCfMVn@fW2BFPq{# zknnN#b-#Kb;VVTTtp+I37r#;^|`9|D8RmRt}C&xmAw2S0?7Nwm51OoL5Mo;^|`9|D8SFK6X%i z<*9P+dSzlRYw)$BpnV{Lil>WZ|9AGF78P3?^vc9s*6QV>pq(Ruil>WZ|9AGFo*}lr z#48hXSyv2w82T$DQ1NuJ?ElUl)WgNrCwgUKF6)sK9)W%r2~<2?Ec?H+$D@~bir>|~ z-76DwS@#`Xgz*CjR6I>pRWgD-PWq@-e20!vUZLN_fvi3k{|m-JBv1(x>@o57d4>Pz zSc`;@i{`^!R>DtTm+6M_A zXSEt;$QXr$uOTuK)&vRm&>qf>AHK@T#9Unz?H^jbBS3HHz{8Rvn7kF)Emp1EruN9gsAQ^Ev$=oMMY#{&r;XV;19frMVS zIVDW6hhAAa4;p!pGVC zLp_kt`G8Zx1bgU=#d#p%<7^(K9!TiC#wlTfJ#^;fJdp5l!+J7EV5ONb!5-SfIS;Hf z3HH#Q+Ib-1<81s;4}p9pkkIQL zr-TXi&?_?6!y)10?5Z!$`b56!bA(>EIVDW6hhAAWB0Qa4y{ZQidj08?Fu@*rh3q_# z@Nsq(t{zC}b+l8$1bgU}z8hVbr>zLw3rC<_Vppl8;x)Y;;AyTpGpW-(`R9QBm*sxe_ohzNTi z!Exp>qoRi@wkAka@IZoMBkW#ZW~b4Z=!lsA~4Ix?6I8g?S87YsZjCpM5=$aZ9>mb z)uR%DSw3cuIrOY(d#$mBijOCj5AD27vdgn?sz)UPvwX}Ro6|RO@9DcAsQ8%fgiPBi zIr7#I)T0uCSw3cu&**!cU-TPyRD8^J2HGc=?6^!lDiQfCBiQ3oy5Ihq-f#C=tXS4W zst>nCvTUE_>QRZnEFbfd@a{P(KAuQ*?y8e9x2{x=N(5&4m_3HcZ#z*h6Gf=_nDTl*eae-8+2n7Dn8~~VXh6T zhql2+1ZMe|J+wtR0u>)~tuWUH)uR%DSw3bDZBc1N|4{KUy~84HP(3OUnB`;k&=%!9 zQ1LO>3Uh5xJt`5H!O%Fv_&}&pT&x0apf=929>Tv zV3v=0N!p^E2P!`1T4AmYsz)UPvwX}R+M=8XDn90Y|yK6 zSz}u6Ti)=c7yl1yg~YJEI+c09HTJ;muq^ibvEzm63dN3-!-nZjAUMjlni$ADv7Qe(oDhQz;H^r_?H|KADA@*eL8 z2-}OC)#l9V@<$g;{y!W+B!=#_VY$VkNdXT$f|kX8U$;Htxp4b1g|m>jbFU5S!X8Li zmf!MF8^pbf#1>~(*YRHX?|av>*u&a?V}jeqHoaE4J<9F8&7$Sm-fgj>$;`&Y4&Qey zH(Rm(OkOVU-Te>v-4T48F1X`AfwjWra;x3v{m=hD9(+95ojs7?UgE4vmIOSIuq>wK z$cD}<*}KwT@tMfWWrF`6-f~ko3khy3yiJYw6%v-kG`BR~(~Sw-yS7J}xM|O%T>iaT z;CPtASx9hCRGRTizyk@(V%qj$@4mV%{km8374^s?x?k7R;@P#mdoDcxj^xJY_MO3TWdgG-mL(mv%T?(`V^1ti zIjdh4Di-r{cYEs2q}}}I)uR%DSr&`O(#030$#;`WE1#KAg^I=OaqZM$$&Ga_%Ca4m z2+XorJRW+jS6{=COm_6S5`O)O(J?~SG zN(5$EEFP!QIrTA}TMzDdNHr=Jv&Z+Bj!jNFd6aroA~4Hh@mN7^;}B{iFI;+LH7XXf z$NsxdOvd&Ztsa#K%(7TKrnS4Lej{q@&)w3y8WoG#BZ{Uazpfjj9+ij&S&qm&YT0Af zNk>*&mMYnD>))FW+d&>d0<$d6_EmxR)pkD~T#bswyd9h0QHJ9|`zlCamc`;hN3g)h zyj%Z5H7XXfN0%0};k>FuV3x(=L1$ut&)sj^?NyD6#q4qS?sK7iR3b3TV)39B6>}SW zd&h07QL&gkF8E*`wDU>?W?3vA`u=Wu_0KJ;QL&gkPF%YH`m0I=W?3vA)WgNxCw|ss zX%#9Kv&Y;)i=f}FL|~T1;z2!i%zgXRf#a)Cv6wvuAGR3Ak4gk)Su7qj;>0{g^;~j( z6)G09$NR^94C7!W0<$a@4;ndR9&11S;oG*TSj--~-?s$D^GXC}Su7rO%@Ff7!_9X+ zc{eH+vquzt;%0XeS0eIRLWsxB%WBfD6WZ0k^<_;QMJKrH5?NLs7yn$?yyu_a>yymy zdd&=uskSWP$H~c;yZ@vfZGY~VHov(?sh$W_kQj9F$;pDxdX!~5b|+%ZO+89aH6SqS zw8Cjg&8n{2Q=hQaZs~jPUR!#I2vm^hu+!0kFAMVO2pd@2+Vq5&RNN;uV1Vl z-<-95y3rMnmfj@-6(qW!dT!D*dQd%nQsT7+1ZK5Za6z&`bgz1BzPw%9{>WLSSBO9b ziCZ?fBzg0h$?CDzE$KmR$JDXsZzI;ZB+neqVc(gQJ{1( z@mvD}vyLA1c+&cn&D7(vXO`9ec5foKb;sNjn6=kS^{^fPp0Kp`bJ}v=4pflX{>@o% zJQj^#T6;9@-Dhd7kie`7XUu}*@%v3Z3R~$BL)7i`tP0RFI%| zF`%6@@d**!&XLGxErxdfpDfCz4iRiAq4-%NQ-r&!mzj|Zs zvcg8xTl46Q3KAnf{2Kb*XNg#>y(kix)%1q1px@oADvIl=bt6?1c>6>=(&(vFg zK?EvDoHhSv7|&ZQZx?sd(HRNMT3huKjOT04+CHwL{++J?P(fl$qFLY)2j?5 zFl(QOeue9jKW(*JJW;P?P(h-6&>wJpbtDlRQvW`J)(Q#Cn%{RVTwnd^=Z^7~)LZiv z87fFz_~&SUf1OBeJYGU00$=qZfms`z@dsQdcKy0be5zhqqJqS;Z$$h1>)k&Q(L}Fa zk-)6KJh%?7cW+x(6Yr~6$fzI@MeFVV4c!Bj@tm&0<5qeVjzm5ya)gZM{JY3w=+~Mr zuaDbAL#8ButkY3gM!MCQ$9!Q`PBE*A^V2O`;%MbUjM#5s3)$=(xuaJm92@&E! zXJX3d?zA;~S0iCDXPq(fIcOh9O1H4+wcRfuuE6RZ2otwO?L&iea_&qKe91S%myJgBEm zxo@BS%+M+%Eat3(`acij2NI}+2=Sm1C*?7!`Sj*hNLcK$hCJ`bt_X<;ln@~v|Ds~IqU1gE=h*IG}Qe)ijY7hM2N>q8VBE|Djutk-lhr( zi#h9w8!t(QU2vOvAc0DV5RV6F96XSY`4uz{B4IIS{jltkWbL}!)dLAsLWFp1PvhX@ zbndRCaS#cMIcvq4mnJv$yHh=oKqW+o#~bvf?AG+mE2VJ|35z*v(t7_$+B|iadLV&H zh!BsjXdG-seaY)I4kBSOXZ3&nAIZ8Whp7h=sDudd*z>GKg`KG#9!cXM5*BmTxa%%U z9z6SQ^*{oZ5Fs9IXdFD0`t~{+2a&LtvpS!2d9uR?=79t%AwoR<4dWmZ7IRkr?)_>0 zagS~X5~zfT%p)7skg%AuUaTGf+d&=~fl7!F58Cn)@2eAO97Mum&WcwKfa8G#Dj`BV z=m?hhm^Yzu5DAMp>+M!JWAu>esu1>OXDCC7IW6V7hMVM0|`_@gm|>3 zac}{RgGbRgh=j$QwQl39pq(RuN{A2->KRh*ONP=oh=j$Q_3Q0dL4Sn=Dj`BVsE13r zPyFhbxm8G5%vlF~dlmG%NT3oT#DjY3l>7F3XdFbsV$N#1^VKkZAc0DV5RYLr4o<#) za((hr^C~1P=B)nRug=CUx{C`0Dj_2Ch}q-L`Ei?BXRgeaWie-6({Ckg2YF-!Dj`BV za8yIWV$S;8tt;VpAc0DV5Dy&Hkg%AuZg^oOoL5Mo5+cL{M>QlY=By#Vu7vi11S%my zJg7y*+y;lxIEaMBoOR~G-$Oe`0+kRU9@I0$+?V`F;~)|ibJnae-$Q?e1S%myJaAM) z!eY+)ti>wmcacCPM2H8DYDiejSz|6+1>*-2sDuddz)=kei#co7vQ-tvK~zFS=8=tR zNLb8SUmv|1wgbmOR6>M!;HZX##hf*^v>J{F5~zd-@xW0H35z*v){Z~Gd4&WjAwoRp ziY(=8xJfh)B4IIS{b}$I&_0krB}9k^U0J4lEqW7;gGgA+SuNlC0opkdsDuddz)=ke zi#cn9P1Znvg#;=gLOgI(L&9Rt+M{+2^t(u)5+cL{M>QlY=B$lRS_9(;5~zd-@t~Pk z%5$~LUTj{4gvFdS>&!LT*yZMG8G%ZO5Dy&HcqCgdx~0tXL5n$yN1uWF-{k)8#@gIC zXiA6>4;89-ZCOTh7LPtZ95+NgkU%9w zh{qF)TF2{8?w#&>zKnymETcJ#N1yM;U!xvKpb{d)14lI^Eaog8eWuq8QV%3h2@&FP z;@}$!Hy<=0z3;1D)ks*(Sv>l@diX%~KmwHzAs!9KL0gv5oF$`=c_4vGh{!w|jDxZ) zqdAL5AM=i)hU1_qAwoQ8%S*hkCcJ%kH7?6y&f?L>9}gr@2@&FfqZ$$xa~6+2{=7m0 zl@K8w-!5vMzCWpV`p;D|4%)Je<}4n4?3|7wBv1(v;&J49`=k$08(e;`jDxl;qdAL5 zA8VUYgaj%fLOgI(L&9Rt;?c+VS4f}|BE*AwxRm?EK}XE3Lc(Is;?c+VyGWoCBE$nn zH6$$NEFOJql%Q`dVFrmxh!Bs4RFBvY4~@shmF^NT3oT!~>u9Az`u0 zqNj3p_Cyg9{DjYx5Fs9PCZ>Guj;3)C35z+4pUV06fkaMGKP1G1T2#tya3+m|NLb8S z{8Y}jb0km+5#oVQ`;f4hv-qi;@2`+RB}9k^^>8WoiQ{M-M8aau;-_-H-$eqI5FsA; zv=0f3Ig6jl`SAk@R6>M!;L|=NEOuG+6fhgR8a*F0B}9k^KJDWtd^U1g%vtWn}oM2H8@?vSvUv-qi;pMM~MN{A2-oZTT|F=z2pIh!p-5fZ3`2=Tz#9TFCE zmOPaU%?D8l5t&Ce4kBSOXYo@xza2OqL?uLs2hQ%0u$Z&>shmF^NT3oT!~5+cNd?y#hMPi88OgGgA+S^QMa zw{s*=2@&FfvpXa#<}7|H=ld%pPze#@fwMa#EaohJD(CxMBv1(v;(@a}BrN7Eeky09 zM1DSqN{A2-eATi3CwzY^ShHH zzgxd7+wsj79n$J_e5ptTDoEIO;^MKQU5E6z()iLi+Hxc?>%>LFld&T@smGwLH&0t6 zACw*>0u?0eJ8|(Cwbkb7W_2Hw9-u8p0<&87ejr&qxsQ7M^yet$|5J!S1qu63Ts*4w zh|*2y|7{Hj%zE^^k;&r&E?1AodVWxPf!3@@1S&|_cjDqPYyS^QM{KisdI9ZSBrt34 z#>Hgx!?&nMe>xUjx9pJiA_5g8>^pJsXiCJ_bQB+JKw#DhJ3N-0`@(Sb7;x60(g}2? z+(85?NZ5Dc;;|*2Q-y`QrE};AB7s@2-!(Ql;hmA{F_F&n+vtpcod{HruFL&mjU8BzXSG-=B-eS*wnyA3Lum{bXjI z$Y)JU`kgb{j>nfr)J`Pg3nDnnD}K55ow#^({q~63ooKBtq_siUMD%jz{T?L50qA1o?QNf`ol1t{!I&Dx61W z$!&C&Ac0v=e*7w&S6ijy3(M$Ce3S@Okg)H>#iK6~wRE;0(15_Knl*Evee~M@gTmF+ zqWTem3KI66xOi++_d($nYPDmi)gpmer`$ge+WF>tL^1t$Jp(F8*mvUM@#~+X_y_HM zkie{;CMpn`;bCoUczY|$Y;f%=n&Y40L|StqUh5XO%m7w#56d*-0hS|U(E!oCw1kE!qN z7B{C+?QGg|Brxm#A3uU|utSH=@lV^z$cYLP_MNzR3?$+j>VZC_Ek^>g-tM#n#&fy? zh_}`&0925$FU!S)t}^2F^eO`h%z9|V68FWrjJ2H}ADrIux8v$ByLCR*#qr;qTfEPr zf0gY!agL*?5`kG3%hxqKeK0URW3TN>hiw~Ip<*#F*S-@Mk4gk)Su7r3(^G)o={>S( z^d1>17V~oLJ8|)-L|~T1;<4Mh|4HAy`nl4lhfl6T#bREreJ3s+l?cqTSUjRF&q^=5 zJZJ&-gW7BF>Eav6fcjDqviNGw2#p5e_w`3jt??Ux`P_dYoYu|~BMo3%a!lMC9Xu+_vc86 z$8U5_E!pC%^zt3*=vx{8&AG))*mvSWS0XUWV)6Kh+QzQbMta|Nin(biW-Hi+Q>Bow#^ZA~4Hh@tE9cyV9Sj&)Rd&QPrqe%*(a!#Kof$ zfms%d$6eIta!-2Zpx)J}SS-tx@5CjpMDX<-f2EE@=26QYEkBn!MgCiMPuO?jnMaVo zEQ_;!Rp5O!y6Io5QL&hpYu|~B2komMfms%d2OUB8TfeKn>{X45#k^emPFy@H5twDM zc+i1H z^_NzmVlgk*z7rRZN(5$EEFN@47V|Y+Eq(8dip9KK`%YXuDiN4vv3SsxWz5&2SH5$5 zTU0FO<=S`R;!%mfEQ`g1`rMeWskiKW>u^*omgUO#=Mq;U?E7;h#Dl+B*Sb+@6v>zA zQeoIHH}6MvqhhTal_N0AzI~S^QQfFm>qe!hAc6ZWil}Z>taYPu1ZLSc{Nh1%qhhTa zm7;2##jmi<2Wwi*zgX%`bS~n_11qnQlqloH8#acHiM_`uKR1goU8x?Ea zs1y|>usuc*)s1olRgK6Im}Rvg#DnTa#acHiMFk1$SE7jOM#Wk;Do0?J)wmFkr!Lzh z?tAAarT2cSNl`)K%YiGC?p;$?*PVVJXXd7HzXe~H*8H?riV70gqefAe(^|wMwpdwu ziN4Q30<)~ThpZJLRho*m(o~MXEURlG9#mX(~tLv!u?9cu=LOf>xTMc8-c%4RBwQ zzv7@uQw6Owl_N0As^5qQRhlYjrKuDZB=E{9im1|5K`Tw=2+Xo7KH@=@rV3hViq1r- z6~qb>cm)_mRB5W9m8Nn8W?3~N@t{gmwOVN^MFk1Gl8qv&G*zpWrg8*kSyd(Rph{D< zT4^dp1&RDMJXM;ioh_B7azs8$szZqfRhp{TN>g+MQSn#$`I!Y(nyS}IQ#k^&tjd*m zP^GDQtu&RQf&|WxqKGO@)oZ1x9D!L@txG(p(o{(+O{J(HfipcC`KVrvR+`EYm}Pa! z#DgkLm9)}SiV6}qV~rxJG*!|{Q#k^&ta_SwP~E7KR+>stK>}yqQN)B+n#vLREU6nO z9#miCHVRhmk*(o~8H5_m@^im1|5s+Fd41ZG)1Lh+zVQ>j*(N>M=q?@ZB5nFy^kl_N0A z>MDu{Rhmk*(o~8H5_pF#im1|5s+Fd41ZG)%Nb#UbQ>j*(N>M=q?-bG%01;YgDo0?J z)wvW8sx*~qrKuDZB=C+Wy&*(|R+`EYm}T`k)q`roX{D(Y6(sP^Z4_}E*Gf}40<)~{ zsCZDNsZ=XXrKli*cc7z)Dov$YX(~rxmeo%c52`ekYNe?Z6(sOZI(1h>Xr-wfk;6y1B(vu4p&m$}5+cN7Blkg%AumYp;%x%ZD_)B_1rLWFo6LcedggznaUL3i$uu-I)!`$@?jd;Cp3 zkT?gF5Fs9ehD@#lBOO>XOuvoIDC8I{1t{zD6)siV8BJ-$ckHfXnlo3XA)XiHTk@RE~35z-Frdji0{6GSg5Fs8k;-oxA?MGi0BVjRT?Y;Lq@Z1>*R6>M! z;M?j}o63!lTBmBqMR%9^J#?M!H2kK)mSr?&@%If}aZx;wKqW+oN2qoiFUx4o;_o!L z;-YvUfl7!Fk5COdUY5}=OY6~z2NG7>t`Z?04ZoG)>Wyw$x?IlU?`F8-qIe*YQv!r| zglYovvW(^|{{Dw6E{X>dsDuddX!z}tEz4-hk~)Xtfdr3aTtAVO5RrM*T2)6REaoi! z9?QI=2*29OE8>TQc+i$-)hUs%n6vo1GJiafKqW+o2OYtz$|e#PyDY7rDfa9pv z%vt>1rS&mUgaj%fLOiI4%c{^KVKHa%_oKewMFN!&As*CIXVr9(u$Z&>J6Jz{Ac0DV z5RZo6@Y=GBc3E2QSI#RWtd1}%AwoRx>t(CS!Gy(}#or}!#YOQz0+kRU9{AQh5*Bk7 ze_zcN7sUe!R6>M!gleSlvW(^|{!W}LE{X>dsDuddz;7Cmu$Z&>dv~t5C>}_l5+cMS zRI`ScWi)5;cl%s%Q9O`9B}9lvsP+yo%V^Hx`U6~XQ9O`9B}9k^ek+57#hk@;6u9D| zcp!mFh!BrZEhJu+(VWHgAh_b9cp!mFh!79_b_ofKIZNtV+@l^ypb{c7k8B)7!eY+i z`W${c@H;P5LWFqGmS@!|k+7JvxXy?_9!Q`PBE*A^U{+-l35z+4>!tYf3JFv~gm{E% zp7F6YnzOj>i*FxDpb{d)BUHPMJ&fiou3zKZITEOZ2=SnvA-3wRNLb8ST!+W^S4f}| zBE*AwxU32-5*Bk7*Aw#nE)uAO2=TygUy-nwv$!sjA3u;lB}9k^R)IpoV$QNUhtkfG zKqW+E9;sDzv>J`PEQ>jdzsK_1(eOJjQ$mDz;HZYnvY4~@yE1<~kU%9whzE{pNLb8S z{C%81uaH0`M2H8DYDiejS^S-!Zy!jY5+cNdT2xl`6bXwti@#U&?HmbILWFow&yZDb zMZ#jv;_ohfe}x1pAwoQGR71jI&f@P!eZPwYDj`BVa8yIWV$S04VEy=k1S%myJaAM) z!eY*n?|DPxASxju^T@_QBrN7E{w~>X2abcNgb4A#Q4I-;Ig7uq_QwMWR6>M!;HZX# z#hk_8iTm>k2~M!glZ1(vW(^|9(}kHf_NZ-N{A2-9MzDpn6r5F;ffC8 zfdnccLOen>Ab43ua~6+2T$w^VkU%9wh)2V5(3WL1XUXVe9!Q`PA~KH#Bgb4AVEzhb`B4IIS@#y1^2NI}+2=TyC4GD`mi$@=SULk=>h!78~4ugcn zoW-M$Zy!jY5+cL{tK1-AF=z4UM!G#m$QSw?dfk3N3smQ#r1fB_2rRlmHgb48n)u7{L8SS#P z9-Vj~VYTfl5#oVQ`;f4hv-qhTSNIbTByx(b2@>KFstL%;GMcmasT|iM6b~d&2@&Ff zPy3LtShA$fp?Dy{Px!dvA}b*x^Tjd zpUU~;fdnccLOk$k9}*V3EUlj@`w9tu!p9XCSqTy1L1$uCEffihIg6jlam7XPKq9B8 z9}?n0Eh?*eiiE|S#ZTpYJ4XVQ5FsA;v=0f3Ig6jl`ThzCR6>M!P!E??p+&-C&f=$X zzTZUxl@K8w__PlRi#dy*%K7mF2~RJ|2@&FfvpXa#<}7|H=dZ7jKqW+o z2hQ%0u$Z&>shqz~L;{r%As(Sx-h4ca<}7|H=dX8>KqW+oN2n$_dl=1G{8Y|gwQRZnEQ@7Hr_wp~2c27|(6<1nSj^jT z=#G<;1rMI09+e2pvRFJ$f-e+Mu~_!iv}B{GuXcy{NrB+fkCw;A`*w;7ftiYKOh z^df8rc?1c}vN+pU1>RTd)2|hvVli*WL&H-z9<;B51ZG(*9&`i?e9RxCZ)H%iSoYN` z+3~0Iq5=^`m?g1z(3u$Xx%(S^^J7_}cw)%9+0Z^J5twDMEQwlF%x$np-!7qIF>gnc zf6Re)UWvdgi^YR_hM4=3Yv>y+R4itXaq(NwUsWP7%VP1M9xmoS@p<}|3>Aynp8pJ+9r?$#3_a=;A1%`+#TC2Ngtxj#QR=6fZ-?=IoHTk5TvbJAL-a9?!<_Wd?(fNxC z5)+s7PriKTEZvR)ExV+@&0Vi>&t`c7v$i^DQ1bP*AE?Km?p@Lj=Qk6PG7r6diB}I7dm`glVaAu`v)aQ-?WR{qj{nj@0MP5{*b~>v{tAfam$QB$%MLH z^?1CwV5jtitA`gx_0JQSRn`CcWYVWc>sqbZcjxr3QTG-OSW=T>R)>k#Cchncl3Q+` z_@vi%>9+?zS@=7x6)H$9UT|$Pr~fIsR((gePtPvBP}u0nJb_s^ti36DYWWads~a}k zD!uX4>4lv?sYx-b`*AlW6E42dEjLf>_DkFJ?Qw4wPNKC!1&NdHyfInz>`l5>U-sA} zJ)!5vh3<>;1ZF+7*KNuBx7@F5)oaWq>9?nUQdmf9g;|?U9GWzpKhiBXPs|&*LE5X` zszQ5OD^!q}^vBTTkG)6fS`9C*E1h-i?}dM@-!(^I*4s^nCBOgnl&;k^+ehg?H;>}i zKdnhI>z?s`%coen!NibrGwUQ6<@V? z*BpUa$DV#)((Bh3b*O7cFWBZmpuGt>73u&#vN#_ zP(kA2(!I&o-_O*wI^@pjrMvgrGM;`~*BpUa$9Er@tUBOzJFkXJFMYb+R`I`<)})yA z#z7AyAN85%mYXNiy`L;iKWw{r2U;sskT~#*hmyZNGGEu~$lmvr4(`5VeE+Roa|CAX zf9b!HrYsy@!-uIAFK<1-cqX1&Q;? z<6qrA*0q|m?!?l&3wMuin$k5#U{?EIo=7%b`;o5I)>Dr!o%{VBarAjjidn6%dLr4V z{&Tn7Jh5z#Jxiy)(kXt5)(RCQwmZLIsK2Pktu(VzAIr zw9A71>s#O7C0^d7TaLi2^KW`KS?`Z!x>o6cPW69(n=0dfQIlfUF4sMqEdTvmw^n)L z$nBc_Wjwv-wJ)s|DoC`vep)hJ=_tCkZQI&zqq@Xz?Ak3yVAlLoUP`(Sw|!MRtYhsq zv{u8ZHWg<5a^Fiyznf%h^TgOi6KXG+ymx##traRrJosdN@=j#?>Vi=})}GROulSO~ zyX6SXdVZ^ylj5?Ebzj{zq)FjiI)Yn#Rg+@YfV*E#UK}T9MxNN}l06HvXLO1;qqRZ> ziFnd0$@F1zRz}gw(+)2*js6_pc5$~Hfmt_)q@pVm#S&L43 zBbjoYw4yvQ^ztEv!wb8`7tmUvg2W})%}IVKFV?etqb7G1wzzV~xa06{IRdjbS@m}E z%KCG3t-3sVZ(*B`JIDW`wZg2HAIwWG-sK&)+&nR|_mhRoduj&EvG%xeAP!lc#Am)&yn z#HiAngAfmz4y`DqgUZG^7Xwwp!qJ#C}-4_YhC+Uv>Bl4AO>TW+3Mdh-VHJxx~? zPN20y1&NLmmL~1Cdq~%+!^oEL*V}$lcy-h6IRdkex#IJrPm3FLtq!_-lX&`hpA<%Z zTa#i|{gz)QM~uD2EjLeG+N3Jp`GGeJEorS#LE^OLUnMR2T(4{O@Y3pdn?Jo&i1z57 zBQOhR7Ev_&_xADNbEg+hSy7Xsf<*CyZ<0&9pROLS9JO71#O_ZPmNcQ?!h*RBX60ur zAC9d_clv5zeb)*68ww-c-09bcAEf!2zqe@j{bY9c9TBs>99X|o0|K*}(64!%+oF1g zENSwdozi2m@w`%zh{wj~iCor@CzEv39_mp%Y((i7+Qa`OBFZWLuA|-elkFIM$cR!z z#A;eABrxmWFON%l{CcQ*ypZ-NE!m?}`YRErAYu3Y#AD6O9;I*S+?qjag#>1mj+~UN zeXfss%=%_v{b5hnq%(;?1&RDUzym%WSpU{jHEHi>@B#DLbX#5`hX5`Fntm60z^!c1rK3wL&77HRNSDufE-A zUg1SL6QAHM&nf<{quuwD?Rb`mn24?2dF7XdS!+(34eew1+9*DoTGVz#pn`AYu3Y#G^S8OIyw>4Q)VR)-R{O3H{ZDr|uLt zrylN7B2YoX?)!wznpSoEPub1h`&+qa03x}#S@pjIWzh0%3-m1thZOE^ud>V zlqNJFFzclQ%gK^soAwlsZbW?ZN{`Z6M4*DiU%SmriU)1dQ#_9ByHncfuOmvQHXtzT zf6khb>=gA>k4uU8n22^npn}8>NjX`x?nw3c^zOFlHk-~X{Y-lq3CudQbDF%opuc*& zPQ<~R%qtyC9;hI3_P^7l%aj|{rhjcf-7wOUbS~OjVCJ z4<`f_bm%f<1a@ou3F>pqY(w3b& zrSCQ%FzeE)=aW6E>eZtsol}Q(>Xi1OwL%4nuj-ypwtj!EdW>5=u>Rq3HR)Lmha&6M-%%U+Gwod-qfBW?{IKqA^|*M=z}nA<=+J;*+OqCkJ_WYpCmIJ|p|v`m z)+(=fV$0GL*p4No9)$;J%g<~;VAfGzOoHQ4KdVRK8ES`1Y44(f#LPP;!SPsp#E3!< zZdDD4eAYxbuNECPqVP{TOIp)fMUhu>#E@s;yt-oJd4;R#Ol;MFh#>3aLnc7`IAfD} zg-Jy8p}m_^fOzxK@z6ewj-&Wb)S^yoKw#Fix5hy`??=RLMD!v86(mNs90%?EpLf$Z zNIe5xW910Ux@Y9m&|kH@L1~a((lM;x?_`p_+M7 zaR!ep7T??9!qTgYUr9=>M!3J{2~3xrS;5(_Pgb4A# zN;*hb%vp2(G>iI`+tdRIR6>M!;G0fJSj<_k{e4#Q`XM)|2NI}+2=Tx-myxiTv&K%F zmArfMwd#QcDj`BV@Jl2lEat3MtzS*%K6jORAc0DV5RadzHdPmT*WhG&*8mBNIcwJe zuO?02y-YojKqW+o#~^rz9tn#%Yx&YwlaAdkQ4b_g2@&G)3Vh*)gvFfI>gd_Y&e6r{ zfdnccBJ-%{dSu5?T}~t{=B!R-nz3ZtK^_@_N{A2-+VT>AZ}2p|i-Uy4oV9w7*Wh>{ zfl7!F4?2P+KIR+IJ4HxX%vr7Oc@54hBv1(v;(>4cB4IISUG&{+&_0krB}9k^e#wf2 z#hlf9zt^FiBY{eY5RY~AuG&I+zhnZvtA>QdoOQ&&*P*{c0+kS<+d;?TKzh&XD|+V+ z35z-FvZr5%eiv(Upb{d)<0E=!=~$}y`a8Wlh=j$Q)#tU>Vf;V>l@K8w6R2&hf92%* zmCrS=Lc(IsYW2?R+1M3DNT3oT#G~OC3QeQ!VX6*AwoPFelcRpGMcma>yaPVRjCIOsDuddX!zxeEz4-m;;&#n z-KmXwAc0DV5Dy&Hkg%Au_-mfe$8V+{NT3oT#G~PtNVY7aT^4VX7*;bcmP z5RZmmR2gA3XYton(`#C(2NF3&{g4okhF^x+vW(^|{z~lC!#7qBBv1(v;?eL6H(Qp` zk~J-97MTYUJfkxuL}VV>sD^~aoW)=5nYXLUnGtzK{E!e2+VX51M8aau;;#>FA4U-p zsDuddpd(o7Onq-l8V8ZE*k#dIl-aouA;Di{ni3+!gU-Zs$)w)t=v8}HBVjRT@%N*4 zPDc?EIYs@D5D#im=@~8dNoU@>Z8Z`Wa~6Nq>f1RIsDuddpq?RphQ`5RG!7zRF=z4D zxz@+Hx||t-N{A2->fzEcCod|EJ7R7X5*Bk7e`RcaWfUQSN{A2->Z!Au%Sc$vS^TxM zA3u;lB}9k^jX3ETdf&PE^yXDaSnRUstM6>=ijd&1$xR6n;&DIC2d}(#a{a2AG9TP3 zD)zMbAjh1=v#^doJnsG;MM$8+^TCFMc;KjpgvFf2v#`S_j8_jNPze#@fwMa#Eaohp zh5fc}ih3Y{N{A2-oZTT|F=z2CY{zLYs0R|Lgb4A#O1DT@%vn4OJK@oidLV&Hh!78~ z(1e7=oW--S^&g$79!Q`PBE$n{cSu;wSv(87;Qm?afdnccLOgJGhlItP#j~(u&zh|s zNT3oT#AD^O$+Z!+!-w;luS90^oHgm~bnhJ?kOwWi+~=&z7KB}9k^j%r9)%vqbhI|lk)Bv1(v;(?Zsebi?xY?_pb{d)qv0>O*s_dvS#&q@kKUct0|~yf zX-bF?54_8XgvFf2cOyH`>7pJ;2YF;fUJ*Ye#DliH)T`Hk^tiVUuSUXR z&f>d~whyBS2~d~zMUh1N{A4ThWABnSw?df-;MPB6%wd~2=TyC4GD`m zi|WKana;(@a}BrN7Eo`w12fdnccLOgJGhlItP#j`Mf zULk=>h!78a>jepmIg4juzI`BpN{A2-eAolT_k;u3j2Hz0vHX*~vE+BP z@=9ZZ=_u-Q(13WswKtR=KXRKYBrN8v-W_Krh2xs)mljB%5+cN-8`a+VjGoiKyXM|1 zBrN8vFV2~r+`2AS4(?H4+wc)|jha zPd;f|uO3LC5+cOo{Na;p&!TqNi)w`-VXqss|EL^G)eJ86+%r zSwrT)d4)s-N{A4TmDK)5)4BTu)zU-4V$OQ%yE)K4kjN?OhlF_G><$TwIqT@Z&V_c4 z1S%myJnp1zXi4`)H>3NaNLb8STaTCv{S^|Zgb49Cf{w*tIwni#z9mVZz7L_{eNky0)u2PdV$K?0Ga=a|+DyOmLIRZ# zAs(;N^TAygwoc!o=YvRC%vl?5^-OY3hrg%?5~zd-@hDSGK(1c)1l0sY!eY*9)@@?) z=EJ9`2NI}+2=N%YuyuSLy|;Z0)iy-JVwW{!QgX)mSE>gR5hx)-JU%^bQDK*6=caY5 zc^rggY0Oz`znz@SI_hTiKq99E2=UmPDn~Y@cDOOsnnc24&RTxa)MWA7cc=#vsDudd zczp2W+L6=_AEa>*35z9bTC#lIUFv}Z-`O-JL}VWI>~Xjo2R&glXH^e-4z`0lG9s@C zjf8m6mX~;6okrhHAYn0QHEa6<91kQ=2@&E!N3g`ld@_xLNLcK$hP(*p6%r9BAwoRp zOicOQU9g(RL0Fc?oVE6~>Cirq$SDCrJg7yb+y;-N+PFwq%vnEw{t~ovBv1(v;z2z_ z%6-X78V8ZEn6r+VQxE+W5~zd-@t__q`xGAZ!2KCstUi-JZHLJAba7IxIUAw>jd*Y`^6_P(h;R zy5ZS5ohQ%(>4oRtQQ^Eo1qqJ73ZAUG1p?RiiKY)^XCM0Iw*wUQT+G`S?%_~Dg7?D7bB=R# z-UA8D;=Mk!Pv-!E3ZGY0ANK#SR!H#q)^7guGaC1BxK^0OfA?n$_U))3!ROnJ&+S{m z!suDR&{k}+y-a-k$k!PPp+jdoAhgT{PP4VNc`o&b;)-(4hXb! zB=T9&{@(=0DEr+V?w9O$emLg6Zr5E6*UBq-;(xOpNZ4-|HSQB}J21Ouzlp<& z{RYqfemjt`UkPgLf%^ora3ALP75~cAeP`e8jybP;hYuufzGQW>-rDhj-Uk&VcrQfJ zJ^vp9vv^ONUw*B4eQm9HJ2rl5m|HHkv^-(IwZr?weo@EvZn#C^vXHRf{0Z+}TNY;F zUeB);DoEIG7ll3Sti~)nd-5Lq+i-VYaGTpd{2Ok+uDjjEYpZ^uYtefH#{>5$pI4hb zb=UuA@8Z5fg4gQ$es=~ukiab7CR@Y&cA&!h%C-rYlqXO@f{*4+FUgf!WdgJC?8y_@ zC)%&q@lo67pcR(JP)m*w59xLizp&N#7vNT2&Jm6 zIYEpSIa}0NlxRv~p68jGD#>qs&f3q}?{&`Fjs9_8ujh52&wD>>+H38z*RV+_Uc5d? zP{lSK)(87n`$C@5&i*(g=pkX>@N3UG398r@!Wi_Bux}Bz#~?u!TTB>(_qJ4a-?0os zf*ulzXZL(LK^6P_kf4WzO2K;Va)K(3L?NO3+@7gdnfF1p?~)HS?mNZ~2|k7QeChG( zUuN{VUv)5i*;&=YIu>r&ArX3>uYR>w;#GK_4++Ldl7d)h%&XNw$A28@8AwpY{Dm>- zA<=!@+tu-3KOc!ff-06<7(;8pJ0I=Q$gS3FAGemb`MV?}=m`k78hh-G-6N$-LaV$@ zrM1-^JH!Zjv^x5zrE*p9+lRk786zOv@2Gk6yDcbHRDI7nFRrU~&&?DDzd2dwRB07+ zJm-2F)je6dkzNt!ec;=!{y%TN+040iK1^H5w`%QB7`|OEpWE+MRwT6dpxfA<3n(k9 z*m}ZNqP52l4_mBpEv$yLWo^sP&eL#Gr?S)^DG-do1T9LRC?QVX9cVBvcCnlLFv*%B4`Vx1XbF55bv)75Bl@+R>FMfycElAkisBUfd_=H6fa#8R82Yf!ID-& z4+)iFyp@okD(EYNe9%L}mtm~6lc0)ye%KP{k3AbtMHd#&SLI_AS{z3>w$LyJJtX*K zP)<MCJobKvDbbbUZ;I$4p%mJc z!WcK5dQ9W{;QklZ-p%=l@#{0$4QMHPG0Fje%BP~F&j_;P}(@}8QbfqHGbE@PL+Aff&^ zo^xJ{D&99?40=eYKeoClC#Yht6cTKss{f-dI;GkB*qnDru(gv=8;keUB&cFrXpdp7 zorGHcF%!o{Mgv}pD)z2n4E1Uges#`B^|k6Bzngz93ki-;h$G7S^z7MuU&rXiwWNA%hm#sMOTC@2eCUpvf8B&8 zVJoXbg5{&OH2%o*8$@|o(L+M5a;fVtXwYE{5>&AaLxLU>x>qbu&Cr2nl*f z_;KabNUBIs#eOV|!B(x-Zap0Df{>txgzhfuE6WM0*rwYFyK_kR`#+X*UW+Q;o9!`d z^|0R0^jPwtMu~EK3<UuXPJ$|xh^01+K@SPN*E;L#=OZylP{nc!W9aSq(d#YM$gSRmcOScG!`8d^ zM}{pHDJ#vf%$@HE&6u43fiGSCfBt;4IV;0!X-43TS^m0=U7jiunhP1Xdn`t9tw2?z zHjKf1@Vc6znK?BUg9KG!DKO`nl^ME2_eLpd*6Qe`ysbCs@j9m`AYADtNlpiEIY}sm zP1W~oy9J?qG*cMHz_qASDOmo((q&s>-Doc4p*t3dv@3c@Xtt)$14}M|ph|C`t1tDA z5cH5>FA?U0M4)o-$mh?G^(8@>xR!Xrjd`u148s`g8PpPuP|H7ltsaqlkf2I;TIJCg zq4@#xXzs3g-S5>B1H#P}S_)h8!D~UqyC5W(Uf*JR`rLl6vLd0@v+;Jl7Eo4H1+^Kp zc6vytElgi2R_7!FRcR|>Z>js7y{PrBVOg>FA)(S;aDPRW=8&w<4`a|nLi6?UewPGQ zYBAQ&hcW0;tF%!jxKdCb^pMc}myK6p3=&jnhA!Th&_hDAa`FC(1XVrVswaEm2vbE5 z3C%9X`zsQG%FTJkdmpK+jVea-p5VP1lrF~)6227j`>~XuihWF&bFH8%o{F9?p0CPN zg&Z zB}}DNdhs`RTFYtg+o;kS@$O0N%^f`?w36Je6y`&#eC=0?R{7d*^74GpLqb=IzXPC0 z>yYg|1FsaOiXIYL108>tL4qo+t&YDhp+{@B?VSv-RGumlS}z`d*T-v7#kvV&&_hBi z{_TBfIYCuY8&)IVCel@nC4&kqTXIJ)nw$6>D&67-PJ%Jq1k zNP;T1&@cu)B($F1dhK$8D)ty5!ImMF)p>a<--_(2Sl)+JBXoC%~pSDjIxyjy3-cCN0EejpLjla zEvjV4OP3xJdWMh3AQ7k>5sx8N(}U{MRE~(pkgDmyb%WDr!qNpnRryIFJXM9~zNnt!`Jjh{ zTF-)sK;>dI^B3j=9ul&@A7QHSH#OT8J-jY|izZ30ea58g4Z5gv?3$lWv{M5n4L{YL z$`hU-P@JSwM)1S}v;CEJUhRbRs2ldF+;+&3UG$i(Ss9+(lO$yXRc8AbuRVWMTK#Zp z<)fRYbkSqBV(!?PGlI&g;|P8W#u1*fRw^F0WY{lUHpCn}jRc8AbKXGm9Mc1}2 zU1i%EJ!UILaH>*LMo?w8kMV)KH@0>6$X|c6Q;i<86(cx@DJdhUGTXffIMhU9S_A%TYmFXUQa+M)9ddyY~p4Qa32cra4X8RbfXUNn$ocLAm8a-w!22Y)8 z^d(V(DzkkI*TZG%6JPE2S{FTLD+bTSYV?Uwf-19p4A)a<>f3KWX>u1mW-A8I4NHF_Rk%vKDZI@TDYq6AfD`xtKI%rw@%^4a?n=`mX|c zneAh^CxA@P45R;aU0-_4R*WR!xlv_AsPcr5amMQ%>98pSJOA-khdY(N_yw6H3pLKE z`Kr=)vpfEtY<}3VlQ)x{BwdbpV)DSwtc9S8zb4&9-`ODj?&jAz|LO>ONF1?NvU%U9 zzsq9`cf>Ncyw>@*7J@4N{!Egkzgjo#dB%v!bVtxbV#e0-V2E2}z!9uk|L^m+Bko2TY6 zdcQX?o#BW#T&hS=#rHw(dH2CS=|SJUUU|n6^pLpfgpaC6AO2V#9_BC9J2DrR@=m>g9 ze179=)%QO6cOGN3Bi3-l11$tq{LPRgo9y&pWnovsBIqHJBrjASzPfwWx7~q`nCois znHC~cahB}4QGc#{=30tcyH0UvuDQZ>kAHVo_2uUm&0`$lTH)%hHI8o~s0wE2k`G)< zKf<;6(;Pt$iA_&>qB`b+CG!~PIil)_ds_&qdImGR-;N(qS;pP#_c($c5-UCNVD*N{ zOXo4VyL)_)BkpP;sN(Fh8=a@V)~O!oZb#5V;*L+JSD#&TU>;*7*H^v#_6F%-*Ahuk z#aZ$s`Ns928@rx#IY-b#LeF*!CClV7X5KWgb6H1pwh*C;>#ts#JaGClj@Z-@QWYy5 zitBFwgDJ?zhc^wJzKJ804-!;ywNR2wx%IW_vt7>B`_Mz;6Gs<<99N%sHl_4-iP!#(IyMGuKXS3M2=?zWCtB=1E@ zP{kFLNwQx5Bpc~^>i1m?dPv;2=!qCV20LQj(n-3eYl$SN3Rh-6|3IH?IoDgS;0St1 zoVoC?F%JIQ5$8EVqZ$dS_zo~hzI=CJ_LUns-*f~$B!>Uwml)5VcEs--v6@R2397i) z!JT1!$V%Diu74ls2zp4Y@P7y4xn$)-SIW9v|E{)6f-0_>PLe$buaPY?>y*j_N6YIS|M_y=>^;}NYmB0Y#IC#URV|(q`+l`$Ubq;qI$BVhs0X{+Pzvl?^YeLs_WnN^h$y%uEuXXA!j4qGxdFrpoc_~ z?B3V~;m33L6rRm+BZ8j7Nrb9mZ%&fj&}&R~_z6=x&z_iG%u^i9KJNXqDq5FQoXk^ni&Jh$@D!jJ;bY|AuTA&+WLS-a*-~k(VsTmziNKSmgoKZA z(wK4e)7*DoCcM36jfB}!Y0YJEo)8IoVuX*8e;qh|ZqAN15@vf9Pnsg3XCFI*Dn>M8 zbUxf`OuE}?yENXz8DX?kTEAW7BmXXPg9tr79tj`A<-DS@y79>!Y9!2-N^78t`XE71 zjPNn?uTH0nKDT*|gxL+1TPa<%D-t|0DMt7ht|g}Ko5iX7W^s*#*-~k3b#Z@?2t0X8 zNcb4;j!NI^J~aKwg+pp2%$7=Ppo{yQ1U)gr$8bGEdh@^fr4tV9Q6pitR9Y!r^j9S4 zi4i`A>*3N<4xU{Zu>0d(B+QmdE2WEmmjpdA!pCqub=q&-xXQyfpVdXeY^k)ix)?u5 z&=Vtk3^(GW8lz6WyJr^(vl}X$e$yD$nnVImjPNo3=*Ge0M^Eki({<^^+_h!4RNRl1 zBqZpG5kAI8TaC(|bl(&Dbl2s(NSG}Z_hTgq33_6LkKw*RoNeXm{CGDGk}z8;?%+xi z67<9fA0z*2X!?;G2T7PMRk$;Z1U)e#&&NVTvz>bnO^^Jxca4PEQgLsm%LfR0VuX)z z?d*P8uc_{PTZgY)BVo2w+zsl!0Sbbi7~x~AbI9!as_s7A$&G^~%$6$LWlDmc7~x~= z3he0#UYyGWQVRk(+j1U)gr$8bG$s=oaq zHx808TPmJd(CFKn1U)gr$C%>ozh1wa+WFC4J-bMlEfr5JaBtN>&=Vt?F*3#YP^=OU1Rk;W$W7jPNlys*x~TDz5Pi$3c2xgpa{djfB}! zaV2P@?PhB28ae5S5k7{yqcYutH@R_;gxOMYC1~RwY!dXu2p=Q=nt3|+u$5~h%$AC4 zM;m=f_Ux^@GzfZPgpa{djfB}!g=d5(c3r77`q&wi z?c<<%VuX+JclWK-<=ncZ%)J-owak`Eqfc=L9SM43gpbiW4%)ShmP(^fah4tldSZl+ z@!LIS*C+P+WqRJ{!)heVmP(_Kt=Uf!67<9fA7iNrCa>eOM zBQgxOMQR<7u;NYE1_ zd<@R^kuX~-&B_)1E(v;Kgpa}5J`!e2rCGUR{2)P3jPNnsh?8oJ>N(BN58AbiZm5DY zok(bY&_=Zw;bXXwGt*dm{!BkVXk)5o`|S6iX60-QZj7}}f}R-RWAOJN3A3frteic4 zgue&ri4i^qe-Dx{TPn@U*;7>bdyt+O;bZXkAPKXj(yW|4+l9Xe>4_0OhI_Ki^ej5o z{T?J?wp5yxv!~j|vuKl`Cr0=fob4lFwp5yxvuEx0`9br<2p@yL?szS;rP8ci@%w`W zJu$+^;IBIpW=o}6Is3H~{vMj-*C*gkO|W6@<+NI!MN4KC*-sJeFb+0~mT{V0zydbz%7@9Lb&rH-J7gzXdeF|HWg zH(he%oXRCGRV1kTa>}ggt5bK+V|=+*lIrg^N6d1fBt{Cg)?&KATJ>C5vNx44#mj%)FcI)WY&woly0IAQrgmEJ?vPk-ie zPJ*g6AD&hno?Vs4*z?sLJBL2rk^bBf^pMc+PwhYVG5+<&j-3^EukYh(kVL4uvwGmq zug+tf@!F2lH*>_kj*zPG6xX$V;y%V7U*B>1`Yu(!aH%3e)ic9yK|b~xGN?Xp`SsI- z96=8W+b8a0JmZK-u5=%ErAvaUM=!Vm^-(`~bbWnSgQ^dDNZ3B{JjTyP*AH{8qRedHAsT0eP&;bes})B6|w>K$(0)& zK@SPrC+=g6am3!PZ{NBkSpU2aP!Nkg$E?KE^eUxHccvNKke7 zVi#Z>Tw#UvvoDAEk&_-0woly0ILQ$wyB_E{mva(St^d?{7|-1kKz4Ed1V9f7+ga{o zxTlQlxcn)D1XVx(x!-^8$J!rVGbTOrr+aoDbM{PkE>5xM-0Y#V|2V_;iOWusGJ-0z z{qCC8=bV%-z21tIK10$jdd${!ZJ)T0QASW@wvX|STSqq6ts}eBts|qyY+cv(iTfC3 z1XX7H7|YK8f9dKc-Bnq6$EjWPn62yDK5-wTjG)SFA7jw6honFF^*fa>zM9=dkJ-Ae z?GyJg$_T2=_Av(Bwr6_Uk&C50s&l*OF(rN$%QrT8a-zF>-v4--Yz5bJf~giB$_d%E5@R4_;ZSiz3c^H`^1|uq6AfDH_NK7vO1^x zk8AXpt?Sx8aUa8#Rg|F0Y#+nbU|n_o>04XY=rLQ@wSD3~Mj1hs**=DAyLGkQ${#vw z^q8&d+CFg~ql}=+Y#+njQFYyeQ#aqRMvvM4x_eRc8Ab?g=2%Gs8blzq*SavvpnDC+=gE5mcG&W4I@oOwT?`jQdR&J!b2=woly0 zC?lvc+sANEWSO4fI(J*XiypIeUE3$_W0Vn8neAh^C(BIFqTkFscOpGz>$p0#Mm2sDTMiBjKI@E#7mciY*U4$&KR1{*3R2TnP7iyc|HP93lXnD60%Jd zwjQR6`QZNZpbUfaUIULSEA3cTp7j4_{z?g|xC=i#v6uPK>IAF7pbUc;fv1INwuMqc zw5hZvp!3nZ^#ladt5rzae{4B7I?M;liiFllX=ic!{Xv2%#g3;+^YYVHTG(GJ-_NV- z>i^nV+#Z8D)arz8V|zAKK^X=)r-y{r9Sq;DS0n}rsuWv$!{ezk4+$U7mvmUVt>VtHbNyG&j$&rST|v+=po_j-Iz&N;J2v?s#0S5AmFl~%y$`xYvNkYGNPbE`p?VMx%^ zN?2PcCq$b{^Y!|gPkXAEUab)NZvLqa6-y+HK@SP7VbZr!+GCKQO0naqVtTa>Kwlry zby*@|s^}r18Ge29r#)39s8Z~B4Yr;}p|1hyx>_NoZ}7Cophvb5DusBeNKnOc3v*5n z312t9+{y{6%Im}SJ1d7;&tSQgZFve~&_hBc9d9KhsAAoOG3X)T>)*HIa)PSzI@eAV z8z;2$#l|S@97CR*9A;A=e1U)2_KTB;nK~;Iq zwNuM_9POyG9*+47W6;w|#7mciY*Vq+!x-8hW4*KXX{+L6u_1Q^oXZ?~;vCERiq2{2RbJ=nWwcILIalAV)xWZJH&5#r-LS({skeM+hm)E__r%-km9!dHbV$(S z#}7~FN)|gL=pn%rh6Ft%ls`*tIYCu<&ebz~w&z%%bJy>FIQis;&HRNi=uy8*B3`;A zWSfem9>&mpuGPbh8q9aE{`VSW4%P2!eX|kq8YCgxRBSzAs+bSu++wf{LxP@G!tz&6 zh&Gk(bFFo5Z;8x@a&Gm(G7MwT(@I!dC?`alO84MV7o8GG71OK!N^7W3m@0Zms8>2>;dpPkseSVQbEZKvBj72W1${ zO#~iSR+bO_znQ;Mf-1dl*S^&DR>FK}KFVq^D8nE|;AtV6ZK0G9Z7R)}JTfeAJpsY= zYTiKmU6uBrL;`{y5}K#bPS*CElb}kmf3JVvwLpvEy}44+$U7mvq>RYCcN4WtBtC8(AsHj^~^n5-RC< zK1fi-x(QQ74+&rYzNE_us=i;Hvz}RQVGMd&iFivSA=^~t^`RLB`z@n+9Qz%mH~01o zAErt(BlgS0&;0mbMVf)I=j)K5hlH+Vu|t9$5=>!8&_hD`v(%OoRF&sk@AU1dSTiQ} z6wdsGG3aR};-yPMwy9X^VGO;~w_gyNF|l7P<@unem5A3M3E8G%>j_iEd?@FZDwbhL z(9=p-{>ll_rqVn8_)|FZp`2R{vJAr*^t2Mz7Rm|HrqcWN_%9ZwS925g{K*mtW6(oF zb0P63WD-;*)vf3qo^9_RAtn6+N?3w{n82^7^p-wHi4!Z)CZZZFve~&_hBc9d9KhsAAoOG3X(o z`nPsmPEb`|=WCC>yn5Fzm))nGI@*=A(}%rg$ew%g71h%xz1sMH7=s=X+BbE>q#rft za)PRd4!x?nSNFaVf*umu|MmRT-4{SmReSkQ)t6_k9UA!1XVwO>)PsK z2W}oAR8|uvz1rB<%spQ!_4{|ZEZ^_U-yigl;BKz4bV*Qk!X}qhd*8NPBnCYs!rfd< z6$z@Iczjah3rBvR7YTYugge8^2&xqO=-ZZyv_yJHDBiF)hcAGjig!VK>Dv84Lgn_W z?sr9E@LE*yUI}BozVA)diSu?FsZ!)_P_?Ti58S-*|B#@E1owHC6IAIgcyQ+0kr?!l z;6BeV1_`QkH&?p%jl`gb1owG{F-TCwJ1r#WA;Eo~_V>C!_Y+yTyekVL4uvwFp(gCa5XHp)D$M6qX_F-XWZ z)z1grT9S{@QxMz%9+njes(7b`1U)3U1H7D|iuYqkaLmvhb@i2J&d@zyK7PdxvVlMady zYD?y6C64_0)e9g*n@V>OMAhgNl>-PWsjBoHlT-uPQQu&HXuP2@3b)I^pMb*Jn`Q+B&g#37{*{*;weYv z?TQ`}JdG%fL4qo!)_#|S1U)2p8c{hxl}bJS)JG2qo?jHkAVHN{PyFeX9uhpiD2zdZ zDn8qV1U)2peo;9=6`uf;L|=*>=DscKz7(4!iT@((60@&&=VBE5`NDmEU5It-GHFVzMbo1EbYGB+tYoy zce*3!A;Eo@N%EEZI`9xjxUT~T1XcD8U>~EO`vUPB?hC|o96=8W?jKE(Lmcr>M_kZC zP-R~~_A#pNOUjG6FDZ|61U)3U4>n0Ib6;x~;l7w25LDSWnSG4=+!vv5bzg*D)e-cN z;C|jD>HXfoY=$G=aH%3em3>><$LRH7pX?z2W$TO{65N-ZB#*jpVQ=k-6(l@zI}`}+?U1&_%DrT^pM~_@gy1T zh&3GXfQvzbD*I-+kFkmSV*0}Vi|H9XBy8`y-#I(b5p(@l*#ja}`R};<7|)IRbNw^- z<#)Aq`zpKl6#MAIefvkaZ^f_fzAit$g`mp5I`6Oaf%}5}5$+52r#XTi5XkG4RDFzZ$B(El^VPcPJ&vG<1kX`$D@7 zYM%#|%wzm;>TA*9#y67( zPT%s?O!c$x~JfGvk zn+A4n;t1t~1Xb(ZJ01C$a_eiIvt7>B`_Myz=ZqxDm9AeO=}K4iL4v9&2S14VnCrgb zJ~*#IdPwlR6nD(>Y7t%L+sJzshp?dk#7OAmJ~ahgjNJtTPUOOo8>h*6Gk-@Fe9 zs)jE+t9p3H!g-yq?0V^q-5qs?Bj_PvXW97sT*S-nuASXNgsSJOU$2$qF;?H{!OGWp z&yXba6zAfE=kToMh(3AmLxQS>#=Kfx{P>SY`g?GH*Gms|J=}vXRrHYHc|u9Dts@r6 zdr=ZpbszV3^{lU-&tt6Tdg+nw?|m189uhnk$$dk?spl=7q-(mCNP?2{wt^$*A;I&V+*!qrIL{I9xKxp#s^?3eR(pImIgjzBtBbGP$oZxt=pn&# zs*>bsNBqtatGQH>pz6E+U%L6Ii}M(nYayqP`g3KVBj_Q)^R|*?W!DP3T-#FHB|+8D z%f6{T{^-$pj6GdTUuM=Rl?jfZhXl_JOOhduxYFGt&$SR#%{=hC>Yz`C$+>)f~ zh*e#mrKeXCRBe3e{A#!Hqw*N;2{|3_$F<_o5{DmNQ297^BBdoj$48m~`Tt9cv`a_NwA7u6u3=p=Td^zZ)Z(F*+4v zhtqa(XHyk~*;4UsbR$NS2tA%A;bXX*S5#KNaOcC3Fk33VRZkKU^u!1s!_{C#b-um( zPBjU$8>tHBok?&OAV&BYt|g{wyZe2%VU2{@QgN2N(RP~zJu$+^aCcOydvG;(ej*98 zrQ&RV;~s1h^u!1s!}ScQ`jWHVcdAL4EfrTSH2RVzK~IeEFkbo(H`ZV-A7{%WnH@&Ay}Z)fu?fBvOSLce$IN+H2t!XoC)|2lu(;qPl9PNayLXyYUFv-@Nu!kN!I+7}SNZ2Z?_826n zV*bK>&_lx3VztL0K^03qjKQ*E`RHBdTWfxqmmzDA9ul@zu{~8JsM5R4j!%X~N|zoI zwx+N>1_`QI>S505A)z*=HFxbXNKnPr6UMNW#JZNP5thwz3kj-hwdsE+cr6mP+O$0% zB&cFZhpFPdCY4so>bh)iAwdrb#nW2e_EeFeO7CPB`fhTBpofI5Fm8`w>%!$>e`Tw` z+X;F|Fm{-85>(k*=k^%%kSNawYcNTUYxZhvZ|$klj%6RcAZ~f-xa!QO4~g98ycSiX zM!8d!R(U-_*g9mzuvNvf%SVGV?;BlxWaJMUsj}7TBFbaXL&Da#`~0!LB0&}N*IHKo zn`*k&zUQA_{qT!x;AVF1m4bnrx*3-AgAVC#dPnZu|->hprKkJn0o5$_nC{bG}-5!G;60Dmr1_`QE zPg)(_9)lhdw!*xfU_NY}c59x(R59%&Y&Cv+3=&lFP77nuLqfHw{SECgNKnQ5F^s`h z&DPFdA|&V`F{J+m)w>S7HIgb4RI$BeAZUYT=xNa(q=M{;H)1_`P} z>ztAHRMDe+=sXdrc%`rg=^^3E@YF~Q5>#v9*n_zkgZbBK02qWJ?He0(34X! z|G^j}sM2$n&hcuG!SWHUv#F#C^TZhRkWdVrN7f#LM5rpB&cf2=lO72@$>@x=_826n z((~L~Pam>bJ3$W#Jw**!<@E?b4+%Z5#B)x9Dvc{sM*c984~@0fXV{5?O1sA0Pwt5I zB^sBkZ`ZhFZAni!#Y`M)kRB3BVZ4=)po(oQtU-E6sN8hsU3-0ypsKv>vP@W38b#-A zcts=z>p(fT)?Qv8^pH@gTTc|`oCH;RUU}@e{UfQOhlHL{;(a1LdRnsHnO6!^MGpx* zOXyV3_WB?}6-zygK@SN%6WIt?PEf_WAS77NQrW0qUgz|XP&|9$2xE|-O3zw19(Ze{ ztmq-(OCk2`LxL(j!@cwI{gD{-kWg*LpU6m1rPgClfML${PWPRB2K4Mdy;uGHdV4fd zqW^z0zaB{yJtPk3`F6GU?x#fvde)utT6N%xm;DbhNbED^#p;pQOo_x`s;Ihenc3BG zlkSTUQXPKHlo`4Y6l3WXFKgJklD*{)%Ze)HspsyeEr8&)NT}Q{S#OU99mXI*mHuz_ z)J~X(glzl&es*ejN-M4_8Q^k4;V;ugQKUSw~ z^kU;$EA4Py^*`sn*|0f>5E4v@*31k#{^JJ0cp*U#iSpSD5>y@2?dj^YJD!Z>JoFT^ zB;o7{$8!=?{rc3$s$b6Va~5Gf=pm8b`at#W32#JF#S%StzniPCk9ltarOR?BvFK@c zR{uKp{YVTFR568NKIkEF>2=eqFDE{QJ0jJtR1@6{d;= zRpr0vLr*bdrq!+1j>8xvsN&34NN{Z}#}Ymbh6Ft%%10a$RPm`cjG;QW`8u`ZuV?rb zZK}a(6W$ov{v^YEaP==!7{;K7M7XY(_aF(XRI@+*!^}vkLQgSMsTO1T3sXgcDz(r* zZuDX#20bKnH_tuy%?QC#)cx^v@?Jy5QV&x_4+-6m)8@V(i9v!YrZ9{_4+-@vZ;tUP zEGMWc&pGFW)oa^x0#h5tpofI|E+FSru^opoxaN*)<6gh@o09RI9uncIH@008 zp^EF_NN`0X*DBii!tM8(=pmsqA>+R$NKmCSA>;2wnRcDOYGqZP4|+)GxhwwMPJ$|~>kV^G4+*yXa)K(Z zPYwxsNbuea36`Qx*0f(jEcK9}hlI{gjsGelK^5Cu7=s=XI`!7x)sz!d@xBQO-4piK ziFdGCPy8JjJtS0{_S7H7AVHPdn8gkWdPwM8UVGaT5;{}V-VW%rPqsA)$W7-T{^qRIwim3HAo61M7oThVh<( z9ujtbe|z6ff-0T;8^5FIQLWis%PWQXpofI7|JWNA5>%`dYI7$m3)OMx-$jNit!@)LVy^XWXy zxt$#>m7N_do4+zbf*uk|txke&#MYUz&2_INs47oY=qavi=To=GAVF17B0;L`q*GnX zPCEVmIVWM~*|w*O9y=%Z`^O-mvypZFa(j%RbfIF+hBauXKkHg*?K;a@Hp?(1=pkX} zB)6xE1XXr6ayvnfovi!)Q$@l~@@b|P_m3=&jvpJ!OQfhRxdSl3lN zopjtDg9KIFeHzA~hlHJ5+#Z7jRYA`e+)?z9u#=A4W00VVJ$RT8^&dLlUe~fS;{A2M zPrpmTP9ASh75iPPxN|y86+I;EMDz9-B&gCouk*><33}A8=!|fwf-42}K@SPvcP$!; zL4qpoG7oc34+%R{x;-BxsN(+mFa|v&>^$`L7$m6T?ual3JtUI+ob~n?B&Z7dAlb2k9YUUxaUuL4vBV=i?m}c--^uy!n1lq~htj@$E54 zP{q+MY$a?z8ZB*1WP1wndKn zm5`uHPipbjP7eu{TfDWCpepF|gS(a<624|*cP$C3ICh1ltM_91R)$)f-mvMLAF}x- zEF|b5!8dv#K@SN(vt@g;cz=+fO7E{Ng<%Z6|F-=qdV8)f6eu5hs~+FUN)HM9I$Qfa zNP;T8(Tnfrq)PAi^u-8Wx16Adgx(bDix};xB0&}FDJ&~`Na+1#eCG=Zs@QtM7)rao zM4|Mm6!c94*_u6z?{`+6+uAz41=hDxM3nC)r-y`EiN251URETi(hOaEuO&Ss)GGDO zpY|9es8Y+1r%G?)^<4>FOLG%eRxFXQbm<|XH}_WRA;CIOYqxmi^+68_-D&!UMtjal zP{sQuOcgyO?5mIMF-TCw`#+4qK0~dQ?eylALV_L=s{i;-ZxU3o?+RnE&rn}$eIomqkf4WzdhK|sNKnPQIgCLM z35_LIZsi1393?`+ohjHneM_s5>|6_uL?J;BiG|&HWbqRnNKnNQwGm@!cjCzacj8Gp zcK*ZFg)d!ehR#CanNHn)`&f06@0Mu%KP2cO!BeNo394>N|505gdF8(5IV{ao(L;i# zXN56HP<8iCPgQT(cv2(=JtTMvSQvu@Rf8^`S$(iJI1+;%5MF@IGsN8gNeR~WNRH-ez zIsfGdK@SPlzfKr$k3oVe-33d0x5UVHf*ulT$2wvBzY|pH-dz0BwIT#PBy>OOgz@$m zBtq2#)!pZgj1Wmucu43}Hht%(Jq8J?F1t9Z-a2~M2tf}Coyw+f47JA~LDiiv+*5t- z()}X@JtTB0o4!QT9)m=vy0iM(`~xC{-Y1%;mC*NQ+GCKAZK~~7xwRx8p{F2pDqB1s zB&hoN5jU082R$ToDqFlhNQA2EO50W8A)!;*%Gy;yP&GFBbJ_g?4+)*hR&sxUplaT^ zSC!o7^pMc0Z1MY?1Xa7=cST8mMGpy`$`<-)O+1XU`-_;U$8BzQ_* z7=r{=Y76n_D|$%qw7)P0398hlVGI&f={~n-)R3Tu1W#WqCqmVA)g9-K zoDpj!g@*)Bkql!bNkLGhzVflryGCNrLxQJahA~J`r9OYwrTa%>&_jZ!dWJDbgsMBM zizNp}VrV2YPb;C*P-CTA5TZ?`F*u%&&{GiMDXZ??YxCCx399rg5w8z=Nbt1Su&hXg zss~EjRpBAQQ*Xl;@g#>9X4_lsz)_?*7G|+Gl4J_VqKk zpEpUKxZ~jT(kDNxT=t_EyKEnA?+?1&f7P6KtG^k3&`8<#|0QNW>rQoie#!mPHGbVA z{p8txo6$*n!w>b0f-ZkCvr+w4g zJGcq3B=Bc`6-xbr> z&f7Zu_T_Cym`bUlD%=G#`Gw`vVYNBzEup zQRUrh4o+8IVY3=NW{X&K&QsN+S9>~7)sEF?D7hV7UPge#W zdszD9vs=_+D#ZwiKizOg<&(XRO8@!zHZ^+87BPF@zgKTN^~F3@tN-+h$|0BkHofnY z^+uRVsiKNIDwAZj>ZO&zzd9zJw&ag%F_mJ3#ILtLwzBrQ$ESy$w_}YSvqg-$@Nd<7 zZhA9M)!w^QEC1R1#Pq7ge>lQaN)=VyshK24A3eOX?o%hGC+)OzEv8b8kT`COuR6O{ zJUN}S-7YnH%og!=*S*yv$G>M~wbc2Y?;kWKJ@lVLMwm*eqKbPvlVqbV%4LkRBv0{%4&(( z>(y6X{iO7XQx+RxDy535a3||G_YJR)e*DDrguicBi>VYNBp!MDn0mj9j!##vZe63t zY!UrVaNok7{zhI_{ob5d|Lw=eq)VK=&#qsPvh6oi%#Q7V+o5UR6C|g%|Qv{cg=C>t_!>Je_vdN1K>RsiKNIr;}ve zO`fjTk2oy7XshA1m`X81;{BIDtdG0(;B@L2>(}TpTg2bDzO4Gf?oZ{ZI%)mx+3bJr zm-bm}&L*Z(s;CP0jQ{MU9@+mbzF&I#J8RZrD#ZwiRSxZ&ZF~E!>1w;JQlrOg5xZ?V zvHH-NGxAi`URo~u#g5yhi~a0xo0v+eqKYTexbJy=xO{fpiQA@U^ch@>sT3n5F1u%q zZ0EnE>D4>;tI=b&h>IqlU!DEw&3US}9MO?Yeqv~P;o_4wF_lt970={JlC_r{n%(nF zM|#bNy=yU*VuZw-m#5jL53Z5EyTiOLddwEF#4Tr4yU)BlPu0qwY?JMA<&gC9*|&;96s3>{-jMzrBqSHlbe#{s^#~~h8)x*eej#tnKEt4yj~v(ey9Or=y& z#S_}x7a9NGG1;-}Tw3{TP^BxTQjCzOUvPYO!Q#hO9=fAX7d>W+IQNj>RR>LfWi#1H za_#*mX8){hTzTV*r#3c~QbiTdrc07lo<1?VVawr_>;8EAM0#R`kFnetW3pp!I=(Y~ zXO*Q$nC(?Oeecr&Cuhez{AFkV|C_Wa&(b6D!JOl&U;p&rJRi56H70w1{;{2VOkR7b z(BrS$9wR5Fzj)|NOEZSqB6Ot#4>9 zFS>m-{k{`c>K{|-x*?I5Zhf~ickNG)*&wa^{LuQo$=lKjWD_P1A_RNtxR;7v?rt=&|* z3+xo?Bza^1qq4Im+)?lT$SwVOEmP^bX8TnA!`-zjCr{Te+3w-~^q4I|ck{ou+BZ*C z-ZRt>IrPVkd(fg&r5?jhI!=-uZaO%7;`0yd3;+1V{xOwegv9S$4|m`}J+h;>{;WSe zW{XhIcjM8g=c(G=^`e(8(=!|S=aU-!l|`pYy{nyv?S4D^o;vHXefI$|m12ZMJ{n}V zyx3;|J!Xs0D6!DY%kxy_BTl9f$5bkJsx%T6=WOSrTDDHl0Rv(x#R!Rf$^_fp^&Qo=+8=Zgg#L(=xSvNJtL5oh6M(yIP;%n<`WcU0r&2GG4wE;1eVuZxI zA1t5UcjC6$D{rndfF83&=;`BuGiT(fO5Kyp4Lfd^t@M+>HJ%wPI#qhYDZb5-KP_cH zpWHDZrc#WM$e+lvv+v$y06k`l(39G8yFZnuDu3$B^wei6)gV=R8Z6F@%AYK=+G?8( zh^Z7KB=V=%Y|ztN44}ts5qhc}wZaQ|st#W3$@-py56>Q`e$;ptwdhpo$=Oa%OOjEi z+)>XCI4b*Q<~9RjD#Zwi8xFg){`n!tWUux4@c??v7NK7Ny{EsCr>fr@6YH0Kd`!0T z=?jf8mCA}L{mQU&+>#{!#gaWTVaEY6m12ZM{;MdvX@{K$&||g;{aU(Z@%Qpn<-fc# z{qi!EQbm=1k=glYNs|A%%kJ5JmjN-AVuVEg3o^T5+%5y?F_tFj@WuYOr;nhk-x>s?*Fzr zfF83&=^% z>^OV?J!Xs0o3PQVJ)Ng2f2)?wxM<_X`zwo1mEN`$Cl$``^HJrNzZ{%ReRurzs9d+j{^#W{c3<=qs`-^Hk+;wllriHkH~H zReIxX=b0u+{`Ne3W`lYCV=Bc6iTn+Hw#q&4_NT{e5qfjK{S9a4smf;oGR*>*N~xks zvjcW!YLetL4cS6Jn$@447@>I0*^I`l3<*u~K_ptl290{|f;_i`L?w2lo z=Pv1;pKn+rVRl0m>;NUfJ)AMZ$N2hZvn%VnI$6|xL6U^oQgLr*l8^{Ic}ht57$=Px zS2@jn3G+txB}@`#OBL=JB|%S&@G+h_YHH`h?jG6AebJMI*zx55@t)q-KR-HBJkuXA>m`VJ1WyXIN{6Q zH4)|r>i8p*Uv5SP+ zQgM%JqfcxS^u!1s!}aZ%`u2l%TfU2g*-{02R5cnj33_6LkKsm~Ok>p96Vr=HnB7oe zk7{F#Y7*S<8Y6s+Kf3$x_|a24@BM4fE}mLuwp7}uQJi2#f}R-RV|?Vs!6#1}SGmZI zgCxwBO8Y(>m@Sp|m=z~rlAtF>_!$4jI7q^5skE1{ILVU)Ju#vgqdBUPFk33^H!AYs zVl)YQVuX+3a$Z+ib-8hngxOMQS5i?QBoX)yc-8em@Sp|j~4wd33_6LkKuai zOnv*OyDr~F!fdIu1GE@FNYE1_e2gh>9PIVGshz((C%u@2*;0iktCFB6Ml@rjit*81 zJ-hgAIJ2eV*Wi-G#b^@r#0VdQqZ$dbrQ$c^!f}wE7~x}ZR3l-wRQzUKI1bViBYX^w zY9!2-irP^=OU3VpHR`-M za?%qcd<^$QmgyPphlj6RBVo2w{Q8(%&j5m+7~x~MC(BIFqDQ)Mkc8P%@f&5XF9AVM zjPNlys*x~TDt@D^(U&wwPI_WQo)3(JB+QnIUo~s=iOrFdo*3a{a8x5g(M+CPmJ&}mYOiGvfY-W(tZB1Lyd&l zQfc%l&Uzt1PmJ&}II58_TPlq{#R)Vd=!p@{7|l_QgxOMQ^eOV;Vl)YQVuX+3a$Z+i zjeK*<8VR$d(&$sv2MKy&gpc8Bu&z2k@AF|b5@t)K(WhuvBkjFw8HkM&CJK&i0WoTPn@U zRUY+cxi{YFH)j;-i4i`An`sE<2klx$OQl&kJ1@R5H_;^Mi4i`=EAH3bOYZmJ)$aEo z39}n2H!D}1bx%SweCCM}K1RijgIBpe@fU6!Bw@Bxnw1;6gPo^OBJkw#Ncb4T+&H+U z>)ZEq;~)vMrP8e2(Mwqj67<9fAA_@fB+T}z;_C>Fxw}rAQPd2deUBkVG-EVJH4WjmF*w^t!fdHDD`)p+`~0AJ zVuX*u**;#&Y^gLWSM*mT=!p?NM(g~bUCU^xG%Hv1yCmp|5k3ZI`$(8Am1gCv&u^^# z2<8XP6C->KH{xU(qmG^K=Le0j>o!#QW<#Pes!3>m&_=Zw;bXXwGu2pIz1PnV+L&sm zy-B56IU9o;V{Mb5Cr0=f{5?p*Y^gLWXU`Jh??HNEgpa}BgCxwBO0#nI6czp+q$fuB z82oid!fdHDD`(Gk;d@bfVuX+3o-9*6i|*`x50WrjD$U9j&$}e(i4i`AdqNK82klx$ zOQl)4;<=p!Ju$+^;IBIpW=o}6x#IT+33_6LkHKGeB+QmdvvS4nC=&F<2p@yL?nsy| zm1gDQzX$1w5zQFQagc=BQfXGM$OnH9(i01B5jh8peIK77=Li%;2|eZ?Hughi`uz^TmIq9&CJ$` zFg#r_Ny-SS%=TB(IQTC&ms)e{Wau$lF?d#>9|vOuRc8Ab*Sh)n`3KFe-0arL&||h@ z@T@>LZ%{%|Wwwv8rdua7$<1w#aqDF0FJ9h5<rMG%P(W4N9nQ(rR2t&^e0 zY{lSNfsMW-N>F9CkKuZ_Onu^}Zk-H0W-A8I3T*U=QGzP7eGH9i>Z!kV>tyILTQPW6 zpnoqKBd9Xl$8aM~rZMW4De1-Zn5`H|Qk*W>7^9*@sPcr5amgZs({HZ2y1w)yn`CFY zT^r-qsm_=&w?}gahjv$R*F};XaOCpoRtMJV>+drnyJ_G%)un6u%;@n!uLiO5$Llt1 zUMWcyd2yw5(2iHvFaEkCh{5afN=Y(c-k|iQUrwthA9MsUNO1Q^l3e`Sfb{&;@2!8h z*6@I!YPaLxsP58xTqA`^@|$k`(^W5dqP}SNp&3=&`4SRaU-*M`+F>u(FMq!yqlbj; zy79YGR=9l8^qnCu*B@G9ctB9K$2zZ6=l*0;o~qZ*SUA0?`zQ6iU8<vpZ<-1V}XQ#MS zQN`U=A#v+LFIU#7{U96RQbi95?)gfRgASiv>2c2D**pK-C?KdB^vu7i=?c^HRJ}Xx ziOQQ_ES=rwQbiSaqJ_j^2TrSu?LIg=@7<1!9unLimn2UvdPilK%a_gi+`dsjQ1ydP zo~+*A>#;ml`|N&QWr;0T%=UG?DOKFH7ZPt@J+X4nI;&=>OBFpNxR)?V7VCCFWtrct zlC693Mgc)p#|@8Gf0jIxr|PU@$5wWztdaf7rHU%7J~Wopba?0YTN>ga1~&;`JBvR1N<1I+cg-`%$)}OBGez4H^=AoZ79j z^V%C^gWvAR=pn&9s!4M2RbO;&*l)e;%pEog2&!i8e{Xg3i(kuAwdR9UIuE~X!|V~) zuBhV9*^qd9!n&RRc(NmV?ahvi9unNonE{f8R`1XYKRzoR;D?(2D~ zc3QE=#*^JI)lFPkQN>-xA(4&x(ez)qR2}Y8MGpzv)$D6F^!2sXKHt5Nm(}ZQuT%fY13${Hcd4R^yVpbFl&O2w$Gg_v-KB~i61H33 zr)r`3`_wz0Sudc zLSm&;rqvJXHaJ`4wT_G)5_SrMFRORYpH@F&(`B<;4j2{?RPAw4SGD@hJ$b5redQDN zpU+)7Tfwz>s(6A#NL+O4%k||Z{vf;kRW}aeS|oU`MUpJM=F9cxdoG@J>lhXgR6W^k zLiIo2UZ1Dxy~RJNzdLr}Y!#O(s(9K)NSwSUfBHf8{y{I-pLw|>qlbi@ zgyL(k@1|}nANgW^=CeZsf~s-fjj!JM-q<`Q8yXN)^*`>k>SM3$ny0G&HY;XxMqXDR;L3_B zo_G@ytBhDR8*t^s`rH>gGI~hx9G)b(V%Gmw08EB?t9kv-ePD#P&Ih# z(bX4+%(+j`^GTB4|D$Y`t=DO!iYlI@6cVF{Z;-8Uc(;1T3mq9fB<$oSpQ=%dZjgQZ z_(JuI+{tnzs5fILSou;9a(MAy3>F0d`CtP z2|MM=r|JPmeCmjwwh*D}gvN>QzO497J?%{I{qedZTYnXWzi~+DN#?58Uu+P1*7|w! zOv6@tyY-b_8+PLa<%#b5IPUlV*hafDkDjkPM&Hy>=@&rq(@7D6zYX|A{{3Uv?*TqJ zm#2yvUQ0sYT$ehjE>qAc&R}XouaVFNs8BW1-LQpFY%ri$%Hzj1f(J??)<6$!QW zZ@czcK&q(XeG{gN9^OUFUr5kHg1_6#395MCgan^5IJPr(NYF!qV{kb^63g#tvZ99sfBTdZRI$eh38q&us@Ko@ zAIge^^0&lyFGOUtN)H#$~+>vHB?%8 zsPEDHE0G921)(byu}OrUg3#=ePAO@R5qb(j`72V(7$m4F&$-r!>Z|pQ=x#0N*c*K* zg!yBPz|%s+OP7RfQ-!6@7+RTk-mJxZs&GL z=ng!ttWMkA*R%fL%wH)%mDUSCJS;DffM7nf&eCcyD8qmVJS{}CEtC?XO{LY1osZ_N zCm@(!t*7obcF{&{1|<>@^pMbsZ+$Vn{r(_9m14(Jr4@$yQhnoE`I#lM^?!Z&y*&nV zsCAaz#`bKef-(&9K@SP7pd7wkuSg6MR4I16&gmiHDdSn}+ zl8)zt1XZk?Fje%B@b&LYx}2cu`_(z?ndKJ7pr@6Hw?q=MO;uhWTA!wqG}Pj>9!@8B z$kv*&OAo!UVTY;G%Dk25c#nwg$wdv7Rt4(3jP|xm4+&k#Vz->`ToRgqRvE!*?dbOhQyZPrf zuFDb$Q$-I6tyP@xt8*f$B0-g6$7`_lT&=V2J*#nDt##LK^7fq5Bijg-LOfL@sA9Q= zIj4t&uNz-(x>=po_j-?!s(f~xX5 z*PdD%4YY^X#whKBwf-@Tq20vR>x-~4N;{dY?+OWeNa#uyJ0$2K!4!rBJtUMrOKmwp zRe8>}=iGW6?G3jcj`<5?(9=r9OP7RfQ?b;;7~1J;y|Z=}+h|ap4|-aOcny+}Z7Q~& zFjdTla&D<&8HNNst%T*ToDgj)oj(xo;g}EQ+-i_z7{;Kdm9Vx@PKY*@c1y=c1EyE! zGuRl#5(#6_LxLwMl@nAcc05%~uXbVE7{w9^W6(oF`>W%l0ST%UJ6?mWXI@$Ftn)dn z*A7!fk8C4U3h`8tpo--d#-N9UubbEyMS`mG`mj?~G)8GRx#d>2%Dfxq2DxI8x5lw`+%!Y~9V%Iz~6_FjeX;AKKxhCec0dwt6M) zD-s??Ri1P844>^e*5};yyB|(IxnVPZVGMfI z?~;g@E(zJDVyTBQbf0SU z<*%F&Z7SX8+O^f*5}6O>-0Fj67{;Kdm9Vx@PKY*@?!lujIwg`SrdR!yc7rMHERiq< zJtWlgX`fen&Phs&JmIs?MjZE*&K-rUce+9&@%XBsp!a{dSAxzp{C z_qJvrbOuCwD+xUXp(_=!TVoWSg3ugNlEh+!o`O*RiqtX&398C-u6O!p%v#Ln(9M{P z+x>sac?%IQU6z$>Q-!6@eCQ3m&a7yZyPGl5Nf@%r^AUJjhkZr24^)OY;2TyJZ z$}pIl2t2N=EFb!RGk>K7ReIm9b2QppBJ-j7D67Gs41*Yfr-f*?g;GMasWdP0$gsTi z1O(Hoc>|rcp|l4j5)kx|&^(3C=1391x3o+`~QRA1`tua%#Kq3i1ZI!B{D26L#{ zh3;b)ZK#4W4Dvw_3C&YHbjKo*7$m4t?0B8iL&C@NB^~ynttVJnDQFHUo^yI+8=;bp z=Ys@QteY@Z^pNoN?@PLzpz8b8IqR9_7RI2bm58@Q60%KIULTrKu-`J8$Fbj0dUJ2j z@L{SnGh)9?{LGL4RiqgRd%g|{dPwL>7CR*9A;A=e1U)2_KTB;nLDm1K?7YLPsJ1pf zpdwNg4%j;gHhK|4GRaU>RGNUO*NO#u7eN$Mu%UnuVz7%+M4Etrgq-1^2nZ@(P$DWS z7VHg6^s0R8ojvQ!yK`pH?++i>!&<-n?l!y4?33h@<4j*y#du?)t8gx#t-+qEM11Ws z0b8TE)@==(>FW-He>Ebx9PFt|#J3<5ur-Q%kDV(n2THE{D6T`BU{6&-%a=@m)+n6m z$FIV<94NWAAlIR-!Jevw_Jw2uv_|2)J$}c+`Ng{lU4L?o*c$9%0`EfNSIA6o6tv@W z#reg11KkgBjo7(j4-KSyP9`|Y zZu9qMwR6w-5M8Sf9QAj} z2G6P4xX`3@*6}UfpI77+TqOj1n9yG)F&bTj*gcb1aBmfYqne-hruXQINufsSoF;DP zo>K~z2*DmE^p{DDM)h->xTguRWsXg7ROJP)d$pa4P@{Z&%AHtyLqS>y_AsHpOky-1 z9G7zI3b9pk#RNxvKKC{6p3Sw2OkF+D#c@~5f7Rx-bJ@d${xXTtxHjK$o63I&i3SrK zwd1VSUb~@9LyaMlqjRJz`wPJyChT7+$*;4a;3*-dNy(Y8qDH;!y;46f)L1Mv+g@t8 zLEl|uhe+)*!BO7)W!|n9w~ol)`CPkzU=I`6g-5?qGU1C6`A0q9&iz7i#e^NT z*sI)mMyPSmMQM&reB&Hl&J|9v3o#g6BDF+iAmG1olm1AipFa5Zb zd|x5h!-W1aiP89YMPB;&7A@VUC09&v)Gsg3ruLZHb4vP9X~DTdu!jlzS4y50qI1|w zn6RQo&7^+yb?pu5WzrL8psp-W^t&kf%Os{8FACubf#-t>j;cHDS$aN>$#?vV<%v2> z2=*|czf58@)^~CIJLIX|Lu!`^jyj<4)AXFbGcM)#uC<}yUD03<6Z*>}M&q{eDgPXK z4quXzGr>_cpLl}CtBP})_&>-~wN(iAFrmLpVl+AmG2!GX1!a;eCOE3%smEyCEj+%Z zUm;^VMr!sjp}$OGG|mv>a2eaLtU_>9^~)Zm`Qy!5?fjF&8HYVg=x>=A4Vl&a=fhcz z2|Mc1;7)@XcjeqCCAa7r%PqQ~@8{$V2JRNnwgwY+6t7pfu6QNG#DJgId%K@KrXXlpt9EVA z>$DE~HyVx;5lE@axnt6~8k{SRN^TGKFo80CK43RLSAz+T;=W+l?imf%WZT>swZ{8j zkLf`hpkM9pG&jA{s;mCLukp5DvB;6pP$))-@HaDJb!y*fK`{=2$j z!f{s9sLiv1omLdZ8X=F&JN4W>$M$J6;#q=+jz< zHUSM?8`N#^s#oLLl>yOw=&RlpC97gaYD9g!WVlI}MmP|vZELWH%k z)HcYKYTE>RINjtH!DMIO>{j*LZ`TO~=&LjnA+3X7!yI zczTUk>;1KJY__Ho`Y!cqCi-?+>uoyu?idYLN7RvvU&?A|+a#BR3F!T?b771I*A+*h ze5cKw6GL!*k;5m?z9XBfe=a!_sA+vRbIYM=aTJdjHo^JrzhW!hF;Vxw zYrO-Vr(#OZb;VKmcg?MxEA}t}y|s0xBxq<_9L4?3*5GlFpQu@jS0(ga_AueBD9=9g zwgwX%wdT@Q*lt_g+aTdENiMlC5_{X$!KRt-(># zD_@EFYhpP#Ehg4ATb1y9Fu_sDCFdCj^`_4UcC1gGSTCl{*~0`h;ztH1IO+&5<5leJ z9izb>CQv3FyX@L!f}^-KZGt^apr&=KOeQ!gxtCxBIKO1o3hetZGu(I4>cGa6rl%CP z2Ii=`&YB4A0|+~|2?xZMuQ2C;vQ<(6~^-;f0`bo zh4I{*JLmtAD<)9#?{_Zzhg@+K*NB}fu0?1(*>_?#SO46vm_Yf`b*CicO4H&fu0uOl z>|p}4=-$p#2^!kA9L2S6Yhb);ws1_47Uru92R>=imH9(cvI&e!+Jcy`G$)*rP4GD- z#`f&=t<`o@@k_nFDQOPEF97L3ksL+ltIeVCZUc&Q1X<1Q;wTrn{)tNvo z=o4(0gFTql^qJ?BY=S*ZV7`ifqL|>Qv?_ zrNzJNIF?JOhlxdNp3A6GHQzr-3twjbyt7fx8?)qcFoAD5KWfr2CRbc? zjnI&S4`MZi@ohT-;Aj%yrWl7RbqE1PJ;>9 z8nwM>X+nE&6uxQKyeAXvVFF*6YrWYm$OK0fT)!-OHtqJ1@6ENx;k#$;yF9Ph8th>L z-$2Lr5=0%|uVv6u_~PQvCH(^%#GdaR7t@05VFKTTWZ(Q+54)bz3I+QeuuVMi^NT%8d^pqHqJ3ADevplu9+XF}ES9f;O0`f)tL z9wu1ZE;$o+)MBr?(=H}gh>AQ>nUc$a5l34JW7k2Oj|$SocPH^}&LzjVqAh5biQhC> z9wIPaX%Dqa&ICs#=ZZZ{V0?`4?M!eK*NB}ft{;5mUw7D%|4>(~!36Fh?B*O6(}GM` zQ9Nr~&mhkROhE7VyAO)dV1lD~?y^hHqYR$y?5swsbDQAtiV55c(D^Z$;3(WZNGONg zUC~-Zl(q+tM79Qdn1G)4{A7Zol1Dh60WeJc<OAir>D_&uGqr_zR~%1*o2rb2bka}{JXB4b2Ze%gyX#YuikS; zQK0q9AzK4GAw7xb6KFoawh8tyffkH^)4+rkCGFJwh((3D->^9Bp>)v~^qVO=S9s2M zbAArf!dH`T8e8b--+81)P9jf4V1<+Y7R%}-{KXdZvZa-sMSMB1H_#}o^z|)(MOzx| zVFEh~eV>q9a@DY+5_9D^&t>}$c3awCk=yv*&K@SPZ_{VR&J`0J#Wj*kXgQd`t|TjrJxuJF^K8O9dL}r^u65R64-+Vpehp!lg9(m8jl_S? zz~7|qIDTsO9oy`VQ=@lm)-%YpxZtj-a)Myq9M5}sYQoz-_B_hK-zah~;hw>@ZfmfIi3j>mjo!p2_A8F!K4xp2wdaiNo5S`M z)3a|X`AM@0_Aqfm>GXt>bDbb3`Zknn-PT|a6DU*sdrl@eifi50U=I_hXOkH@)$KAmVm9evOj;=f4YXAQa1(FeKJl#(@= zK#k~EHpv7>aSm;Q^V_+}jO8q;lJ}-YkMLB=MT|srzFCP zl5>r}`?ikJz@EIOb6DWPZo9#-BLf>d{pi*fYp{n2?9Y$bd{m4EdvJbHx%24%hXxZk z390kmaWNX4D~_^i!5Z7y!vxM}n)PcLqrrp~l~}t~+k8)_U6^jvnszV285!RtQvzpX zQSagQV1lD?&KTcI*uw-Se_9<=4r@nd<%&EOA?2&(gtXNjRd;vU zC~Kc+X;_{pUDSFuhqeY09EB%M%V)O-&XzuF(l973PKVdc+57)da*L3&lO1#F8QRVj z)fLWUG>U88&Xtv4>3vGrd+NlxA_Dz5TP8bKR975@XGLqo&J}y`)c(G+ktr>uWD}fU zCNN@bXuf}3T~S&bg^}pPyAO&Xctqxrn(q}>$rasEv&hW!Gsk> zBe<=BzN@1p&K7k%N3V<@;n>3jj~KQF6IPV;UI++5~&7bQABZG2u`Y-&eIY_`WOOcH{ez zHo+byki+N{k9!Fd9ECc3bH${X?*Q1t1nlgWD%LYtmCz`(tm9O~Xt0OV#nbil=31HD z^LGA{n7G=ZZZ{;0bOqv}sH^*uw;#N56hv48b0Ykmp=; zXqSTtJi!`;=P~{*vgIKHPi_3$J|?UvdJAah3M&iE3HG1bGqAIaZ*%rwRiib^DJ5$# zfwfP3?OJJ36jmScb%k>g{TdS|kovW{m6G**u!jkpe(HDc$>rcEt~Z-t4-+_n)*L1i z9EH^7sl2z$bFalE7!W6EA}vf zv)=fxahc#K?)kO`PU!S|W1Lg!_sytv9V=~uJxt)lGrr_pC&-Cva2?tj>|p|B(%dE! z9L2S66YOCEHLc(8ClegSBauyTo!|^v`x4ioO|XXv^mgsX$plC7ERjp-sD>8QF%f+s zzF+aPhFt0BgWPIL$r?Bhqeai7pKlT18_<7Snu zCZHGJuQ)A^;%C#&73L3pQ;9KH-(cdoiGGQVSK;ho0@}LYu{D_BDA@5kNcJ$n-)qh{tsZ|#8H zRv3+rLVWp3Ucp5|u!jl0b>TR@&u`+kJatOJIaLUbn)vARUVW!9)VN-V4}{oP2=*{x z-)Z>hp_F@Y{S5`b$uCGU!BLCfnC;EobaSY&R)~}8Z74WNG}yxg-=T1v3tY$TApdo% zLU7dCC(rffrzV9O=SlQ|^4}mK*uw~NgAQif|JXH^M1YQDF#$MjI+6DdQzi79uR zl-zM5k44Z86~`%)nq4O~j9=Sig72~P`RoO+;)+F~##=(n5aKH#EDxp2_d*=!9O+Yw zrKfych2W@hUoG^`Z&V&?Oci3X5Pu569wzv9gyTFfzn^%F{LL&LV(t&>l-bla%}r}MEQ}Dt6wBnwkIO^ zu7l&atMby1O3DAOLU7dl1C~*HlnXIW2(&qSn6SQXb)GqOO8Nz9!LO?jcGPm}SKEc~ zg^*v!le&sL7Qx@cI*-)fklrMHcWV^_-(2dAs%eYM>G`;@-iGuGLiCr~wLC=F-`4hX z9lx18QD;^mII3rBpPuupgg9D=?n1DK3BJMSIFCJ)^2_C^I;9H1QCDBIg2t(C-MDbwTlnEGHu^QW`aF&1Zc;3zsFF2!06Eh8%{rXG81Ye zitmZr1bgBLqw(-=L;M~WRutUwQ}JXb)J7EFEO#6x*b_$>jhzeo`tQ8mz%5$%&SWOk zMwESHoeB2D5k{jyjrRVg-P*gOeyv%;gxZMWoBoc&1bgBLqp|(J4g9)``?_ndI--OL zwGqX?4d6ITuqTc%8ov&%NVnN-hYm_d*TSAAtf(BT@8HWv=S!NMik$W59%sQuqTc%8q$IVX!F`zx|T4ZHlp~3 zyyGyzo;bp2NKbUpcVF1iwuA|_5ykiGgT9+3*b_$>4W~wX_j7p$&w1#O5+>9}6yL&k z946QkM;ML67xi_g%UE*X`MZ}ep*EuU7QW*!!Jat6Xxt}lafghFjr*^k%!JyA;(Pm! z!vuTc2&3^?kD+b@8QWLSyKgcRY9k7_RibkSCfE~47>yEnHiq4?Aph*LJti}uHlp~K z1ssP7_QVlJqg3X>XGSf^zp31vgtz*7YfEiJ;hm1&;Bp)$EKf)?VKk)VKI-ZMnFpCr z8&P<}AKmj}f<1AB(U2DO(dM&c9%MpoMB$qNy-^vod6r;L9APvLT-4W}Cw=#?1@BB| zLTyChTZ8CUBNOb2BaDVTQ9ho*2{I2dp*EuM-AQyilL_|35k}*qiU$7H7y7!pUw%Xh z6KV%h@}-L2A9Wli_@-|hVKfQ`RHUD(F~ps+qeBT3Y9k6?z35F{$6>0@6fEqgxV&G@Afi*9i86#jU%!e*;$PVwGo9c_M&o#MwYNW zMvn=jAtlewYD}n&D12ELwFeXIi6e}Lv|s_+{L=TkmN21q5GCK=Mg58izOfuf7!B!( zF8c1&AKI2Mp*EuM#a{G$FkyMZoG@WDcvfRVZA9UFzvwwy=0PUZ zMijmZjK(V_*b_$>4W8AQP#aPBjxZW`nP5*GVKjJFV?u32;fuX!{$PSVafH#38OOyO zwTH}uOsE}1S@*V?sCx4nIbp(R%$0et#;^tXL&lo@p#G*Lc6YE5g-7%pyqOc2#Zd5VBo;bp2@a~QYwGo9~Saes03HHPhMuT^EOsI`0?82hkfK0F_ zjxZXxjU1i6>%^h%gzaWOsA(yUDD1+bJBm!OCyp>0yt`vUZA4)g7X2PF6YPm2vKrZ0 zjS008g|chLpSjb@lw4WBMRT0=on+4i?Szgp4FI88&UYiFX~rJuqTc%8a%5pp*EuM zRbcddFu|TU!f43K(#5-pK5{O~gxZM0mvzx|&IEhn2%{k@WEbyP=E{DM3AGW0@9(1V ziV60_5k^Dy1}@$eZ9jeeWG2)`6u!TU#$6`Z6Gs>g*|E5I=k=GIi!z}$qVUCDG=DI` zo;bp2$j-~fUhTUjdrW3RZA97k=$T+o9APwO$*gwy@CEtz7n^fYz3rqopAd!9$n4E0 zhY8CQ-hyGmXz;AYgxZM0X=L`U6xIycnUg(ngwf!6kO{RBh11CBMimq6i6e{#pK>yx zHllDE8Qq*@f<1AB(coE)3AGW0)5z#PCll<6BaFre@_sNS?^rg-`#~nu4x;2VGJE6H zVS;b3#t}xNQr-`?4&M(lp*Es$8X4WlWy11=Ibp(RjG+A>6KW$0r;*V;VJ6rUM;Hx0 zg-rX^wHllDE z8I8M4uqTc%8ZuI6-w!gOHllET8OUiay>!{;<;Q2ld-*{hk_8*o8&!IhkNj9APwgR%1eKL}3>e-8W!@J#mE5;8~3c zwGo9~nBIuU-4CiKjxZX$yW_OfMih2o(cKIt*b_$>4W8AQP#aO$h3Wl<;2nK-2g#l| z!e~_84{BOUBMQ5)=oSPM?1>|c2Jh~eP#aO$g+;f|m|#yFVKn%w7bet36n0_Joj4}g z6Gs@0s{27rOKC)57Z%;^V}d<#L{=j^4>F-PqOc27ZTmYJ_QVlJgTIquLTyB07Z$Y# z6YPm2j0W%Sm{1#0*o8&?iV60_5k`Y|cTA{_DD1+tPut(guqTc%8oaw>LTyB07ZyF| zOt2@8FdDqOV?u32VHc*OlH)MJo;bp2@a~QYwGo9~STyc3!Jat6Xz=ci3AGW0U05`K zFu|TU!f42snJ&KNym6V?4{BOUBg(!R#squf2&3`1%!7N1#s>>zKS+N)S?%_>ZgcrB z9y<;bw#WSKWhP)d&H~xpJv3%?!3P5lp3H>Wh~mGIY!mE>BaB8bITsx%>(Nm=iYGIn zHlpmmz03rA;s~QLPR>PZ$yvrHFT69E3AGW$zjxp`Ot2@8Fd94$GNCr2_*W6^d5}GE zgwgnJQv-jhyr;kO$|FjcP&CTMil>L zV#i^^@`QR!7>zCWj80!9>(NU-?_R=$+K96MelZj5i6e~0frA#5*V=QWTd<{92@`6Y zsOaw(I}Q{4w~*tAtVTXG{v+RuGNCr2_%9v@8d<{jn4BZ5oP}+ zWhU4YM;ML0E~+SKA#Gk$_Jd5Q9YoPz9d{fi@Hfx3U&RqdLTyCxUx&887iCWzVKin*8MaATemrmY5+>9}6#qSGxzk1j zd*TSA(NWssV;K{V9k6~f6KW%h|L(JVBTNK);s~Q5W4nv7{rCCzO=d!EMA?5GnhEyA z5k_OG%!9|>wjlrUm-d*V?F96?rT|?yG8#v2S5JR$5Wi?j7eRJRi0v zB5?0E{`p{nqxL#*Ucz(E9wu;qIQ}_jf}`fNo0~9Rv4;uVYK|YTnBb@#_s>ZfciF=P z?sLbFyG(FYwIk;w%pdGw0{7D6=MN_As5vxu@f_tik;f+ZwtN!7cj}>?u6|uiM*W1qr6C8!U@cYjCD{^N}_AtS>MwgwYcl#DT_T|O*E1EY_6EQ0RW+Zs&poqCLw z%lh0CqhWiZd;8Y?dh6FOnBXXk`SmtD7^A@+Cis56T@EJfsKwsF&V(2Z%w+1RO6dK1 zTZ0MM8iiRqz8tnEBJBJ1{0uU|QCNM%w+DNe;QRGrz!%YY2Z0k) ze1VO39eAH zSHzGOqVRiUuyK0??+tP_@GZF3JH9>FoFtc=JynVLUcv-yjp80^*A?fN%Yhpzc*l}k zj;g==fZsgRlH<4AatY2A%AviIYsAhKd#Vyz)5!#Ajl$RQ+DIZiLv_@fTKeh?>Fo9Z#f6kfUD6ThKgFQ^3ZQ`Fn zCO9g&J@7>v{#JC*f9M7%zQ4oY1I_JMmWK#@i-p^=xddzA>o)vl>l{66wZykqEkahZ z_)FTk8cbllt5Nt0Evsi~aDEYm+r&Y-|ElB`A$qvg9Fr?6ttbj*%IaCU!dF`OE7?d3 zUsK`l*Q$-XuelodeiJuu;lcN!8UW4R?`q z%VBwlK#gem>~e4|qK{>JpH=I;zT&=HmB20R+*~mMTchwrEB+RGE@63yKs#y6+U2lH zNF_)6Yirts@p84qqGMuRx>ZT!*#>dzi55Fh@h%mZL!9{&{Y{ zVh2e*~|p|Se0yM(in~3i6YM5%mk2i2 zk5|awwal$6>{#$Cv`XMtXklYLj~hI>1bd*N1X5CMyBt_2)_8VhHeJmL)^@mEldHjL zu?Cl^iUyUI3Dk&|FPY$|e^*yr3$V3Jwg!8cK#kz;Qf|qa;Hc!f!deY~%MfWH3V#(5 zHdcVRkCUr`)vMM!_6C}h(D0H!vt36s+UY~6tv?@&iUnXaDTHk*uw_@Z?*<|m_XaaKZ8tgRC0UZD_@-_ z@Kv$SQTQ_Vir6^{-#6DO_rf|7*&1BCTyIS z(sG$>4fZgB8qt)jxvbSo`Eln{GEy%UYHHwh?!7XbO z>|p{a#h083jzas#w+DNeK+lhV2ASX}^sD%15a&L)0gC4XXJoi>3L7Un_*=i`-}$@* zCoK3&!%E;U5W~jV32uPq61Hctrvy@pw5w`Fo`~Qa+U;R`A_C=$a?2V_a8z>1akhZJ ziyD+rPA2g8OaC7wuR_GvF4q-ojk0T<%Yl;{+*l2ACFef42Mas79G0gF5#NGLz}6_c z_i(Pb95^G>Tv>H!of=r4Dnzz?i3Dhk!nqIb*9J9W5nK+OKxzwGb!ZWmrwWnn3yB11 zjl!uK{@QMCt~kFqJHfqOL|HXrX|RV0oTK1IZmtFs90l$8T;U7}f7v!jE4(2K8~>iY z2W#buONi4i{2g8pRvlUddziqv7XA)zZaJ9XC}_vGIeVCZp4N1gv82kcQD`mTG%CL2 z?18NWYC66gOmGypjh!p@FoE{hnocG->fg0Fw=>t9t-+qEM0`(V0=7maw+B|p`rQI{ z6Z*{r*1qv?^|8{|Zwf%@7Z6y(>w9jy9PD8NDXF$iV0Eu=r$K8@Fwg6|dz;|2ScA)C z6YOCEHKOH9CO9g&uCTJy?+Xy6^@G)*z8SYQxOTbTxE5@JJxrhuRXdsBsN~w^Uc#m2 zGT9pJVFERxEt^bmRB~Nm&8cs_5v4r?E7|z>=j>quE7|yW+k6uqt3G|#jJk?%LH00# zRi?h@wo9%zKrtfo4N&A(^{No`d~mC=woR~y39M?h4wDIv;u^6D?(N)aT+=qe9wyMT z@n4HD!BNRA$hFHgikgo9)_^@saPP6p!5$`%tN1SmnBXYx)3yfpAO0;1ZdsdP4--f! zzT`}B6xu(&J=ntpdVc&f$OK2BU&TLzxXJios@%m5Fx)t7c;%w3z5R+se(ue%szem^ zn)l;QKcMZp;+v&a@4l*DE|K-n-B;_bt+gV9h7wkk(EsZ(JtkMU8$5l}&4CBR*QrT? z&G(Y+Tyg#2uBE1H-PE*lWqF9eok-Qo)zBKXqUffkP4L}EzH5p5iudnyV@l4qSNVP| z*P*Rpd!qZb_I+O7M=`-s_;)Rzt--ls+N#6E+GPTI+NW&|PRou;>bvN#+RogsxX0KU z>|uiMq9+p^mE04n-t^VJ#O-fuu!s8*I<+BO)Fu}jokW6rt-A-H%9!t2LxqP+;dze7U zE~qHj`D5{9Ce%h0-$QU5CfE~47>!ruZ@4vor-A#1{0%oI)J7EFr*Ir5*b_$>jm+-t z{ib`gcW3-ovxEt?5oO;bVS+tzgweR~od*7$@>{95UvWeU6KV%hbR$N7$BPKQ`4UGM zjgQW&NFTNP5Vz<@{3b_qyGCt9@jV^+`#3~co{(n3XjFv1$#JRtCI=I0BZ}`EISv!- zi6e~0^pOk7AFVOcEtS9F#)R4?D!OUqI85LSS?^%Q5m}9VXq*=OCPzdljVQkV6=-A$ z+hb@ZjE0mv`Qk7e^Qk z>4`4-?xr8{n;g+?K(!IY_X>l)n$E;RxuN5BZ}{<24iBDU{4%jG-Pad zF}D99zg5hH+K94m>N3HeIKpVijN@XC%9r1!VnS^b72P-v=BO;ecah@=L-Xv6=MKLh z01tXQe#-#1)hn$PGJC2L__c*x4JKe`qo`NfD*%j98pY2bj}kV)9v*!-C7WPRRRXs& zbIZX5>}(W`+O`JI;kx2Lx|pxNQBhy82`&fco!1XG z!E+zaoSZ|OU=I^KwGaF64j$hB@0>|uh}*U1D& zB|o)XiztWojDJ^GOrYMhSK7JawCpG|tC@avY5!lR-*Ml9@{uwh-v7+6-hHk1%G9iQ zA#?vTUs-m;!HqNTU$G$LIJ+V=3Mr}WIH|W5&-i-O=yX5%`%dhEhDO2uxy6y0MMo?W zja?BMg_P8mS?R<^Gv{1Xk=|3*C+y*LVNYn)GIPQAi$!BsghnAHwH;?+Y0sH|$gZWW zth3m|>B4@dR_DxK%a@79t_Y1nN@_dKUH-6{t9EPeA1=S?%^pq{_KQQhW~yJ|i^i@9 zjY3LlJI-^@O_(WV@TDw)hI%+%*n3nzB~z#3717ugp;6FK+i||C_tea@b|2#ZeQreo zdpKR#g^%{hd|C0DXzYs6D5Rve{G!t2Su@LU4j{kZ#vV==cD=p&XSNi)B^tXTGzuxH z?Kl^IH*e-VInTKK7WtbKBaGzuxH?KlI9d(Pajv4Ma2i+uwP^>DhdG5VxeREox~2#tb<+SUjcXsCzN zg^f}4iU*=Ig4xl(MNv2bW}j7htmZyuGL;eMniUY7NH)S_=*V0)lo9n=F40g zXfVO{euEnqnY!8)p;5?{+Cl9$lexA)=Gs6*J;)W?zqdHD$h5h%M+*CCz27 zEs(i3&`=LF*q+>~Ws&K-(ytN;je>^SL2qv^&xfnehkBsF_H(s57nx^Jo{vOAqoAR7 z@YFWPJgd*SdZ58}*^sV9W-O8CJdw~SXsGQtSIwHxyqEm)>BVn12zOfMnOYu$LU$`spdDxx@YT!6~QQ~9%!)L{n0)}W^CUTp;6FK+i`xFJga#%S-+il zmzh7*0}Zx+soB5C%s9IuGzuDOJI;yU&1*hd)}bHVW9C8iK!feaS`8>NbM3AOje>^S zj#DTaw~9uSv1UG34>Z_@o>?>OiqI%6hasAm%xaFcE}ld7XgLt2^=8&SyCP7#h(bzg zTWua_sE5;qjrKQdIBN48LZhIew$*oC_Heqe(T~kql=^NCp;1Ul?O^rVT%JEy*SqTB zbYbIpG;3;E?Rd{o(b#>jY9!?iF#uc+Skac?^p;6FK+Zq#tlB~UyJ%po)i8fsf(dqAj%(}j(3-t5(AY|kMy3L0t$GpEi`0ihmF7dGZA>=SoQXcRQm zws)!Q;dJrun1hW5pQN(KCZZjy{Gzop%DwQB`7<#~-~Y_tL0SzeK9HyA?;s~^*R8I5yid*9}j@iC<(SmE=529dS z#k ziizYF)H(ry(xRPVYaQn1NJ6gMn7 zq+(NGYc1sFN?|L{cPc{IObM#Y}mtQopVDa5pV z$M54hfrffGUD$di>o_BYxVpgc<-Z(4qoASv&2jD&V($ql|ND9yWThW@I9=G$Y3;j0 z)SQ&^d+d=*XcSV?Ug?aq=8iC8G0PlUp-h zO%~$i7A^f=Yx2@s4tO|S*m@@GI7bPwSL>Gk|7PbB8ikZl>t>|BT!B5dqYi|(Z0wHRjl1pe5G|+o6m&k5Hh@+(M)~mlE&`=Mj3p+ZkT_?mr52XAq`{xoG z71T&}c1D|bb{&75JcsPzbYbh6tbF?+#2|SF@n2O!qww!|n$7GyNr>}nZAceClnMy- zaJsPdOjh1a2r+n%4e5jAIpnlB3jZFhuS$jZLdL`g&utPA>ahtvt-VT!<4&KFzU!P^ zB09O{RUe+Hav9q%m!}Hq(W);>7kYXo>o{G6xNuWmy0`Sks)R=2-*t`ZI5!D#zsync zya$AOI9=G7yUf`uoS{#Lc*L{iO{4L*KwapBh`GtH7i74#ukQSm~oBbeb zR3%j1CK5DUjWWBfX!onRGJ8(a2ne2?b-%1-GCSdLKF^o=JSaKmJt`BQ2#51|zRc%2 z1a|j0X-2NF_c435a6T`P`8*)hgPcSJp9udh?a^UtUco2FAmvs&AeV?vgrgO?O9PqMaJa;h1rqqTaJ zF7))Q*R05Tp4Y_vHJlBY&?uBc*YJ)rUNqXu8gbv1X2wwurwd!pdL8E^A-c6_>7F6u z38%$T`1fdUFjR;!@?X1O&CIDDo8S}Sa6S*l6HW_6bRrz>!W;)Z@ml$B)gNXB5bbf8 zFy#o(kR|#6Sx>(ct{Iq!&X7$x%)0$*As&#r`Z#S?GSU7lN*6iQb6>~VPtxD}xR&nR zFLDWu(mFJ|i5a4?UfR6)RI?&Odzk%slrA))6X7XBxYFidhif<{GzuE%3)t_-+gBl8 zlD<2-j#*i%htq|v=e}kIaIvhX*M@6RCNv5fy1REA%u!?W9k*k+rdAK93tP{9vukRs zt6ffuqww!|n$4*J*3?)}%ep!s)MFETB0NHfXJjm?7@tc-r^9BvGADQ8d|n{)d7z;u zLePi^J`r9Z8t+J3G?z9(ewm0)hxs(>aUouiK6PHWSBp-gqI99B=e~|}un_xym{+hQ z+^aF6QP9@2v+R7HkM%oyI9=E}!^tMm#1{`zZv;s z8GD$x?#vRe?xsfqT5{F0slVT(uKvbTik2~9N0oT%W>3jn+Z!5(|8#_3{rc|y&*Q4M zcbv$>M6qbxE*j?#1F_?zWBsy@1%CfiZnDbZj4Jj%xurNW`R+@tGC9sQP^Q_oD}{LW zxpsbo^V|D}EUUh(vic;?|8QL9)3(FKGs!!6(>ST05mj>4(UBcd%?|z@XWeQMtoMBF zN#5(##%CUAa*L$&;H)g`&| z)wl!O_+7Sj^b5BgV-Xz1HR3ppXSDMlzp%ZZH+=Wb+y-cyw6x8Sm*1Yv)l1E$i$+ku_ajuvsl)iAZ^o2XS+$9=?2et7heB9ArJogxj z;3%!PrOieQQ6%lLP}(E&^_h9>xldZ~H)+Ak>yD|CtFhAN=SiDaUNY9wU_$%CIa|kw zhCWf_Ca<;#j?$;A`kD6#p-=5=uOHII@`TTMvj^_2k}DkD|i=g+S3us6?nJcInM|Lqa4W#P;Wa&pd?60iQ?M>9sF z*09F@%maJ-!?%6hnLSLfw%jXv>~O#Az8-!_tM=`f;3yq;GYya{9jSjDSN%oyFrg#3 zDaX2}4)o_7e~LdnUDk!m;f#9N`+4{i8MFuI&~ZvT?CUV0X*Y=aAGNvaUb=ls&cfslY_;L4kuKQQ1_uD5^ zGu~ylO9`iV=X^6Y7^y97=eKeD_{Tlm&mZ>Ifq6`D)PSE$z5Uir&6ts4`C|?Jqnq{h z|EfJL@5Lph-meEu&1{pWbKYB}-aD60&EPp_TISly2L3OP^!0oEc26FAn0V#0QtyVR zr)Ji5#aQxw-v)kJ{eFJK#e*z@qwHL{>l*n_l=Suo>|3`B*U6R}OT8=4dOFjw_LwTU zy1;4V_c^+c|JGsOSQ<Pcu3AZ5J(R+%R`2%) z{?k&sJ?q?C#vZL*%$%H(w1>1{S82h^_n2mBF!6=7?7at1&5Ue*y=XkuBjsNmp6D)$G^jR@$AAJVbt-EWvdhX$`_IE#9-@8lS78~)T7U4;4f51lXo~Nf44VLGwMadgp+oR?dnc1LD z*ShXqw+?VK%Ma_q9wwfzy%8frkr^4T*|Uy&$Y}%JC%0_QV}hf8slL(s>658NKL(>x z{#CWyA%o6vpWCB(nd5B47*&MTWTixXDN&nbm8mJ2x_U`8zB_fG>+aZG#vUeA&#Wvr zdUf6Bq#VaDJZw1=9Mw^3;ZCWA?fc@1>UHKZZqNN(_pV3x>+Fo$jFop0#`D=VHe+W| zg!!u0o149+XHE+1>deoZxo@~dZpEm>@;K_8G4Ei{QG}VyCO&bSx-~|3bvJh_&tnf0 zj`I$76Gdjmxw6&~?#IXUaQCj$xeF5d`qC!BGQ#uE1Wc$UIU1S=ink)w`Yh`j77N zB}*#2Uf+%{>e%#pSpigFuU3Q^hiS)Yb#n*zoCn&vFReUeIeVB`_F0AZPUrDO2LyYy zKe}~vzhBnI?b+{-GA206&ebI+wsl{b)4`qE{n6$9POZTHwFvXXbvIUcb-$lbwEnKE ztK_P|5pq(rrM>(1VPmXZF>&CO3hdRSuCQ0@`F%Tg!9MNXEv*Mz1V?d=IL=sUk8`9w zmd~n}$8Atw+Gd)x&7vWU6|k~Z5zxIvUip?uP1GO^H#SDd)7+( z?IE6EipGsx{H=^j&1GD2q>mmZBiwCgJzcc;-m9}CoO#ZV=~K`BepP?> z-YvbC^L(e{2cB9TuM9D*Ykjv+MxW!SkFaJ=CO(((>VJn#EvlD~b>h`BCY~c>Vy(rO zF5|Q~O2>a4alvwRs7R#Z5{Va+HrPPk@x zZ`5IBI_qO~r|So-Cbch^T)T@b7t&FAyq{kV)hOz7NhR+eYUDr23j zGWNT*%W@_-%Fb2M*+;mozU=N^d~oaK>|sLJDCS&L*FIaim6tKWQCuU@itLU@_glvG zqpLI2sGX8NQT<+O+QIUKPZ0=xy54VrbI~30oR5;{eA2+WOPSy(ef~{*{CP(!w?U6i z?*66UEN2fB`plbNqN7j4O)D*eqjV%PdmK40adBSq_Nv{>!&VDUw%gTwD>yGfPQscF zPqyW}#Kn2Z?b|+_J{D26buJB}A_Jc0YORyhgf}_GGI6T>I zRN27o^Jrhc*GKo1g`-+<(j4w_G6(H{xJxqja#*A5)eAXl7 zo*?`4Z%bEM1V`DqYTK`Yd%K)7ocGqCGA?bnD+*5KS=(`@joZh)Sk5vYU2>qM!9=*b z%lr_mIQO}HZ+GhXr~5ZIx^Ee$Wk&_OJ}JitsjFE+bQ0p)tL~GN?Z^}E?lN_+xIJ4} zX6>_Fay3A5wIh9Co@&6ugyzufQrGuw;Jzv)-|K}z7Qs>B{Fu2dIE@-Ay`;AElIMTC zCyzbaW3WPEZO7Rny(A^Qq{}|jEDa`lOE39K&d&D8$4bBS#FV>K&X#J(*%GJ4QQDej zwe*71$Zag=S2wi&MozYaok?&`70z&(#&Y7tDM_wgYvgX1p18GE-7f55LVKv$N9hxV z6G$dFN}n#XSCbQ#;Hkwar{xKsTI{1aCC8DIR98<@Ee{boVwjU{Ibm^e!gB4azExKo zr6ZB)C33>z;)G?uZWB7OhY20|%&D`Ei8w=Mf}?cgGiS*14${Rt$m;W!$cb=pQV^VM zpZwmt!8=IgB%Ia4lWlni>Ea#a7bAbnV-FLo9h|qjcn68|b|&noV0SNlAw1a*MrxdF z>xc{w6LvY|O@oVfka*L;fZXb!(Kdhlz0inYr>P%+4Q4$-j}3-}c%u7Qs2i1jX~6ntwCJm>h*? z4n~IH>x3e#EQWNL5S)0K*)+u@t);3S=C$2sNZ4t|lGc>P>{NEh}n5q@`2)GHVnzUkJ{|4UB1o*(!}9upj8 z=c@OKZT&5B`cdnoN4tdYnuGJt@LPkT^>RkSDapONWa*nTg#~GsL%JhK+A7$)eBK)GDDAfofLv5+uJEV5EuQ_Bn6C9;AjZs2&kkWz=N(&zPv%8!<;gBR|G|MWR!56-qZK> zi{)hE`ff{32;XxR{VnUZ@C{bbnrA*%N@x0VGU4l4ID41~-)x2FS8_7p>v=m9R+M@F z6`a-wClkKD%?RJ*2k!^M?*M|6|6f}b)B6uOneg>3K=@`XNGp7U6%ec)oJ{!orhz?7 zgm1ILcN20l;p1eY(XCy&Fu_rFuHb~5;>Xh^<0$G;wT?eV4| z_|_m8cmI3Y%BaD*Brbn2;b@#ohonNY~ok1u0K)U-Tl1u zu;uJwB78F*zMHsx&pLie-a*d&aB~?G9A)SB04c{>DaSJ}93?08QQpJ%^+kOyy*-;N zQ@iihsN>%u8u!oKoTnP_Frj*8&$*~;UB97}QmvidH2i(+w36A2CFLvK5%l!9wzizF)K28Z{Xv-!L+-kEMtPB>|Duv10U}V)}A!-MfNbEPp~<&)UgDo zoJ?3z;kbetiNm5293o@MUNV+k5WM+$qHBG>ySyv<``Hl|!BILAnHAaC+d8}R&u{78{O9muelw~k z=@?PfHn}=@Sx@(}(+_eF-F|N|d(;L|tH+1lpRZmJegTn0aFp6cV{WIj-Dz!hcTby8 zT+AM|p^-jeo40&c=TIYw;3&0?#*7b!xcM(^Dp+{(6UFRN8yfFF{Hb^6q5FgyNd!l! zZ8WaCW_5i7R}4=^y1uN_NWbwHGgdP@>X_mO*xVXj#Arb z^!RL~d&GBNEwdByBe8|l`0YrA*%*ELrdjUEo_; zKg+z7zR;Og%pSF&(eu_%yphKol`(adL~xYaMx)K;7rJ|X|6TgR+K(5rM{T6r?X8cz z1IG6XHIfL9Qrl=8*6(!ptdV>BC)S!&%pSF&ac1cU-XQPBP$P-pD7B5oo3|9XJDzRk z-*Cu1#q3cV8hY|#>MDugD7B5oUzfIb7e3w2pI7_#V)m$Q(ha`-3C>6zXYl}_xQu##Baps-7m;dY@gWRJZ^HRJ*);R+jYMWdw-u`j=%d(5zwIdEsu}5tX zgYKK^-P>ttIKm|n9Hq9=SW<6xdeK4Gxj!uVy&-$lhQ`J(XLz+g_d|^&f}_+n8gst8 zG`(feFn4~tIStvPHZ=MUo8ukaU{$D*L~xYaMq|K@UzY#3|LtzG54$vEkJ`}a+H|2e za`x&_BZ=TBwT;G##@&y@FIr`Ge7+BR)P_d+mZhYTL~xYa*>dEg9OLiYZ4!IbhQ_?R z(^OYdj#z@D)Xug?0ovoF#t%(mkJ`{UzVR#6=F%Rq1V^cDG^CdlpkH;nXX_;Ps11#o zH?O6>n?!Jw+D1cqdjX!0`S+%Z*`qcz^!pju@{4i_1V^cDH151)FZX$8kh}Gk4#n(I z8|m6#A`byVvWc2Yd`keLt4Kgz1-Ufq)-c~WWk`d0w zm^k{PJ5%gY8^nxD$I-Z(L~xYaMngtwA7lHazl}?=M{Q^sb%ruA+T!BJ`(4Ot=k zSX1xu@$3|P)P}~GXUEXGJ&E8bwT*_X^nL6NRvtey#U8bx(PYRywEsvVI7)4!Av+cy zdz{WEKb>Na+R*S;-$(nXB!Z*VHX5??^08MN(z7(h9<`zI>q`&NelUsPD7B4->>z#Y zInU|+V2V9zLqkt@V9O2Z1cIZ~HX5=M_OTQG`~jK8@*=M1;jcehmU@2}q0Q+C_Ymo@ywh1w=pSHJSVf(~Dv>yN3`wwOI? zBUew?U+=v>d|}4qFp1zOwT;H$UaJdUdE*Md^N{+*>`@!(Ui12^-qq(W4>ghqj#Arb zoa|00IQ{9H{B>_^oWvfrp>g!-a!u~_m7zuw!BJ|58jrUqXjVAF->25ylh~s+H1=Is z=5<@}s%j(<9Hq9=X!Xuz`G-s%>A$_-mWk|9+qA)A&vDj-8cBq#CMe3-S&edN41D6W z1{!5N5%J}z^Qj!75le8C+S$5Fqps$(JiQ@%)J8cr&z{BY@py|^f}_+9HQWhlwE6r4 zmo{XN+R%8Y%{1y)(&n)QN2zTzq$j4)cW*kVdWt=2L*u+3o}}j^iQp);jfOl?X*`2p z-f~omJ!(Tk@2kOANHR z)BCv%*`qdy;dejhU6lDMpyk(L5(th`+i3hQzh3^O{1uEoU(IO99<`w{>ZWJBFAF~n zHIfL9Qrl?kK4MAwu$@=?gZh8hkUeTcN(2y?-y(txMh8jtP9c2ikas5@b{lgay^snyONmlyoiPC+dY@%1~n3bVM62Vbw z8;zz19`5h8qlaHO;*1n~)J8d)ZF$gp>#PN#MiRkMY8#Cm@{3>i@7caLq}Zc2G)}$j zK5y{DPlXyu1V^cDG*AZQ?Bs&GQ|wV28l!F+`@yUy`H?;yP$OS3fPX5L~xYaMgwCN zMxch@&rY#NZKT_C=8fLlFPs!=BoQ2?w$Z={ijmaIo0npb+9vNedVh6p*vi;RgyV3O zu`P}KpC6qk&pCS{BGfCiG;#=zQroJlf&=%StK|sZ4`>w94eKq`2@}TzH|* zAAyEOK_i^6LX9MXqtrGU;mqldzPP*2gMo%dK_i@lLyaWDjtXY#ASHR*XVwhv4c|7^ z`8@QPC}@Q1hfpJl;3&0CIl`5U`};Gy>$)V+&?snx>!460iQp);jYha4bAMU?vaYWJ z4UK|ExSk6&k_e7c+h~L(BGwJYoP zN$gP@8pAJr1MBusBZ=TBwT*^6Q3WzuyRvRCW{=v?aGXt8w}%=@gdJrFqah=ME2Fh5 z>vlQ!VNaCqh27r8x;@lLA~;HIqah=lE2Fh5>-J*ysEu;G+jJ||?V&~z!BJ`(4H>Cj z{3q-7V)m#FjYTEfux<}Ek_e7c+i0K+$eFC$i`k<#G)CS3In9Gf1V^cDG|(2PVOh5q zvqx=c9QEs$Sht7eNFq2&ZKHucg`Oho_G0#^4UPI6zQMXZ)JP&YN^PToX9GQ6*6qdY zQ5zba_x>L1_D~~<;3&0?2A**|xw39AW{=v?ICK6FSht7k#3X{F)HWIzt7Nn;kac@8 zd(?);d(Z!fb$hfHjU_lrZKHuP7h|ui+l$$wHZ@2hu|o+t-4Cfx?Rf=d`F^DNH?svP$R6}9D<|NHX30Ire)o(?Gb2b6g0y2 z&zN!~5getq(Fl8DTGs8_uQKpx6w(d*aj20*aFp6cBYdLLvToPsBhb(&XoSyWsF6f) zl-fok92tCBx9f8rXlN8PFs?-B3`qn>sckgE5zd!&doW%hEqF8v8sYdDmLrMaD7B47 zI8ytvZr5=)(9kGogyVdukwkEm+D0RsaeP^~>--UDXcRQU`6|>%A~;HIqY=)WzO37I z9t<=z3L4=Y9BL#Hc2qD^2Pp;XcB~nES-0za9(qg^G{W^ms1dFiatMx6+ms_*$@sEv z*L6vtp;6EX*Fm9162Vbw8;x*9=F7TW*H?jtMnNN7&xIOE1V^cDG%&8?-g$2R{5C1}M0RQ6OUFOu?YrOIp+*wHQIQRebqDY7Uv>0p z?zS(_NU*&7w@URqnBD=J3+~890(<9CZ zHIfL9ifm}?f7D5St;Y{_2bGLXu_v-i3$JZG*<0VRW2lita8zVNWdc$$w(bLj^;wdQPrVYFd?6y5-JzZ_{PtLX9MXqaqs`KP?&IH@W)Ag2F%N zq}UVLrGJPE>Tpa6?OTQ4|!Yesg^PGiq0Q>N8a&J{G3r)XwM%q8x&wRc%Z?)lh_m4m4!p6 zm4~wd%8^8HRAiS5A!B<1W`nNXo}I*=$gV7W@sX9`YygcUf}XW=~{S7N$ph5Y7hBNFq2YvY{bkyNlVNfBo6T?1}8k z!j*&G4`%~tBoQ1H+0Yp3Uh6L0I6v*}KfRbekzH9>GHDBq?MVbjMK&~AR9@)5_SQG) zokJckW=~{S7S3uXzfQZYX*ho*5gZlS(0KFLzHa`_4gA_iPAq0mWLFmc-2H9u}uft_yLyaVY zqaqs`b&lFv@X54G{JXwCq?kRCU0Jxi`YP|PUd5qC62VcC4UNwRJYCS|m+Spy2Yx+? zJ&|2mcxBTS-X*U*5^5w792MEns7!Y)7<%HZeytJ3lh_m4m4!DST;?sE_e7|XL~vAO zL!)!YyYkN*Hqsye!nYII6WNs#73{o2jU>X3QX*gRTkdAZ9bJl zG-3&kifp7LB~PQS7N2r$L-s^=WnuA_=czrC2#$(uXh;jD(dI9|_+~@)M0RCix4))S zze*xFDzc#=Ju!{Gd%}17q}UVLm4$WBn@Z0|62VcC4Gnpsd_05uKh`P5p2)5&JhR~w z^qeOV92MEnkdeX1Sn_)QxheKUc4c9Q;~t^$Dv98z$cBcDa6ZPwQ#*}Ju_v-C3+pT^ zp>a2f;Hb!khK$rc#`eFfjZ3j7vMUP*uA4;jM-stNkqr%*aeT~Cmo|7L#h%EnEVTDH zNd!klHZ*Frzs7HR;o@|kEmKqMiEMjMC4VpVxp~F7r6;%b{AeaCrJ1a>u*R1g@m4?F zt1%IcQKDX0o{g$;*~?km)`&`5N~J9={G()M5^?f$@04fLg&0eAd^^qC|Jjv+ZHQL_ z+txVpn#JDQ)9MrjqmRi|7=@82{CBJ5W{ip%-Ng0)yAUXGL5JYTkR6v}%6$DX)Aczeu zgG`DbV;V0A0)ZqD<`4o2BqtY=kO)y`!z3-rU}RFzMs4k{R@GX&o;rK&d*zS(QosAI zXTN)>x$5kliDw_5S&h4Qn{=dBf>C+I+V4SygxrxGr*G?ckSL>Kt?dw6pGT!hY&Qy# z=oFRbWc#n9ROCz&@zlAuwp<4ZMsXgtd>);7Gpg6Ge|tRN^)|k>TDaY6>D*hNc?Sv! z@vHM&@dQbfQEfSqc~_obeO5(2X1>yL7xQRI+*V&--<9)NAt%~hkUahP^{YEiaL;3I zuf`s`VN?z|;Pz_cUu+W7MV>CMoXs|L#(e zGG9Nzf9R|V;v^|unqyk8qk|~cG3CAD8Wh*Ow9nwQ&QwUS+>{<9iYVmJlHfBZ(O#lR zFsdkN#l6ZaCgo}m&$c`(DqP3mx=}m9D6VFe1Qo8U(Yqw5kl@N+JHaUCg_2<3aOw9a zS4UmAAm$8umjo3OYi$sIsdvylPQIe@+Vxk39KPsHc#wEt{8cR;JS#>qFO=6og~U4^ zy0X3t?F6G<`^J@Z|GFfooHypmx<^j$lAuE3#=9p~8_%5O++7lkntsZpaHnTD1eLQs zJ*oQW4cEsg9;yATNL;t$r0V^DnBsWwSd8N8V(CGJ#A{p1bzJUvkYE&77fTPx?MrSu zE*@*YFhZK~x$nlb2Cm1D1>U6vkMTNv`TTX4M6G>ykHdRwT6Uay)oejM7r;5WJ&W zQ^%Ogr}BPGdz#9CKwg2tI9nLt0xXY zg+$)f(Vt6nhBh8c=X%p|@ifcw!SmHsnMm;ZN`eXrT@iAwgG3n>*B~82*C3y)qbx^C9Xk6Lf1SU4-$;xb1Lr@pMlQMr{lIi4=5ybMZh^LmJdd?ms)w|VNEa| zOII_}aZw7&>tKl@p{pm}S>afW($yM=&{eCbrY9|<#^4Mn1bx@If9M**2#95Kh zl^@50*HJ{F6qMJ&++GlArOELiq3cmGigjh_!8|H?EUcxa<04O&1j`2rUGwzL3dbs< z(n_pDu=m3LL*7%?-x^RM!Lu!|g9M|Pr%R$xa80^a>|94d;A-1TE%ztoow8xyQtK`x zDkSnA*#3J(f>C)#Yd=9H?@9ef&x%CeZQAd_vtks>P5C^y$BXwZ@09NMph6<0?H4>; zX=oBDD)0F2_n^Y#=6&e>1QimJUbFhu*3I>ge!`;ie)@io{40?m{7R(W4>!>CNN1Av zi{;;c4B_`5{T}%j97Fg8$3NV|< z=Rt);{tboaVNZ=w?N3n4N4$>wyP_fduBhKb+l)bZw%p01t%UQ;sgTIO$LjYW!6=?> zS!$_}$iK(x_aMP2-i1DoxXUw@)FWP6RL@N8^P$DEf;F$1+dsW%aXovs+JlQ_9zRBD z?r{hzB;-h8rC}6;QOrHf>#$rx;^=D^%UX!zvFMNmvKkhZdpBJmYnw4G_i&Xzz2wv- zyeA+3j$HYSMBpAa&nm2p#3&MSR{lI3?-iqX*GmsxVe-)HXsr`@7fHzV*&Qi8NH9ur zOjsX`*H;p}yS$^*W-e$UR(o)M&P%ZkPxo!%6Z2bg36+%d6G6Z7tojLi&Qso)-;ztH z@VLw|r3a%{`{X_0nkK~iv+S9LvfAg|D_*&rq0J}rnwlP#uSm$*w&W|^QAVZfNcp(* z;Im!r{6(^s8qb}1p(Ln~`27}(WG&UXauST zFRag8!lDa7LwPkmhvT2`VJyX_}vR9m$B=gppx!%n%B^F*C9AxlIo8{kS@=P3JGm@9S;(WYCkKsEZSP8yMTJE@2sGZ z(0125D-ew0HF+L-M^mdGkE^|bR*yt5ig%&(xanQ9s|8=5k&YE-%u^lQ>D*cUY7cL( zbD@BkJabNU>DUXLv!cg0-+6oW;djn){5U(9W!J$#IF9fblS68gM)$%4(lZ=dS98m0pSS7oUD$xVr4~r|J8zc&|t>ihgCjqC(=%J%+2-_I*ps zSy_w2sP^knWuEk2m56Eej%oL-Tq56*wkxNHUX#AZtBok5@|`ZvO7oST?@dzfVp{W+ za~)JPC#I;BryYVG1(8bBD1?@%6qRzNM-)mdQ87wO@F)bMw8n6VQi*j`iYmPMJhW!e zV`W0irsF|^QU6%JBB5o|@!+u-#XMc+5?OuAJLRTT%MW+rFF3B-YMPW(^OK^D|dhP>KU+G3EP}6rWS+q5J>iu@as7T0Bxo zP$7}7FVXEp5%rJV-590Ejdh~u!MmGkI}%nb%ywqM}bTMYYx?B=k;$@MbynIU`DI=k``DJ?BI)Dm|O@ z_o6SV&$&V9JsgE#ls+4Wph7~Q$0!7&^l2*Ly=_|F@o8_EmM=Y8I=%Z-zjjl6tFfQZ zZ{-Z9??ko{jIwm{2yg#xe5+9ui<0B&H-FTljbN0elSg=qdE;A+qF9u8=(mg1qm5vc zrISZ^8++qhjiOjoxC5f>D-E9`a29 zse$;d#(qM-MW`Na1fwjSJiIS2iegde+|xG|Q@V|?uP~A*Jc=(bCM6$N{RRq;2Eiyx zrz7c=7hhh)b;RS^Hx-jd8^I_`Cl7t*#kU$ou_!sNKL5ew(MB-J(#b<}V)3m;Q7lT1 ztNB|2c_l85#Hif=V0B_CJ&4|*MK1fwjSj-)-A z;#-ZPSd^TV_Jh=;jbN0elZW=mif=WFVo~Cu{WExk3>@^SSWGugu>7-i{nq;Tbp zFE5H>QF0xp>$e)~d*u?0vUKtYPq6W=Mo}zEj;r7N$Q^;=SU9c=`oES-)N zYPiO?8bz@vIV=4pmU^@ijIwm{2sL%%TaBVvlz8a3z0{+PV3ehkM`&>x-)a=aqQpbK zQI^}mHiA)>P9CAP9ENu7e%os@v!eJrgR%oMy0PX79Pcy7n72ra2@jsj|QP<6{9Sjj-*#! ze0dSq5edC->d{6p%F@Y0pJ4H=Mo}zE&Rw7XaJr5*f>D-E9-0%2Z#9ZyQF2_($Li5W zFv`-&LrYZgtwvESN<6eYsz)2aC`%^~tr?1MHHu2xIR$rRse6vd*% zL;FGM(MB-J(#b>naK*P8MX@OH(Eglyv=NN5bn?)?Xz{H^Q7lS4v|p+oZ3Lq%ojgJ> zTzbgGw;DyUDDlu9xq7q_WmN2uhhI*<5#BJaJ^fzz#=3rW;Z;>qlz8YkK|R9S-PrKP z_wd!Mle!=J%T3ju%hnl`uSOpH+)ZHw@t&AoH>@;HJnCWn0x^jb4x3Ufx&Fnd%o{hg zdU4uwF}=@!-CP}f@OF`ot1`96ZMv#Z3}4-$;BQE}6Q z3W;rxx}`d1U;ExR?=A^O*{HbbL4|~kahn7c65kq}Q9Zxk9?q4MV3dtG&+~;|akhDcVyf8~@ zQRm7@lu@aV()6(YjwmGLX>K*xbv#Hg%K9ix4=N-yk2xMB7-fBwrU%x>&1f$qem#s4u5|U%~eSJ&Eg9M}4ik2Qv{d9JHtobX3FInli zYhG|XbR-lNmO&kbIRq6Fciwq#D1(R3Yd#P5OPKSeoQLP(5L8ImSfuGef>CmYp?~Fg zP$6Mss-_1CM#+^gxo?rJU#+~IgoAz@?OrUwZ|J+S|M)sdUu z;CN6WVPo~C2MI<^`TBjK?|Zr9!5-`U?G{zzKmTfs;`1+aI~5Z03x$g>`n}^pf>Eqd zOAjg}_B&!>eTMA>qu6$p1WPSTs(L$RQ0~=NuG(Zk?z>$1X?wmqrlq89I&B;0%J~dz z7Dwpz=Rt*p%|R_`QMEWEZb{hm0VHW7Le4OZ!kx1s!6@Fh(t~4Xj*4d= zd__wyg9-^-8E@ux5{z21;PRGP11cnJg}>=Rf>FEgcDdYjC+|`rVLKI?9wZpG)~_#< zR?YF?Y{ZA|y;ADh7{&WmJ`XA+jN z$FzBxEci>*viUNPO@ayuogH>ONR&}&rK#y*t5%})6JcK5@gSkI=P}Awu$msF5@*jNp|kal z2MI>$3WP&YA)%`dqY#YJl@y22S+$tsWF5z5Hrb+<`HBh&U1@SWNHB^$gVKX7^7GqF ztA^e_V?drkd+SVv#AV-|R;~Qb>5(oyNHFTSho@Cv_`^*OL1mlwUt67fLyF>&+C4}d zef+i6347n{c<@+^dgW)=R*%j1u7f=<9jnLVvK1}QiV6uGg*#_Of>F{w+B!w)LB$~) z4-%S=QLKYY59y06xo`a#B`rgk_n9ZTMAME36%txgN4oSN!6?@GC2{V=+11R8)4KD) z`_Hc4zUQ)d+z)LtTgD$w`H&u~t%h^9Ui!ZN8VeN?lh(PWWt2*SQSGZTR7l*o*EP~c zId_)?qnM}5dqssr_vmmPU!3cBkYE)1^Q8wzkQ2Usvpk!4T#gM(f(nU?ufAEHrgK&# z7&Y#Ro2#+kf7u}}S#NsvumAE!RDQha^y0!$aHd`F_adb{5MsZwH zUI!HtItS!8QlDkR!-$BE{{|aR7kA#_gRuFM>#7-{duL?GGFH0 zT`DAwST;*?qC>Ex>daj{6PB*>I;fD)nL_6}NH9uw4moE`=7;@nXPMqRV-T{3s( z5I=i#p7e^NvhI>$>9@!9>6;HrpV}d)koeLG!_see2)dvC&bwshE=KYC%A81r1pV3x zMxAx?Jn6SPXGMhs??~yvxk>E-#+<>?Qb|xDp?y0iUy)#x_8Fb)ph80D!W|D;F|jd# z{mN8YA6ez_cR)}fVZVcI_I*e&N>)t#bxtZI>{q`{4-$;p`s&MC)@${w2IN>u$28Y; z$|p#LgnC4}B(w#Hinb*&t*yjh^E#-I&^F5Pn0>**>NlTAeS?XAonNhf@c+dALwlcr z3W+~FHoqEt`PY#yuS27Ha=x#kF8tcrH^g06zt37|PUQCz7LBE+LJ>;l-W$7&G zA;&b^tCFBX;v0|8l0LPQcS$g+y&YuEuwSgpb+qS_Qc1s97ebHZTsa9weRkqyExSdi zkkFj(c#vR}c>B9vsF2VS?A%=vjFO!1@7|$8LVsEAc#vR}ludsZ5)~3!HXRQVjMBAY z=k8J=A?w5P%NKe6W!@#hC|&b*JgAV+b#BLl1f$w}8B|EG?@lvl2~eL(Js z=E|66U0D)TNN9eGbUVQ)%{>mm+ERP^F^aWo=|P2rj4W)=Z9BoJ_R+TXUgDW(&nc$0 z$KhND6%yLNatPMpSA<=~-`xM_Z=y9I@qym_>f_tYc3K0rAB^JYwY*mx%QA|ycqKuF zM5nW$y6o;3w{Dg}5{y#sc}=2J@^RHKwsz%NkzkbG5yyiH3B7NQ2MI>$vvG(Yzdy9d zKVBiaFZl9;>f8x$i)psn<#kXYal+(4|L+**I!G{zy@Aq$=c~Cgo;$CvB&d*}cRRr- z?GriIL4`znPew*`VSi#gmW&{6o?7b4us?C2nXj}@9ToO6r3Sav%mb1>ou6}vLP>LEF-qs;Mj;rb^8pS)g@n#Oj6yIt+w!cmwv5NpS~RA$4t6{^a+kev zHhapEe(6Dlg#NN;Ub94zV3e*KIYgnP-x$RxT|*j$V3e*KIRq6Fx`yNstVOkUj!~?S z%X>wI1nc~Ef>G){(7d};NVK;ftjTm-8*4SzeC1hDA)(`F=d4IDO2_RE!FdL4En}3n zqTS||Qz5}pP+kWKMrjYnIV&n8{;?9J`$gkOs3$UORb*Ppm*WsrbnnlbIjgjPHxjxJ!13T&F-mt4I0SRGuJFbv=AQBiQX!$M%Z>*L zMlp|-9$$HMij36;q~z>!=@c2O#WYJ=NgTGqRGHI_<>2j`OqChhm_BOl$+9NwoD~%k z{}$f75at7%5~WI4&Ps`xR_~ZD&x*&oe_*Q26vX4wyCkTPXfNj^7^U@!bLCV>uwE(8 ziUgxH?RZcjp>2D7nxzK`Mz!|2tJ(o}+vD)e(zpb&3b5McZ9twT{Yrug3B4ncZYLPU-asTKhWE*=5#A@$ z%io~SZ|jlw)a38c%R6hrFL-K#itUsZ!uCL?x7@T5j5=n6@XPWWf1+={Awh+N?PzX# zkSL>Muk+=ON7}iZlqO;C#4{JP)0j#5dxu7$82&CTl|!KjIkUt1kK z|6=Dls#DIcrtkH!@NWM6?r2Hxw&K~<y$*>XMb8ay;%i=CNwS zw~QT>W7%F_N&oJQCt3(9ByB@jLP3W?DwET!hX%u^dP~g zZ(j0H^_%~->fBSF6%`U%9-Zewf>BdnTv9#1 z^GOatg@o2CqY#XG?efLd4u_uU5L8ImTa}u3mjt8O8!YctsiZeQ$#LziN=*+EjAEa$ z^kAD|@8poVP$W($aF4O8Sj~9M|^4H9bf$iv7p3L{TAO`|p|_BpAhBX6eDaq#iLZwdX4;B=o*H zIgtdTR-SxSbeC#BVAS4Uxu*K$V?S~TDkL;ljzTc%jL+UsO?%s= z4nc*4mab6+qX{Y`v?uF$ zkSL?_EJdet$cfW;z2u)x?4EGs9p|T~_BK71JP%0^4Lo)3t<~axvA>fj6^|GS^C;Jz za_ack_V{-9+22mRfJ9CY4Xn5Et<}QqR#R^hRD2?Od}-jmuP7e*tedLz# z{MS+s5>$LbJQjy%ad^1HXI+2kL=rhYG;qOJZ~f{IU=$B8FQ zpL4~>Z=6UXr_*(eJ$6HQ7$L{4mHJFb;9kvL^^$4vI*iD4dLA49Vw3V-MMCb6DLx?{ z`UK~GdG_V;c^Hvt%U7GJ2Z{8Ylj0NN@nR@{e|Tg}@5Dcyr}-)onNH)uo^$3Z*_165+U)j_udKczLB%J; zBh+xc&<@TG?ci7vIXyIR$N{(4wQEUG@d@z=ty(X%gL6YWIF>|C4-M>j%q(1q@%1;1C6Uu1>Lj^WXa{S8icgq_w6&of97`gn({<$bT+Ye}Ic}}gXF>w^ zYJ6x1<8>I3>GV8uzeMkDB;@{>;uGSb&wPAn2jlZFBGZYYNLX5;bOO(9XXq!*IrXD1y zctrAeK8%Qd7joiG%cfpH!qO5Y?;yPE%2(8b1Qm}+9=C>CTE;nNOt|BG5|&O;Gs9aW zURDnhk`qnwh}vV0c>L)@Yp+Sd(h?=_gv{3wJZhp;k{^lW5w3i$+^eTTsU=})iIR6) z=I23zibo`m@C4_|Gk<@meMneZqU0T&IbV^W;t|OsuCl!T=vO5RnS%LfT6 z9+5mkiRwuiJTtTgBrGja@^^vI-Coe)|z5|)-It9?=#4E0r4>Z{XE zJAb0pA5uqIS_rF^{`wFJDjtzMq{K?UUFI@KSX!dwY345$lAz)ddL5y} zN;wRE3=)=>C~2?q*91vW@rdN1?O-p|qOs+)V;L<`(q83n1CpTP5y?Z_!Cq($ zV#{gAGFqafy~^JPBtgX^l83f~z0j&%K*G`~Du2VT(;*>kpM4L|BWe$62YaD)j&m7C z7%frKUghi1mNOEilKe;{4{Zl~p_dU`PCJ&-5+&`G-NR0Y1Qm}+9@-A}LT@RyoOUdu zB}&>W%L|?Uv_wgJmCFYSDjtzMLW$~08JrpBGDuijqNIh( z<(vc+k4PTca`xtixeOAPmMCdCt&Rz^2C1!$1Qm}+9-)S-=Q2oGTB78QlDXa`LB%8V zIxv?(!qO7O_r;g9A5=Udc}Up^t=gP0r$3g2r6r2*Xic*pMo{sH!XwUQkg&8}hrKPh z_K1WW*A$OP9-#-&lRm>LVJ?G&r6o%4LVoiw2`V0uJVH;VCw-qo!dwOkOG}hI&HPST z5>z}Qd2q~0!qO6DzHz|EBxpMZkN)Hl@5^tM3 zD+wwjjN=)VpsB&4sE=NafhqKx7^90}=#*$iDjVY4D-ZYLpW zi^{Wj{nt?{nUKDge;p(km1iUSJ*be7zLx(yNEA`^tZKgp=XXg+U#lfw;aH5yv%~!! zR7gl)%kpvgJV-Dq&vN&BP$6M$RI@H2!Kgf2-|s<%1lz>&I!G`ouR8R5P$9v#z4Rc# zsJwd8??HtG`zWOci6W|A1?u<6D@v(1Y3&mGTBQdGMv1rWr6>t1B;*XO-EAirCHK(w zQj`Q05^~?97v9WQBp8+Qf~|A1zM?`xp1+JHnjRz=C3)KRQk2(0g@oi|85K1>NH9vu zrtPIDJ*bf2n5vy9qCy>0@1-c(sJsH6M~!ms92=G%Bp4-iWxe~N@SsA1W8Bh%1f!(R zx4jf4L4^dz>g_}sC9R#8OH!+rlzu{HESk@pgrqGh@9O9;=cST~a_)q=odl!u?v#EH zDkL}uRNgBRMO3}Zrr(46eMoRFtMnkjsJvUK--8MX&dHS?Bp8)vZl3^Wc|;`S3|$1xwyW(CJKwD^)o?H1NRqtEvrmJW^M%NKo;Kp)i7! zy@@jOT!oc55;;9I@Q#PBtk!wxX!RgL#V5o=_E^fy^M+wXkwi`p4ZQY^E2|~99j6{7 zsQ83<{5H(*{vpgfZxB{SN#yj(9Sm#YT}Dn4Nz>mNUT&Xr-`D~X&=*YW;8Oo4|Ha$Hk<0{3d} zKZSj-Byu`EkB{DPeR;1UA@|1=pAZjyf^)wf){02vwB@TA>Omqs=cM?Ac-$ZI?z)eT z>3t)t6_Lp4R6aJIIZHiANPacNC&WWbRNVJUBBxV1-}|b$>On%vohd#c9$GW>)(mS! zByu{{SL@M)w@SsxIjHfNIhtZPl$)s)V=4!S`mqy zPVL9x2i>C{B&0q!#V5pL-}Kvz-a%pCD~X&A_bRqsi`0Vz6`xR#xQq2GVc#o>oE{oj zYlF%4*~YV~2`WCJ_iC=}q6_Wdnj~_1Xkh90C)am9-rbs@;uGQ#o}lcq=!JH0EQy>B z_v)p|b?zw%Dn20|At&}iJJ<{D;8+qlJv6Z2UQ_B)P!d#pLOfmz>qPSJs<2i>BBzH2 zb{d*em*$e7;uGQ_*C5w&cUUVTk<&v1+b^9G>UOKINKo+!@!-l2iJTr9`0Pqk>)N#> zsQ833QUSiQe5v$o(lU=;uGQ#MqYDdthRjE_evtCtsP8bxROZiQc`?EJhbKP zhIUZLgNx?L41~67AzioU@$V&}?du4H-m79f7JxEaT3G)bJPL2oTu`*qcYvEyp95=Ls zBM`V(^?1;TOxNRc_0W4&j|W3L7!{uo5038SjvA5EmaooI4-)A)C&eekLuV#>->S!h ziO6(4U!oo)B!`D~Fe*MF9vt0~$mx3CM?FYLxeKjYRD41_v}UNsgGOXJ)mNeIQV$YR zGJ4_eKT>AK&p9wf9M9TlGtkLGwV)mNFW z#~%R;H~TOk=o`$RoNpY-TgiB*cSnxzTm!;j|(h*Rw;q zey@T4orJC;k3firz6qfl-UndsHHbu}>-RJ0kx1w&@(6@@=o=ln;e7z{y*Ob{K_oIA zqSCsvdXS*v6XKz7rl{YG6ZS@=W7Ws4-xK6L*n7OvvFhX2 z?;}$W5>gL_9m*pR(Ib?<@IHWEcppG~FOCtJPVGnd4ZnGSkQTrcpAZke<%UE~OH|x# ztR5t&_=I}I)xP{*96Mh-Zv9?^>`@cCt5_9}(0e6sLg-S}-2MOI( zJOUve`i6~Oct4!IFC!9}uHXBi9wc;E@d$)?=$k@%;r(#--j7IRx_*C&dXUgv#Ul{n z5o);lw`3%8x_%FfdXUgv#ZmDI@z4=V{azfacQZW{--{D|$D$r2bXRdyd_p|rw`9`d z$ZyF=!hisL~NIbFY}NImpk zMM8HKN5v<^L!V&%UL5O}WZLpo>Jybjdd^Al3GvW3G#A8ss(oUY$TrXD18S8-D6Ga(@!`UbOZct2cxFOH2rGM(Cwun$>1Na#M~sQ83< zgjOw%2kpH$cC1WGl(atEsRs!vJ|Q&M2j$D}olY8C=Je3OvS$|7qt}w4;uGQ_eRkMnR#h$fCLqv5D)F?$M>X?$myYhDR0cL=gvxkicg4#n{n(ucr8fcxV~yg?%!yd>E1GRL*V9q9ml;nc@@Tp>;`IA0&~}slKwc zmy(eB!xWzo53Lj9`XGs%PW7&>A(e#GgQoa|cxc@o*9S@DbZS3r6|f|vJ~zcD#DlAS zByu|3tJrp>HNBFc;uGpoulAA1>7jwGhwrJ+w%&^qR}`uEgx;%qeUL;>4-Nc&i$(Qa zkN2u3sQ83<=*)K9FG?b(!@W9xQJs5Af{IUwhtBE8{h}mtdT8K?mloBfpd_gHgm`Gr zGQKC3L{1M4?DL_;b!jdMDn20|Vdp?E{BEKbem60eL{1M4eEd6$L)~um6$vUnAs%4| zL@)eqVs7}|#8?tJJv4CiwTtW8wIrzcgm{FV96jk>hTlz$C6UuZ1D{^BxNap%f{IUw zN7(h!lN~AHcN1et<*sYKl*Y2S;}#aypfBThl8EDR-v$gm`FO64wVw zTRZ5j52ki0DLx?{+SbP34{A#`AY*`>uG{nY_ma@|bp%51RWTm4owAv(`z7kZ5v2AL zqT&l1UG*TL{m&5y@z6eXH|&$K{%#~PUH9A7gM{{@MCu#{(k} z;?X}I3?r6EWV#+lsRs!i*Ni}jhm7vz7YbpYOdJn}kyj)#9r9Hg52^On$k98-KkJhXx}Jwq4-!%jhITM2J|Q0c<3S@bUC$?~ z2MMXqLpvB1pAZk3j|rtJ{(g`|PKSGy<}%fT1Qnl9kGR?=zaJ!#({+2EJ!(SR*Qoe} z-m7|aMZ?rG;}7*9q2qz5_=I@$j|Z*Z&2&AEQV$Y3u8E3Ih=+{s1 z>On%vo%LRQLOir)sKDJec79*?L4t}$6dv&_d?YMw*Ky9n z=an9jkmH)-5y?ZZJnot#VQGnyyRhHdrz}QdE678`7vPy_RR2h7!sD2D9H;4 zAAGoakf7ob$>a5~^7C9+wOkNJsU$2dQO_TGclFph`>O{DDjtzMSk4PT+j`;XJ77~`0 zsFN>PP<`d9P1J(~6_3#CI3<0LWrwh;Pr}j?wcim7tJC&;w_OJaDjtzMLp7HAv_#4C|NP0nR1XqVJR*5$zUsX_yt9Ucr6o$9|BKU} zQx6hUJR*5$zKY*BAYo~VlIOqV`WNkaq@5g*pyCn9W2NxUsOQ5P$jaecjU+5BQIccE zfBseVAVI|=l85HR-XFvF4MhWJLM!q6J#Uql(%VEs?Vgry~FkBfea@)#i9WT{RhLB%7IN9bkrq(>&-Y9wK4iF#oF`(lqQd61yu5y?Yxy5xA-lS;zU5;f)P z_r)Gr@*qLQBMOhWCzXVy?K-62Rd_@~j%$iXBoDpv@uBw`ufqtVB}(ps^vH^P6$vUH zkvu~GswX|NFNHNo5|)-Id79EAOCBVsctrBhoY)QRV9Zx`ETbh#a;5ahk_QPY9+5oc z`y%q?o)g2KR1%h!C@EdiBTF76sCY#3(3+vUZg^)62}?_q)DqGoOCBVsctrBh8m{~9 zuqTy-r6o#gJL!=n4-!;7B6+-mHAoVcmME#UrAL-LNKo;Jm3JLZZOAiu^%Bv^+9#lxkC@hc9dF3P+l~;lKJ*be7 z(PSQ<(}M(~^7>c52Ne=FDo*)|9wZng-ZlqV-d!prY*gIzAi*fPhc*XTdQc%@qvECq z2}Y&7VDpK*aw;U``RDO@8^I_k1vUp*UI!Htl8^KFoE{_?C1um*080-lB&0m%@i{$6 zFe@$`gBp8)fPx?Km zkYL}p^dP~gyb9FsL4^eS@TCU{M&;G4eh(@nI2I{ANH9vgZB4HvsE`mpzda|xD7lBW zHd%U5AtCq8@0XBZRLTpszl60Y6%z9NZOx)QD-w*7JZ)>mB|(LRg9-`G^_Cta7{xJMNl+odaa;JpYFalKKkdISvUP)bGE&r4 zfO#@r))7)ncRDwOwTT~v8L16dICz{qgV4vBC(l;LpOMynQ2cwRb50ng4lFyqx6x&v zh;ztcG}=m}QEHe`lW*Slo(OMS;IS+%QQDtV4-!;7B6)Czo`j_(O8ceiL4t}$=yjwu zuej1c!qO6@{cF1p5L7%OdFV=9@51n_EfSWNC>vl5tW9#Q(mNOp9Xo=Esw0e-B;t_=h*U#gzjJE3t{gTq7UOzX*Ba(++dA)vagq)S6 zB}(o>=$EJm2`V0uJY?Uil&Ua8Z~GbIv5b}|d77bLq8>U&*1KfCYtOeDN9rg`3t_cV zn(HG$#UoN1r89SNb%}(fB}zv~S|^gA;t|P1XCUK_MiQ2mC>-g&wn6=pf&v5b}|9U-X)2`V0uJamS> zUXKd1HSt(ROO%d~)Pn>Sk4PT6(l9sd7O{1Mcr2qON=HcQL4t}$B#%%Ai}fg};iMcG zEm1l`QV$YTJR*5;b%}(fB}zv~>Oq2vM-(1hkBY}K+O9)tqEyb+qh60P#Uql3UU|J9 zWrUoSq$Nu3g4A%yg9H_iNFKVP7~hdX!qO5YPg82RGv9m{Bml3W=^ zUg|-Dibo_5UE%E>tLssAETbh#N>>e6cUz}DCu8Y*{pxT6A3CF zkvu}pQ13P*VQGo79$BidNKo;J zf>AmL=y*^e!M3FIAi*e|%XB=bkYJlwdXQk0&dE9+R7kLGFFi;wO6Qgx4=N zFiPjh9SsuO4nW-4=N-)zpQ^dP~glo#whEUbN~kdWse_A@wV zMS@Y1r|n%&KJ=FRCyg#NJzaB z_A@vhBp4-irM(@h^q@jQ>c_C3!SNu$D5>-9?NFr$6%ta<+pKy!!Kl=BO>oYNN zzkE<3A^kbOe2`$2^ilnCPKAW@OZ{?Af>FB5%E?z$NJ#(MudhfjO80&_9#lxk*ubxM zNia(HusI%7NZ4$Bv%Vt1DBX+acu*l>v-M365{we>u%E&4ph80YZ1$@x=Oh><_b}{d za6G7xu(4Y6I!G{zW4Q9HsF2{et<(9`XFk*Y)RQas_WaU?6X!3vxtjO$m4{_)X=xeD z?(<(aR~KEh>Tnv@J{x|a@M>7|+IzW!$KCj~*-?@6{m?eEYkHFxW>q^ZTv6XbyXMf| zz2`r;Uhm{n&KOI@Bht7w{N}C~R^xh?hM8>=mX@fU_ncKdIJcu7B&c{q@_0R5!|%ei zY!QAjLc-D#wdAbZt2Ouivpzu*R6HVig!z*AwuOztFJDMlTB6RJdt0^5Ctp(!5>z}Q zc|0F>dCUCkPT?0kBrGjaw>>kny6ehU)Pn>Sk4PT3>hFrq2)`>LVd)e#Gt^fvs|N{r z^ROu%QG3W7S?^Eb7gZ!IEm3=Ia4W7Oc+^CxBtH_#BV2i0KYuE$pOdh(M15;;2A&5A zDjtzMbdD_kUX6sMC2HHFZb7~xLB%7IN63j?$-D0jztkgPX^Fb$_UR}eB&c{q@{r%X zN*O#ete=yxv_w6=_H>kU5>z}Qc`OUFYEr6B2)~>pVQGo7+9%bCp}y)#eRbMt=a04e zL+T|<3t_cVs;@{;@rdN{^YB}lPlb|uURaMJVQGna>Zh}-YgZkkbs`BW9+5m=2qpIa zLdpF__)dXS*v5rs!wT_Ry= zyN=u6xoPPU2|2DQ9+5o4o2KOZ=i^rmzmFneX^E1%u(a#?bL$=6_3#C2qjj^VaV+WA@!mJxEaTh~%N|VE6su z_faG)Em6{5J-^=`>Oq2vM#`_UheReMCJ-Q1OW5q3vKdv}$XT zuyl%=8ODa@K|4ZV!ma@w(s zmMCej>>hSHB&c{q^3ZlLu1Aruv_wgJmGcz|DjtzMLQd>T-d!)eZGnWPB}&?>Ts}xp z@rdLhzfY7hI5WI8f`p|dN?N#F&Ph=5h~%LyXLoLR`vnP0OO&*nR>y?5A*QxA5>z}Q zd4w9S{)QU~OH0&-+uw|Omjo4$(CffE`$o%eM9E#q z{Sp#XJR*67o=jKzK8J+eh9oR4QSvnNc#s4Yk4PRIbCR&MMA`T=^%IvL+PnK$7(w3j zzDLJVAtCu##+-@ZjBx%oTt0X4$X}W3--k?v9=xVNgk6cXC5m(NH9vg>#r*nzkQ`bLe5b7cIlb(d5~a~+(Y|TQh8QXNXUJY zUSHFL1f%lzC;RUe6%z9Nr50^^kYH5)j%L3H6%wq2%PS|rsQh)$eh(@n*p`$YB#Nl| zyQcjf9VjH&CYBx~7?r=a+V4Sy1l#t~g9M}GtAF;bq>`XQf_;>BqKx8qmzdk77iM2% z>L;Xc*UVQW*oVtsZR)>QrIPz_WuK8}MS@ZJ>r?$6R7kMzTiz=YMO6J2t$vUEMXubt zm;1v$eCa`gQTc0N{T@_Ea4b@KkYH5)4qCql6%rg%l^!G*mA~iK??HtG$A+Z`2}b3w z%=LRvA;B?j=|O@~`D=Oo9#lwhtX_JMD5C1G{`GtC`-3Dn=TLf(V3c_0?!aYeUn~avo0aQsFWA%JG{IODkS9jORul#L4r||r|oOI<#kXY zA^AA38}O`1FiOg%eLJ`Gph7~*V_r9)2ZHVF z(ET1%NJxLqFCQcrmA{MK??Huxjn$fU2?<7V3|Hn7DkL~=i|?(S6W&|f3-7I6Zzo}CiTdF^*Mw4Q zUuq&j#Ul!j_$D?ImbUB2`^eNI5^`KqJR*7MmB%;Ak+8Hx$z90%8Awp^h~&ZF6_K#C zL`h!A`!YyS@rdN1zcGows3Ku$iCXul85~6Rn9EDw{|QEOH0(eaZ|D1hXfUmNFF+;-;?!o5|);z6Aqh#eM=;$c!XYu zuAhhZ)~-py(h@c8+{xH~CGRzqyd?w`k4PT+8z}Qd1$`shWFOSoM^`~TB79n=ijlApyCn9L-SQ!k0N1diIV4^ ze~&|gibo`m@C%-~;k~up@ZQ>(6YW?=OO)i8{JSC&R6HVi@YhZxEG)S<6T!t)?O#UqkO_=Vf} z@ZQ>PcyH}Q5|);zP2M{R`HBP;k4PTjmwMgs-r8<>Z|y`9mX@g52Va5mL4t}$B#-cm z!)|zQZ8yBPb|MK&OVpADm!q7MpyCn9Bh(D_@1saqTB3H}?Q+ytB&c{q@{rY~P^#ju z;z?LqqSpHLW%ykx2`V0uJVL!LZ$gN_?k8bsiQ4+=%VLi#^%F@@@rdN1D?f2PiiD*l z>a!Csi#@XBL4t}$6drMPiG-!?I;7uKctk>uYl=rC554mE)ddokmMFOk_FL;thXfUm zNFJeoC0`PVZ@(a6X^E1jDLt}u9VDoDMDoy_7~kSS!qO5Yxzc|7-szB_;t|P1)`MlI zMR;%RL=u*kC@EdCb2(iH2`V0uJhW!$h45= zV|``EGFqafwv(OY$%6zHk4PTjjSliX$oLIu5|)-IskLQCeDWYc#Uql3wm9+q?IbKM zQPTRzp8e!Of{I5ZkMM?#ddx|}(h_Ck&(u#0@2#C1-do#~_tsJ&A?>bQc_KK&vfo}) z>MyLaC$rPgl=|zg<=B}D3HG(x2}W(dbV{hN(l=*If(i-t8QTd)eRid(E&HjdkdRSW zeh&-p6$wU-+h}UbzHlleWHjmT3n#&-*S4IB(KgSD3JDt(r+n2$FiO1r-+56XVWZ-v z2MI>WJ@kL)MTLZoikluJ7?pC5_d72tB;@($@j34m2}VgN@PGe7g@oi||Mwpx7$s%X z{~Zez5>g(e25;Ug5{!E7rO7S7$Du+(#v=ajaY!&~>GvnM{H}-!2^ov{zbhiasI@kj z-17SKE*uYW~_ zggk#+vncNs2}Vht4)3jX>O?9eBp=I+UbEgM!6+%4;k~sEL4|~rN14%UdXQk0)G^_` zwGKgrgw!iCJJ|Ff!6>OK!+UETf(i+#A7w_b=|O@~Qs;;F);a_g5>n60>|oP_1fx>h zWp5EI%3y3ElhRN4@BQGhByCaB2K(1Rg@m-b{&kRGl=LP1=Rt)8=Sa))L4r}zCu+%8 zP)KmDxAfq#7{xJMNl+odaa+9#FgLun*47OMWTdF800T0X)e%xm$M@FG3Gc1#%6n_& z8H7I0faD(?e@0sSLGkbLy|r`0duzMly|uRf(MqIIs;-!H!+UEB!j3CZ+MiPo5>z}Q zdGyb>hdyUKmeCTW{ZjQHLB%8VI?|d~TxlR-X^GPQwOt1YDjtzMbS17E-dk(yYVlY` zOO%ci)Pn>Sk4PS2{;C(&K;p^|2}?_qj(6091Qm}+9=b9bzc@w0(h{ZPHuWGu#UqkO zm`{|qI>t8@lCZQy>G)GUNKo;JMh=#|&&=SIj`Nm`=hE`)wbd9NZt#UqkOm~XGYEJwo95+zSF^h?x3=g7L@y|rVk z#*sS8(n46Rl;+_`Q1OV=4svyggry})M@U*HlAz)d$wOx#yOpj-g&DedETbh#M@Z^H zf{I5Z53Vkeu(U+!2uVFiQ1OW5!PO-amX;_TA*lxmDjtzMbY{C7-dk())bUtGOO%d~ z)Pn>Sk4PRmLm$5mOv2IR6HVi=#G?LcyDd&>DxUqTB4+Xou3B@ zDjtzMwBH_gg^{qdL`nZT=PMFaJR*7Y?^Uy787)!Lzs}`@1Qm}+9=g-1cU9P>N5aw) zCH-qFoAJH1vYRRrR6HVigqlHm`f;}*2}?_q^~h3vMS_Y)BoE!I7RQ_9cyH}od2cNh66`aUBVnE2jrFn<{@>N=+i^pP=uIV`*R7gmfx13)- z4-$;hwMoZ=3JEFmVV!dnf>FB0>JU^&NSP1owWAP>(zRlTph80G66rZN%LfTY>6*7g zP$6NX`=$p8M(Jw5<3WXljqaNsBp4;${&)MRkg(Bx(}M(~h`7w2}Y&d zGsC%8R7kKbDa!{5MoB5~zuQNJ1lz>Yg9M{=7T38BDkRvpmmVY-rE|-U2Ne?Rqm&*b z7^QRMjt3PI>}!=CBp9W0{f-9}66`aU9wZo*+Af=oV#`UTpO9X7Gw+g+v_9V8f~YeWb0|GXFiO|F9S#~ee?SzBp8+Q!dcE)Q6VAE-|t_M zV3g!(|2ytfNJu{R`-vnN#W7s@1gVhVNG}o-hhKYcjZWvJ-Z@hqsaAXV;_&95DT80$ z{jqAf&F+fn?N)xE+IryXm@Ww_Bs!gktBaQYd=!FFSG?oCYRPf8I7F%B;~sa&&#GMp zo*0E-)DcS-R)>G_PKTgE;-nues(w50n^6cxz5i3g)uBt$eJk%36%wZ(dslVP@G{4P z1f$lz<&J9i=?fi#3W;+*d}sBI8($uUD5K=}=ZhR7{hB-}P2$y2h(xET-+t_-mg^`L zIg>;jIs3+z>mb3XUtBk><#|vcaop+Gv^)=~5hoC=A@HvVPxz-OmB9wZo5_8-CsvhJ7cw(%|1iPzmTm`YA; z4PtuE3IGgE0#nf(i+3cSj)@wdGp#t5u)tIRq6F+J6{@ zVAR#eEUv!4^X(2ng@pElMj;rr)rCK+w%z0ghoC}2dw`=5jGB7jL)EoQu5gG_iT%VF zrTJEpd{1?^62VCF~R7hw(9))1k(Bdbmr{6f)A*hhh(lrXfs8#lOy87RRUvda4 zB&3%3-Wop~g<#a&ot~-goHouOsF2XwZWMx1?0uBA4;2zxYdan!7{xwH>2casr`3I& zGoL=T?)z-?)$i4PqLQFO;+cOtLE0$itVl4by623RyGw<{<8M7#+9=0^1f%{m>#UYs zLWRUh-#V=&mylr8S9dtKCAU){@v%eCkT%M>4ib#|(+4KDlv*kzHhuhu(ndKRBp7wT zB||N>4;2zWx#N5pM>`%Q81>+xm$uZRR7i9>Lo(WSJV-F=GiOX{X$?vxA6Lf-jt2=w zJ@nhDEv*_A5;}TuJV-EVpJT6YX`QK%&{3G3EPRqjDdmtV=jP z(`+Mn)4kG5{$ZSqw`yOuT)5A33fb4 zFly={XSejisgRJG$nS-dVAP#ko!K&)ph7}xROdQKFly$h-)|WeQ6Zr%gX2MhQOAAr z^p?>b6%yLQIUXb!^@qQo+A>O|LgM3>9V4>_&X|(~qh8Ooa6Cvb zYNr)XZJ9NoLZZ_-y87F=H9ydt10cbuy-q&0W%i>~@^RH~py@$^QS9NA<(vu$y>E^O z2}ZFW6g|di#(B|(LR`Hf64%I-*$phCj#!pH=p?8!C> zDkSXrk4!Mia%ht%m6S^)O8w@IOfbqyT9cqcLhqa7L4r|MV>CUekg!@}WP(vv^EC-7 zB&@a@nP8OF;7x)G39Ge7CKzQcQInuT!djn^2}W6q+9aruuvTG8pXc9Jyla$m$ zlC<@rnnbB&!unbx6O6LnV3VLi!g_!s6O6K6ZIhrv!g{hJ6O6Lnd6S?*!g}N*6O6J^ zMw6gI!p0&a6O6LaQj;i^G-8n`8zGHMFv>=KO@ayu8|jTqFv>=+O@ayuEh~c~6O6J^ zc$1()LQ1gA`;1I5%4QRq1Qilm6FD9v7{#7J*#n?LLTgmVg9M}4e<(d{1xv2bW``tg zGf2%Vr$WN!nMNiUWpiguf(i+n{Ti8Il+6J)2`VIP7H?#NQ8t&^B&d+E*~pOzM%kQf zlb}MvW>rTf7-e(IO@ayun;jmRV3f^~Hwh{vY+ih1f>Act-y}*U&7Mn?&DM`hFv`{} zngkURw(2l4!6;jMX%bXO*y_p11f$B{N0|4iM=VrG*eX!dgG3pX`zU4YV>@f)So+L| zC2gx`O%Ez0G*?Et^dP|~TQ_WaP$8kE%kdz=C|mz*dQc%DwS>&cj7%`f)^VEz6%tz8 zIUXb!W$V#R4=NSiQKQh56+sV}=sF2W6 zm{T*5V3h4hYkE*2p`%I1g9M{&XI;~S3JDz*J02v;C}{^5IfU&t6!#|a>L`TmHWb?S zMmDdbRAP%9kE<=U<3WN^wqvvDL4}0&9~=)7jIzC|O%Ez0v>)VnkYJSUxovt-A));_ z$Abi;*uyDnA1WlYC+m2SU=;g7oz5EJz0v>s`Bk@gB>eLClOJ1Jb-s7r;1_;*+MuR~ zC4J3HzokOi+%HUHk9$H69+UQN6IV=z-edn<5K2!g5)-J2hA8%uW z`@S<_aG$LnsvbRL((oGZI(l%+k33X;Y=cR||Geop198c&U+lj0xwq{6_4oX}AQ<)1 z!4FmMn}5Y%=MxhG@%YLIcJKJZJ7zq3-iza@ka#u_-T7C9dnLqApW46svFBIcZqG~K z+9koL_ni4qb^K?q7@Yb2!vnGG;r+W$f8wO=x4HJMT`D9F48-gMt{9$knh?|8zIXT0 zzn^&P>CdiL5RAIvmWQfse|`C2x>xruzjyb8d#``pUtV9Y>qHGpR7uDeFrNMVs@KW? zR5Trl{l`39{c6!=!}4t6FTGuYQJRiVw$r&gyw7Q^wV%0mwHf<#sgUTL^lG5nR_(MB*z(}Rh) z|CCe5AGXTJu6;SYiJuCIE024mddGo39$s|aLBXSqV3ei@6S3P(W5>_<{comC*z5Q% z6%vPqUlp7XepT@A$BM^pdrsf=@x?38+IgiD3!;pAw7U1Yiv}lrLWmVUa>TAT?zq#m zvFD!Hb)tq-6p58ioIdB$ub;8mrQvOCoeq_lj>H#Edo+Aa@JD*(Z3LqLVfVW_Q+)zYaU-R^IP|!6&zp zGWe+T8Sk@BQ?wD|WtT?pwnb=9gBh9C+@a)MQ5RI2IR(r(bE)K_i>r3YhAGXOi2TS6}V-M^7$J=+<;&1;ve>@e3h%H>FbNYLa z?w#=3E?b5^DV|$xTo4oUbZ+u}q6%zZtzO-7h z+&P11ZS)_3n7HoIy`LX{&8&y_sy*UyFAm53*ImvT{`Qz-220{|&mG%4_Mm|+=4}7P z@l+gQIC;Es-|@ZbE4yuR`0rON2&H4xDt}vA-Tw61gC}lxTsW&m^G@vDu+x;CH+*W_ zU8#@=-_ff!c=+s)r@s@3`y`}r_UbVY6m$kiS33@>>cvl z?pwUP`?kAMaft9_#lwgn@4oFE5}J-tN)OKX>Is2Z63%M++pgaE509=mw^ZVpM8fXj z=DVI02)XkA-D%3K`=6{mVwB#6;RC;RLj61v@lv?E1L5vo|N9l^@>mWroCrL@g0Q5>>P5*Tq-0iPk*&KIS`r?XN8<-9?^Yv%CEx*?f%`md?W(7eJ+pX z5W|T$Ih3f=LW#QOpXV2Z<#vhE(lxlthfWD+wSOqJ*N?w?=liFw`f7@x{th5&0In<&(DkQ89 zmL7ShqpiWL&>9r|b`nRXmSOnJ)r3H6P!No=IzM@!2hh_#Lpb*z3|ia1+Mmy`^suBm z9kk~?YxNN|C~0f8zjgRX1f#5NPs9PC2e5JI0sJhy50VNAZG#6lJ?s17tlEeoN?Ywj z{4li6hlbYqqkHb#v-UhH+9FHZTI%I*mr>DQ9v{=2{k|1;{>n}J6a=HJFOkMk@4fQf zy$MVHxcT_^exygmAqE>GuY#}^S)$5ZGVsa~yZ(9Ky=Q&l+upwP#}|DLFdc z89YCf2_0VzueGY=-TT9+Xrrf3+WwEPuh*kO!p1%+@7@qbUZ45&`q!QGY)LT6Mo5Xk zII2g5gpGaD^JpU&Wh10S{4R{6J{`tUzYlNDqC&#PJ}D=*5k-`akP;Dc`}j~ku9fm( zqpg&8lPl^z3hq8 zcRuBo-xjk5&+YM0_1E`I8hrb%-z?@FI-L((cUbp~?RU8D2k*aoJZB>uLi>ro+UV%+ znt$5my4{w)xFD2{QQN=kq3U~AOd4K)9qGgUI1mrsI)2-~z2)NZR7mU?h?B3FH2D15 zLTvHUvE6^&`n+3So&AM^VAQp%K2-gG%FYAKit_sZS49vMMOhNNYq*OY6>LPg!wg~< zMPsmG7aO+NjRN+bD6A`BAyG>rK#aAedhXLufl}APR+G1pn}8?M11tlW8s?KT%CQebVP9X zNB7VDVpi|INTjn~iiUjpm{eqwi1_b&2TnU^qrIqxQ^iAswuS?OYB(h%Hd#WqbiROV zIQ~>met7?0^r@QDilGf5pEmsJJSO~&`{Z&@Zhv_&^XvVmebjASdBB#VqvvT9H;}60K|M#CaVDR+#8U6l zXgi>}*J(8ON;7w(&D^V<-!rky+|`@8S37g}LhkTj>Y-atyXX6@9AUDMzVNQm(O+of zeVCbnoIrQ`HXA&?@V{O7i5kr#Ec2}WuuG8}%GlKm`eR z-R$`M3-XBPH!d9TZQ@~$D_6SZAQ~^Hi5KbnSV-STu^YG4_B-HXc?dH?rcZU%u;94P z`%K%W$BGo;zBQ)%9WpxFiRKyJF!KyMt#f8jf7YZvf1L4Y0Tm?P8#+3ftD$*@ONIpx z9x`F!nTM??pn}9{GhNPOzg0AfC>_K(0%p&=l6yi(Tom_CY~D{6zh6S+jefp z6oFZIeyPfmW*{4QHq*>HPPq1do^>>Hh!V>TB#kBtG@m$?=Mzyu;t&6+=lMjL9n2yy zOJbRU#5rVCkjRa!=lMj>JT(%jEKA4?B+c~&G}kxP&h?pNSp|-}4gIB_&JMo#+GfF# zJGbj|!^}Z6JE#O^4c-h}1{zHSG@6)7qY0X!SH(lfoIbWbNJwn5@cYl@Xf)9*qluuN z{tn8`U=O*afoIHR7FfSo^PRh~LFzmA5Hhn3}cZ|ux??0D&W7@EI<9+towSSN0 zG^;j-SCmW@w(Y_(QAg@CPN%9*{#~B)u}_{EZ@ui+KJU%=$Pq?C!tJ2tb*fx$`iNoi zGgn==@ckUm^%)OCVAhB8$3(Z&3f71n`Kf)R?%Fp>-oez)44q0#Bf8XCKKn00oju-S-#kn!SiACg3Kb+KfA#>cV9C8pnX!++EQwoe&zYXnH^(vx61kBN@Cuf9 z6+nqpmL=pl$CU=jlIL8HJFWc#yn^Lf%|HUPB$oDy#!+Qj!P;qgc;*(v)$$K z*j&GP&-55qKn00uMC?K1sQYTTX4v=BYvLykAGmj~XNIH*%sTFyF+3_VqZe8e{_vXk z?4kX3UA4g}1y7c#AJW8T&s`sXFtq=!qi6E0vmQ%gLv;OlOw{4s$67}1%VV5HG$Z`M z$sP7S{na#qS)Gaao<>D~+nb5oXr6lgV>X<3;p$#}Q9&Y?8w;bNO^G;?X0|`PqIZf& zXBonbUTBS8i2JYLS!Y!AxZ+K(=Hf99f2xVcY`FK9t9zvg%#u$S9(@iI3+T)T4Cyd$ z{HyDiQ9;68H#^4ZLRa@ay1FmSOcR*puDT`Q8>Crh`+cy2gnYB%jstj9#COTrhYy@b zcS#u)B;#f~(yZF(G| zAR)a(_=}mjJMYcG@u@ejKkvwgI>x9VA$>{9zJ?e`{YN;y!`@qcu~mw|EY~yGnY+JG zA9c;KTkrbA`&-4HEVG9tO+f!abK$o4;$ulHyIyRYpUm~S9w$Y(UWT(=Uy{uA#WdHq z3(xhTf`n`Hles=Gk;;-jDw*p`=E5b*&Us6}#96MFNap&y1ZKIuB$?}TJr2#c+un;6 zBwR0H=aZqwNfDUk`Vvb(k3;JQwwh!G3D@KB{I%IL(JXr=Qban-)S`5UGLfDawKX+g zA6Mz~Ik|e?o;i#rXqMBAGg=@k z(pk0&w*>7LX{OyGJJW6vnxRKUuTT2A(SC+tX_tb`j!Rem?Q9L#>iGOi7up|t`xO5rD1V)F!>y=rcTh353_ ztO{g>9OL`4ZEUNo?l#WR9cdM$<>h?8icy{V1b? zMA}1UKl;$@2hGEo^JrmrBxGJA9Ajn&VfG_MU>07HT<#m1DGC-g_Idl8A-;Jyb53rS z%2pXN8?}&TqiF8c&R?;DS3zc}THdD_y<84vyix>axw$Os(Vu43K3y`Y&-nG*r{>6b zR;^6?B)&2;<~l!@%T1-3yI*K7Jm}DR=B|Q}s?QOhw%?0tI6Rh#O_unzd`0^Xa=DN` z)vL{u7QV4Q&up7dB8n2}^N{((J~W@$oK}>OnZocF;{o%D?pm3h1DJ(ZJ(nBz8%P4p^MFL$&75`_xqTCPZK#%e1!cangtU#3!*iH;xW4& zRgZ*=IcwQz)1pVWSs)%rq!jT(BJqgX_)2~BS#1rI}{73+tD^^j{7(0x_I zXMWuoZ!hIzx!7dct6=^;xmJddE1F4I5BUZIy06^#VUH!pM`+>gIc1mk6X`P!yFP1Z8bYO`p6%Q^571$ zqqpw<*~CvSm>s=X&e1!B_{@>$bMQh|LRQXtcOldLI6nK8g-n|`P4vEOPSo|d{}`q8 z?6hdink!9w(xFY!!!@HlgdA%rc$iqcJ)a8C9MATH^Op1b+YO!mRCut;u<3|q$> zH~Y*{LE^q{v!i|;+Ic<|5}5VcZ)ZpQJh8rqKm~~oKg^0wyQzH@0<%`Eo)s;9ZUYaI zzV0)lw-0*Ud8%M7+ziQR`PW+(PlxWPx*4_OE4`+?PVM???x7i*KRFJrK&6H@!+L<0g?h>QO zvtnZTX2aH>O0MowR^)CsG5gW4E|@rdt?LE_?%7xJCx`BX?? zR*w%C@}1}*P(k899TxGOScSl>19~muJJCbnH+b#GlcQZ;D4DB^-%a|=Q9)wxl*!SM zLl+r3o4_phi%PA(K~#_kE~npjKBesOKmxPy7XZ_r3fuPQ`%R1n_F5!8z?5j+mYnoB z*zU?NS(*Dso+uM%-&d$0k;|DU*wE=ug#>2dJ)I_Q-KB+}9CNJGhqv%^XW~PTSjN9h z>+wJZi7i&Q@YC!e&;#jbUtSvB+ho1dp9&QuF57Pz{Z-@NJRV43*4;NQjfNjS%R}t{ z@Z;QG8Rf{`D#T6~49!%$nA7 zN;LlDTcmo$`wA5#uZGy5{pJZ5xslVHXaWoFzcQVpNK9z&PT{yZH^^(yNTtl^mw3xgggZv zLhfCo$o*>KnOiQ(=$+|r1Cv(fRJxb`H267lXGlxrxl53cyJRU}QMnhS?eg4LMnOXE zV?(E(T09nJ$y4AVP(ebTv?>Hg_~m?wr9*$xQQD}&0K|hJkrV%t`kib9w~huX+;US6FnYCVAfsb z`CKP@hzDL<6ut7$JN@|XySIK(R2uibiL>u^RFD`tcu}xV3zb(o==4e67&}}N!6eBKmxP))ADbIwQfbziXK<)o+<=p z?Qz>O^P6Fk};=;Km`dIu~s24 zOUAn%0u?0w@Ip&Q1%L!*$qa(W0~I84xn)sPhc9Fv4qG4Wmp0vVY4qv}J3dR_l}Mn1 z#MpP^Xh4^Fo==4YX1V#x*55hSoVRvc#^aBroF&huiPO&qDo9K|ZW)h1st}mPcj%N4 z7kda)kZ8GU8IM1z5STTnv@BZn%`y*xV-BeRqz~81AbsXo0U)t)kBL$E`8%Ep013>( zY9Q@_3KGNGO^mt>{odn&1ZHJd;iw>S_REh)9UpAxxmHME7LEYY=YdtRj1BtneIGMDZ2^rm2AuvnM$wQ!mgv?TSh&|#J zJnj$pJRYUlT33Zt^CKfeI2hpPWr#mRvWFhl~`>-5?`K z6U)fbbC;lkgp63L5SS&`&_ketgp9mB1kU5){O+OK%!`&y_@ZCyZx9tE{_^phXh65- zDnvS~L^YhR3g@>=Ii-@w<(7Ipkg)HjvRU*0UCKC*w8HPEvc#XdEyy?zBrr?HIG#_1 z3KCf1r0+x|FiXZ)9uHKI$R6V$fmt}Woc>g(An}`D7DoRLe5(LRU>2@4r9D#Bovb4B z-G}FtCQ=FzsrBg8nimq7g=5jQhnzd8Ap3O@H{XJ=N!`KfeI3Gbv+(PV3u1;Z{7OfIv}>xGKTYbpn`;q+o}+lC1X(! zfeI3Me(7t41ZK%7+~a`?5;8)nLSPooi>E&oDoDt<&EtUtW@XQ};~abEE>x>;y16+n zR_EzYg$fcM#*I9O?D`*-ged*^t`@?? z;%(yenWKV)e8MUOX5mOC?STpsa-}^UNMII@kkTGFUXqcQIW8V4O`w8=jP!!mEdvti ztp8=?g@lY)Jsvpn!YrJ7PoD>_FXOs%dL-Ybfl`+eSV;Nby zUCLJ!$3E%vKm`d|i8pjMfmyiznI=#{LPoD14zZytBVQ}UpzZCnHSF{Fe`hGOm=^T{M5>>FcZuEG83mgP(ea=p;aL;3;V9L2P#O& zZaR+#5}1YiveF*s)y?Ad!KHlWms~K5*9T3U-T{McA}UCXn>35p2MwL}KmxO*=kyRb zlOnqzOcu_(q&-kULT0=?9!Ox8%+GlURFIGvwkiZ>;Rq>x9;hH8^M0N=G9)l7dsZzq z?vtI%{Qcv2C;h2X3J|G1(5X29BrprdJ82KBqvS5>$Da!8t~7xP5^`4>I-9^OY`f9~ zDoDt4J zGCOFpWG>S~q!lweXtHEBvI>D&GQ;X2P(cD)rS#QB0<+|P^LU_wM0N{@1ZGJK-qQLm zK?MmJi+Da25}1X%*wbg8x<}z}bMT%{6Db9V)L-4CS_ULA3;Xu82aYqO4>xCvt?^KM;3uuF18*uC;g@T(Fa!q1AhNPS5#cg$91!6)+39+EEijkRjWU3zUYwQ z!L~aGT~To{AJ^@mwH{dnX1UmU9P{uIeRpdb5j=i%-6&LC%*S;*fvratfmtrL9`6i1 zsc_OJ*9PaEar0YkwsvZi>=4&x9<@A?!GV>d&Oz>sJNJq>vpGD zk1PVSTx>m_*mFSe&!Bs7@Vd9uqvB#duG`OIJ+cVQa-Nc5k1PVSTx>nA_ae!pEKBlODLQ1{D{x2aZK@xhw*+Tx>mR>iWjt z-neT#Z{F}4R9ws+IHscaY-bRdNez9joR%P-75E&l$$+t;AtV)nq%E8SNa1ZKI|dfc&iV)^3#yEK0F?pL~^;$rr|eFwQ* z7J*qVwjMLK+ogQ|(Cgy%rw{Ckii_C;_fO<-&W49!pft;zkpvsqDav$dQh&wS7}fmtr*Pnfg}eILAVhHFcVhs)yQ z$}=w>(w4L$Fw4c(Lt2Ky%JZhWw#0b2EcTFRUOci0%yO~ykd~ov(X7W@TVgz17JJAu zFCJM0X1UmUNXrm>b;JFxEioQ0i#_C-@5gb{mb4-;%f;41T87}`eQ$PcNk3Lx79Urh zdGW|1Fw4c(Lt2L5&atPsw#0b2EcTFRUOci0%yO~ykd`4BKC!23ON@uhVh?%d#UqQr zEEii3X&Hh)zx1_hON@uhVh?%d#UqQrEEii3X&HizC*I`R664{r*h8Lq@yH@D%f;41 zT87}9*MHs=6&JIIv<%{rMPQbTt%r(Sj3!PGAe3CV3v#d6Vk6> z*fCCg-aVVTF^=(YS^P<4EFvCR1ZKI|ddP?+-h0G6H^wm@E{i>6EFvCR1ZKI|ddP?+ z9`yYBZj56*To!xCSVTOs2+VS^^^g%ueE6nMxG|3La9QjjV-fMlA~4Iv)FdTg<~&@M zxmI@1zIbF2GGZ}VF18*rVu_2VUf{+!_FBPlWh^2dSp;Ue*m}r_B_96J9d3+cJX{u^ zhm1wUBa6T+7h4Y*vBX;~8|%h6#=~W?2d?Aha#;jsx!8K#w(~#B9ga9RUh&(`=KUqt z%X@L$emKr@`{CLqFw4dK3F((MuILg!e*CfV;=}sYpyFaauKNov>ybrZmW!>&wx{kH zA2(*d_|SbWszJrYd|dZ8U)Cdwz$_PAj{)Z&883fg^SJhzJ8MvJF(23MhqNA91ZKI| zdc6O_nepP=J}NJoKCT887xQu54od5hMPQbTt;eb#E{j)g{$TmWqaUw9#l?JFw=>gv zWD%IR9=c*gV^R9wu*b#F+p9$5rtx!8K__SuLy{NsuPu9!We1{D|c zaou|qtVb4sSuVC7vxfdTKDJL-DD6JI1{D|caou|qtVb4sSuVC7rT<(U|9r&k!p5IA z)}Z2IKCXN7g7wHEFw4c(p^Wvf!mVT z_t-Ld#}*$8XX|mLiQW*KL131P?WdxaA>g*;yuFX8N5#ebNpStkv_4(}vs`RFsAUMa zEqUpYtLss5F?--TUM`nKV3v!m2ek|Vw(K>3<0+#y+%%|N5#eLf&12Sxhw*+Tx>n4WeB(}`Qn_W zdQ@D@9_gI}Sp;Ue*m_XQ5O7-PItk1PVSTx>mP#L}16abjA>8I6jI z`MB=y@vKJ{fmtrL9yDTUrgfZ{)^RpN#l?JF_jiTXBa6T+7h4Y+v6N{YC#H3ruBf<} zkL%v`WIeJ7%yO~ypb<-%)^TE5$LWfSi}|?j{YBOzi@+=wTMrts#I%kR(>hKKDlX>Z zy0;uzk1PVSTx>mP#1hjwPE6}KHK@3lkL%uYWIeJ7%yO~ypb<+<>o_s3g5ib)0%sT+E*&y)QhAz$_PA51L60XdS0O>p1nOxR^a~ zA9^mAMPQbTtq0Ad2DFY-pmm&jR9ws+xI5mg<9G?oa(LEqz1H(6VN(NJt{6{kMv(b zWD%ITM)C3 z<0UZ5#nyvnQVX<>6VN)&XjELx9{4vcW*x^%V3v!m2hF7JPwO}Vt>bKpii_C;|LVr9 z<9G?oar%yKaw$*kjWThdJHIIb-*9xjWIE6==m zNL$j1z$_PA4`~_7w2tH2664{r*h8Lq@yH@D%f;41+LAJ@zvIxv_ zvGtI)B&Ky7*OnL$m&G3P%rE6QX-irWnB`*YA#F)a>o~40S;~sb;^WFQFCJM0X1UmU zNXrn@I*w~gjEBo&4|(RrBa6T+7h4Z$OJZ8baczn5a9Qjj&%AhK5t!v->mhAPOzSwV zEioQ0i#_C-7mq9gvs`RFq%DbQ9mlmL#=~W?hdlG*kwsvZi>-&WB{8kz+=q&b*+W_e z@yH@D%f;41#yA13X1SO@VKT-EXdTCmag2w{;!h%D z5%G{QPAdYlTx>mL#1hatjvM0`50}LrG8Pe!ECRD!Y&~Se63{x18{-%cm&G1377>pu z0<&CfJ!HfZ&^nGA;}{Q@#U3&i5sxeavs`RFWW*BCI*uFT7!Q}l9x@gYk1PVSTx>mL z#1hatP7Nw9W)B&Qh({KISuVC7GGYm69mkDv%z3yhbFJ*VU&SMfkP(Z?aleyPc1ZKIIKVdSH8qhk9 zn|n3a#AUIE%#n(R%+|IdFw4c(V_Q4-8qhk9n|n1LE{i>6j#NCd2+VS^^^lp=fYx!` z+^g|$S?nQmq~ei9V3v!mhs>lFXdTDRy&4af#U3(8Djrz`X1UmU$V_U1)^Xh2tMPDI z>>+cc;*mvQmW!>2%%m1*9mmbR8V{Gn9x_KN9$5rtx!8KhOzIL^$8mG7#=~W?hs=@E zFS~HBmPKHei>-&uq?TzN$IZQ(zg=)yd|a6$6^|?evs`RFWG1yt>o{)i)p)op_K-PJ z@yH@D%f;41W>U+vj^pNDjfcx(51C07k1PVSTx>mLO*o)+oa8qx__+A@Sh99&z9-X` z@G5dE0<&DqM@rU&16s#%Yr^LKaasIHWbIZwWKFmgfmtrL9^2YA;egh0+?ufQa9Qjj zYq#Q&MPQbTtp~LXye1sbI*wZtHXbgEJ!I`xJhBMPa&Kjh@6E+?$i#=rRRy?u@%yO~ypq7Exgv+#!HVeL{Uv}Jd82x^feVf00Uj1zj_bVUP1BtZKny?=Hd&vAtmG|9x zeLWH`<}CM@Z`K0|RD6VZ%o!BWCyQ_X?!I~?T+CVSFa5;>2vmH8^`P$}petNHbJ5@G zk#I3*xi=PA4LE+xY%adzxuY<3JLcYWj9`oXSF;bXa&v)o_dTMr~q@e$U8+gyICs2{9B!o@br{zicHKtkRzV$O2!hOiz;pyDIMgZgrQs;D2V zLBhqH<=zh{9zdYtBdiB~7coCo)DPAm;bP8mZ{DyTNTA{)tOwmwF+Ww*57r>zV$O1J zxw0NepyDH}2iJ)FR8c=zgM^E1mVINE^+3YC|B4kKk@9G!evs}fJeIzROXwiwVTiQS zny?;n=4I*!-FcW}IhwQND)dWTD?^~-BdmvfgJtRm-S=UR@Ne$YK1=2(vAEP1+|2N0)&J-80#r;7T)&5&@h&9b8~d##XgBRW=mgm~0#pC5Hhhq_#DWH5B?zUAdnQ&PFl)kk)1s};y1mf)JWxSm>Mm2FW6rJhcp!mU zJ#y2cKbNW8!0l<2CNH&r1pYxfRx9*@T5)*h%Jaa8Xq(PdkOaoYrDHSRSn z>Ro$-hd>31QI}7Nb{sXo3V~UN+%+vazR&X>0u>}yzcD4cqjUSEt?52vm^x z^AFRalU}^43V~T8Pnr>3+WTS;feI1>KA#>P^~zmU2+Z2~l$p_ly>Ipqs31YR=Awb` zjIBao){R%sik@x!i-$-ndfe}Jni<{wYGV}wv)*l-9i3Qi@DOiIDo5{cP}`61(T(4X z`Fl3;+O^Hm);mTfPPd|{AaP5Fn7_d)1ZF+FRdcl4Z%_9Ss35U;(=va9RS3*Fr^k}0 z<`36-2vm^B<(l~$tU_Sc;NLEeb}ae&^R%MJ?ey|u{suiBNMP36YZpdCe;wr^P(k9Y z2Np%+@0(GDz^oUV7eq_m^qn~>NIZKe{oce!C65OZn6>})^P_|JeZ)hcg2YK*&W}F) z`{F7DW}UeY{l>_5<2?i_NbGrUDSBy}auouz9{+r9^insU2P#O^^qd!sdaK#vfdpn@ zb)J3(Q9)w$vvZ;!HuYUABrpqW__RmonsPMep#zq3%g}e-rCjNmxWkHabniM_nmA3M zg2azAmU0bOg}|&Gj*6qf<&QjlEhnDyGPG1qW?TUQyVAhG3pEnLG@Au#Lk58`Om*?R`9 zJy1bn)-x?!!&M}0H<`b{(FpvKn00^-@cIN zfT|FfHN0+7^wF66JOnC89Jgi>&lFW5Fl+iji=)n;+~y%rL88khOL(TJ3V~TogO)_4 z^{)01s37seUd=pHRE5B-?V{%Bscld85U3zAJ}mQ0Q56ESu-8tv45%RS3jJm^%@lb& zkiabL+tVKHhR%y>UVXzH>*k$G(YZf;Vd7cum!dlw?7yc8RFIgsXnr(o=;xkKg#>0z zJ!?Vq>7v&>1S&{;b~<3z2u!L1ZGX6yZy#9 zR(l9kkeC}RiB|RWojDSi)%md{(X!6VJszka@y`j((dlhy^o0u>~7-f?L(`@xx22+W$a8~v*CH@>kmDo7j_wnV2) ze8l5{1ZLgZy(LwP=~DoD&;u{=8X&xI-kX8qi2d2~t8(LjbnK8S1ZJIa%kpT?qyFw8 zP(k8=2`i%gm%LDgz^p5`Tpq1=!e;$ip9d;PwA*(@v|qSI6#}#Ny?t5K^QD4^Kn01< z9$Ow=^WDK!2+TV1`IhLBF6Vg&RFG)+a9Q;BwU<{RFstLYOQQjY-tHk#L1M#B^o!{` z{~#{5X!r)y%CzVAhwD zo1+uAU+5uFLE`io<>;2_%c~HW)$^1k(eNWzdI(gI`0}LYXx#QMR3R|ys9zUFm+$nP zhd>31*S=mHZFBhRRS3+wz@}zEuG%0LSWYGn=go-xZz(O0u>|{ zeY+s~@!(IY5SaDT*b>*l9s(64YR;V>9s1ShRS3*FYKwVXQ+o)^y6)w9T!ovgYyuS| zP8cwkt8kA85}0+|gLAkF_YkNcvB|>OT!mL5Fzc@TY_7sR1S&{;xA!cr!mALN^@oKs zxeE6Xs338~(ivQZS0OO#>mf6^3ilAGAhFZQO5~cDKuEMJjn04*zQ@9HE5U3!r zCg}|)!R!`z8 z+(V#(#2;o%Jv$y|kd2vm^hI%E=8;Z+FC zdVKdOT!niGRFF9Tx0AUFuR>tf_noG4749KWLE_tQCvz2Eg}|&`Y4;9Q;T{4NBnEsp zg{$x?1ZEwz{dBIvJp?L9+}Uj!SK(C%%;Z+FCdhyX2T!niG zRFLRWY~m`s3V~U(aq=>v1Q3io&*fmt|bZ9Iy!x3-b?*2cO%*bwT7 zz9H1rO#aJB+FP3ts34(p4s8*brK_@)1S&}A+(}ymX6fp3C4mYOItSDifmymrUP+*W zgwAEPMPQch1E?f)C9WaVbp!hAvt)g+l0XFsy-V66FiTf6D+yGP(7UoN0<&~gwvs>v z34K=DA}~wWiYp1-<=qhK7>9lbE7^NqNuYv+j>6g^FiUsCR1&Blp`*#R2+Y!5J(UD1 zNa(1zEdsN2KT{>4`>7j3t@P{nC=vbsJ0<&~adL@Ah5;~@8i@+@1TVF|_ zf`pC@+afSa|3;vaKm`dM=Bv3&@*9zMrFiZC!R1&Blp=+LP5tyZWDJlt6kkGZ;wg}9^o+$kd zqJo63L05VpfmzsJr9E_~Y(uE?)D5BT(yjDB1qq!=Z;QYz-ECY+pn`<12((3DmhQ5u zBv3&@S2o%rFbk`}^wmWL30|A7h;I=5W;sgS@d-Pc=5 zpn`B!mhLvLBv3&@=l9zpFiZDYR}!coq3aZF5tyaBzbgq;kkIv(wg}9^r#XF> zpn`<18&!HBfm!&>r#-MX)X`l-m|Z8Lf`pDgD?b$yn5BPDQAwbJgpQ-zA}~w;E~Jt` z1qq!GXp6us{ri?m0u>~5UZX7nv-IzDDhX7O(D|9R2+Y#IH>xCXe5N}f8p7Nn71O5UFr1JnPg8%L#TUA+9EJZcgj~1s34(xX4)b!OLy;85~v`ddw<#@ zFbnI)^mC3161s<}(gO+1!YVWEf%lTmKsJQg_Z2Eg=p1R~r$Pd=^zZR12~?2Kx!$%2 z%+kLStRzrDLg%d8A}~w;KC+TP1qq#dZ;QYz{X5S}0u>~54WTUpv-Iy(D+yGP(6x}Z z2+Y#IqOBxQK|a>Bg%h#;x)?Kr( zk19bQ#U5FN_BcqeM=<#8VCaZ<%1<1&w7X_u-&YE?FJX@?0<$z`kEi!MKG<=Kj`7^5 zw#cKRaVgZkggvqd%+i=WzLksMIEzyXb?$^cvIxx5m_6=o?i_UN zd0ael`P@7z8ka(yJ7JG30<$z`kK0cEtnlSaXT*nJ_Ea7fjZ2}4LJSrNOV4Z?JvIw2)L4rM29(qIHL#`hYpM7JyI?clMk5Z_s4(yRd zV3x-0!L2m4)^V4&H>g8J<5H-r4(yRdV3x-0!Rn0E`>T`WsfWZvovN8Zr7=`jwimoQ5`B8mqHz}vPTwySsJqkx9ike z$D_92unrZCOQDWf*&~aQK?R6zYhTJ+cVQ(wIHCU8mMMe&@IA z)uEzsDbx`wdt?!qr7?S$cK!Q(;;F0tlSf74QmEq+_Q)bIOJnxncAZ-5_`AnH&ZDAn zDb&#mdt?!qr7?SOyH2fjT(kC-JSrNOLLI%ZM;3uu8nXwt>(pA8*>ga_% zvIxx5m_4{%r`Eb0jBm=LqH!tI(F=QI5tyYhdvLo>t#$dws~YmCXj}?)^uiul1ZHW> z9^9@|Yh5lJcTFA@jZ2}9Uf3gxz$}f~gWGj#t(yn^8s$;ZxD@K>g*~ze%+i=WxLv2# zx-V7Xc~mqmg*tj+k1PVSG-eNO*QvEGP~F}g6^*HGPwfQEA}~v1_TYA%TI&MU?Y~1s z<5H-j7e0?H0<$z`4{q0~wJuQIJ^>YtOQDW;*dvR;ERETN+jVNK3skpHKtwxO^A}Sh}LS5};k1PVSG-eNO*QvD* zsBSN!qH!tI^1dt?#1I*kN-aJx>ebwG7{QL}Kj zNGa4k8tjopV3x-0!RFHkm!$r#D2u=>joE|Sb)IFRy1fw< zjZ2}f;UvovN8 zZr6F1h3fVqDjJtU-9^A2Sp;Tj%pTmX^DGP1?L|~HE`_>_fIYGZ%+i=WxLxO27OLBe zsAx>%+SK2rW)YaBF?(>k&a*63w--^-xCFaq`8=`+-SvP3dvLqXvn*7%7c~oa9^9_;EDP1`MN~8{h3BOH-Z_iFERETN+jX90p}M_@ipHf-XT145vIxx5 zm_4{%=UJA@*>lap*>m>z^sy1~qCO|~9a+;ZuRDIJRZHGS)e!0~-AV!#Kf#}>?&&|r zhrGF8VaV2(bw@&DToYywBy@$h1fK*6_W0uY%i_tKJybaT)cqbqLSrJ5m0$Kq5uo@9 z_ITwV=fs_Qyju9~z=;#^SQ~US`z|pJ0#Q6fY`Y_x07m@#lY2 zL_*_+Q1=wF2NJ0G3HF%T^jh;VcMK1rVBJO}G{#-`?16;tx-Y>eL4rLxcWgRfpRee* z$?G;~L_*_+Q1{le2NJ0G3HHbh-@H($yFS?A`3)P9(6}Mgz4h#Y1S)=lJ$^a)?!vBn zUKup^?A(Zi#<-h`J&@47Q6=~!NU+EIyFOJY^tvE;bN`JRk_k<-801=NTA{;*kjD_!-J!a-6}Xcdbfy##<=T+J&@2n zEG76PNU+C}8AF0?I^=@=YF8JL(6}Mgy)Ep41S)=lJ=W>?5xH-x&k zg*}i!#ZR!uJ|A5fEZ_IG!u@;PUqnJ<`b~?y@O|M(pyDUkQ+R>Pq0VJ0mFmeeDXzeK5UtQgvJe_?rmWYBvA1a?9q7i z)xp2oT~l6f*viL{(6}Mgy)Ep41S)=lJ(eAPQ84b8Mddkj3*C{>nC`38?;9Y2il1PQ z-<)$=@b0Kl}Otc_cJ$2=(uD z*aHbv`~-Wv_gtUgZ=3HCe|zePJQ5nyr%L^91`??F3HE4Mv3+pzc?ZS+dgYNk5*jyz z`gb~f9!Q|#C)gv}v_sJC>J#FQLl@_f(3pN_H1#_sNTA{;*yEHV))Xdxb8dXi|ER&Ff2NJ0G z3HCT({M7Qjdt4e{_3K7;NNCJs1AMDI5~%nI_W10*56UABI4fTIZl^jVG;Rp>FBkYc zkU+&xu*Ww&yTt3=acsQDjqU4@(6}Mgze8XTBvA1a?D6_WJI8}h4&sZ~{F+BXWBh9; z_CP}a+KJ|RlHVIZf<3<6E{u=ZaL0JtOFz#ep)ozRsb5_{0u?{O9(_6-7r*&^=lF*1 zujY}^xFOWPY2x!h0u?{O9vv<|J3e>2cgnjCSei#dfp%fyHHoN$1TfBB609T$Q{XhCPr##ZRzD!<(lCkIea|P^kTT z5ebc{_etIk!yZVW;wRW+$}z_T`>fqGs2%=#5ebb;p}qr#J&-`fPq4?8M}@)oH9G_c z9rSq-35`pkz5|9mkU+&xu*W7F^b7{Z`v(X1|G9{S#-&i-0mB|hpyDUk34UI2a&Y?Q9UGC*xD@I;VAul*RQv>cT(b6s z!oROOFZlge8#W@LaVgYyz_14rsQ3x?*#GyB6n?qtvS8yLog0zRxD@I;VAul*RQv>c z|pJ0!x&Uv!$_`eSidW`GTh=j(pR+PM}oIQ|0 z#ZR!uNws?}+4ZLpLFc#IHzJ`ieILnt&)EYBRQv>cY}JrhYcGyzHE7g1?RYwupqrrBL5)&K^jh;wRYS{rQv1ch0#q=>FroMI}J&fRvKcxCAL<^A%$-t1LgP}X?~X^;*TcP)!|EP2Eg2bsh}J zs6vjZrY=)Wokv1r+9#8|_nbYDK*dk62UW;1)zoFGsq;u^TnhE==Int4Dt>}Js6vjZ zrY=)Wokv3BQmAh?XAdM$@e}Mp6>>~9bxbvN9tn+0p}yUmJ&-`fPp}77$T8K_G1b(0 zBs4CC`gU{nKmrv%!5&m0$5d0tR8!}X(3t9yle%Q%zlmgvK=fNZxzS z9!Q|#C)k53le%Q%zlmgvO;%-)_zxNTA{; z*n=wMW~!-Us;TRc(3t+xB6;sQdmw>|pI{HFkPo1mI;NVs4hfCv`$*n<&K^jh;wRXH zD&)RYQ^!}Js6q~?rjDtm&Lg2Q?P5*dV$L2& zpyDUkgDT{JYU(o8)ZLNLxD?)=yv3Y7kU+&xum@Gh0oBxHs;Rppp>ZkHca^gT5~%nI z_Mi$mpqjc&HT7diXj}^QUFGb71S)=lJ*YwssHQGcO+5h#jZ2}vtDHTMK*dk62UW-c z)zr;YQx}oYxCHab?16;N8#loxL4rN#O}BY^H*Ouh8#mD3bZ$!3JNi4!?12O-T9-6c zR5DqFRvCO;_dCp$9;hIp^+Q_(X6f%RR}!coq4h&s1ZL^)Fjo?&Affd`TLfn5?=V*q zs34*BLt6x9>F+RC5~v`d^+Q_(X6f%RR}!coq4h&s1ZL^)Fjo?&Affd`TLfn5FE>{b zs34*BLt6x9=`TW85~v`d^+Q_(W=-8?7XJolzXdx~5~v`d^+Q_(W_|hP4E_yJj|VD9 zX#G&>fdppl{&W-n2B^ma6(qENsPsSrvraEh=idPJc<8TqHl=3k^tU=IJy6kEwWf-B zIBZ3c&^fXu_(kwa5B+t}^l^3et1SYv^!L3h2~?2K*{`+;%+lZYt|U-FLTA6)A}~vT z-@B4P1qq$~YKy=u{eACB0u>~5_Ny%dv-J19D+yGP(AlrH2+Y#o_pT&RK|*K0+9EJZ zf8V>3Km`e%{c4NAEd71&N&*!mboQ$)0<-iN!7B+=kkHw$wg}A9UmC9@P(eaxzuF=& z3#-9&)rSfaI{Q`Wfdpn@&6xJUwpK@8O<{JsiwY7trmFl@NMP2E&rajtUiP%@s34(Z zs!9(eFl+hGQ=@p{ksc3JkkBzzr3Vt2)&A(I(XTyr@OYqtgpR2yJ&?exL!O)x^_cKe z(7I+o1qmHfReB(SS!bR-C7OB9M2`n5Na&cV(gO+1n!3xB=$LbBJszkap`)-$4whHODohm(0K|=Tbv_)XnsLQ8BJC2&~ z@jwL$-TPDNfdpo)eq%~>N9XoSTb~CiNa)_5N)IG3YxIRvqYrQB>G41XiB+jxNLY~} zfmv&}pBClE{lVjb3KF{ar}8|Iz^p(2FfBUi#j89Xn5FxDn!;=X6(n>gPvxgV0<#8u zK0P|>mAgEj3Kb-DCr_mZ66vfN(ZF}cdOUJDRgln~Je3|uVAgj#&5Z7TwbA2&3KF`L zr_uun%&I+iRy6*;86FQ*kkFkxl^#f7Rvm$oT;JWxSGck)zvAc0w*zEFxrz18gTKm`fi$y4cp1ZMT# zb3ydOroL;13KF`Lr_uun%=-833!^2A=XuTp6(n>gPo)PEn04HmMLcWZ@jwL$-N{qw zfdpoC*<=aN8hAWVK|*)(RC*wRSugC>%(Dg_4^)uQojjEuNMIJu4W#>XRFKe}Je3|u zU>43G&??zkBjUgAc2D!#t_S6{W}x*ts1r2i8R5S^{O347?|||Po8FK|MdPLrd+lrj zvovOpFE744-nRRg^2;YaoJU3DrVxAWYyz`1W{#y_v$xegVLn?me^vkA=7m_05Xa(el93$KZPd2^#WR5Wf1u@BBB zFiT_hn7{O&&Bu%$9v}I9r#e(LZVIsv&L%KRWA?zk2B>J<6k;EoO<{0XPI)xWL zzdn9#+jZ(t(YPtZJ~*4eERES??uS~YnP8wa@) z{}4YgVon|vjhjO3gR=?D(wIHgozf%74~pVlejJlWMdPLr``~N>vovOpF`FL{+&OW# zc%LV(&ZDAnQ;2i@*#u^3%pPC=cVO^*@i*}=zds<4ipG`e23Z8IA!y7VPi}T%f3`u7E#fd_5nQ8!n08_tCmGz zmd5NswP--KXn|_cA}Sg;g}6G9O<_N3?K(%OrYSAJp8dKZ;yB3~}>St%8vIxx5 zm_4W#4X73^P%TPSa6ym;szn=7(U@yd z+>w$+q_Z5s9#o44REq{wi_$MoqvGPG5ci#A6PTqjdr&P}pjtGbTC@=rjhjN;calwD zmd5NswP=BA(ST~vMpQIz3US{_Hi20hvj^3p1*$~@szn=7(YPtZeJ9xjW@*eGREzed zS~Q?qv=J4Jn?l@ol1*Ti#_WNAONNTZO(E_($tEyMWA>n0v`n>VK(%NiDjL(+`Pn%< zw77eHtEux}vQ;54rvI)%6m_4W#jj0w5 zs1_}vqH*QQXcmEMo*J_U)uJ)gq5;*SMN~9y3UM_vo4_oM*@G&}m}=30YSAJp8aIWw znwd>tmd5Nsm1Rt|Xn|_c38-k?6yj=THi20hvj^3pG1a04szoQDqH$A*tC`sZW@*eG zREx$`ix#LB-5wQoRGNxLzK(%OhR5a#i5LZUC2+Y!$J*XCqsTS=^ zwP+p{jhjN9ndE*qi@+?6*&}O~Q?r^2^eXik#R0(6v|Er6U&k0-xG`6$oOA}_KFTK7DU;fk1O$h(H6zXL*#O( zAc5ZKktQ^&G^h|=)-b^1kyez*K95{(uZZ60PXDc4HtNBAwA0!iCcfvq9?@Y8hOWO6K!Z_NQxQkJYaO&>QrpYvuFEfr3QJ8$EJJ zK-Q=W+V`hx{ml^EKjzz%Z z&&W8fD3QZEUjcdsQv_sno!qH^U8#@9Bc%Y5dNxxY*aCcT(oS?t_u27|QH1XjRgjo> z(r%IeQz4Pg!Y3{5p$Zbx9(&FlpW1YmK9A~P?h?8_$^DwT6U{xX9wRMh`;X+wX-zC^ z{hiD6A;*GerHyA0pSxCs*8>R?OIG$%iwY9voAr7ip;^)@c?fBDjUsKW%}PC8bY=DG zf|4R~ruXr9NFOB%W@SCK_^Hyg>4|(Ew#RAx+3nL+jesn92EBx74HA#!9S^E8}gY{4a329@z9!g+V_I;JE^t3KX_rdzP z>{IKjWYQH*CSmVN`3_9qC2^VnB}JItry5~B}l=;r#SeS(^ zUz$J#i5%RaOpLVH$Qb*ICD7}{ytDK9)^%}@_3*k*X{qq0|}`N)T8oR86}lPS42lIauW1^ zbRM7}A+>~h=$Qk7S?Lz8*NEADA8JqU7vcYmT)+R=v3o=`54KF>+GyfF>-YbBg#3FB ziIkGiNbsF<$xSyG{(I0>#sdkBYopu0XxD#kZ|8voDt>}JT26bV@YQl{zq->Jdi-ePq4>n>+c=h)^2a( zfrQ4j(Xa#B_3vEhDd&L%Dt>}JigN}9C%n9w@jyc3+Gx+s+Vx+31dloCUPuwB_zCu) z?;@b@q|CP!5*pV=UB6zh|J&iN;(-Jzeu6z#9&}Z({w+5f4?6UM`~CB_2@ zjct3i{E);02yQ=|;wRWc+C<}lgvPerJ>r?}avn%b_=!Yci==2Im^N=ZHm z5^}A|?ph(Cacy*Um-fk3H&-_yQ1KJ&!EG)-ReTyqXj~ihKDK>w_oN9_`~-V&-@$zd zdmy24ZFJLL+b2&!nn1-*um|^n+_SL<5*pV=^~>8QPji|;#ZRyY_vNlFK|bq&GS$0>e-J>)xYMJR3WE3L1P;P2Tfeu6#d`HNi*hlIxV`OrEM3BF&Q;wRXH zdbODU%hw7CjqP&|^)3+n+&RThu!poI#sdkBZF{A4I}+S}IK@w}hqQ^t0|||7yQ||5 zB)A=Pil1N)dj868jDv*6wl~mm6cXH?JH=112iKu|$Mg4rgvOMWjKa7sK>`&&As#v& z%tcW$9!%oe=)u?eMefrky|ejLX~oe<$hAtwgGgvx8*Nt(B6ro(BS=*I1bc9s%TEcNM&g}kkGg`n)THI zk$alc1S)=lJ-9D-Z3z+@*G9_^IUsVaQkp=;Pp}7l7s+@K35{!`Bc9nma;wAsl0BiH7q2~_+9dvJ}&PZfJ0p>b_=&d~iS(>ESO#ZQ2T>1&bD z*q({gQNN8-^ zD>v#(6Wo3{#ZRz@w28(835{*L>qdQPg4;o-_zCvF(H#;R+up#9`qBiq=T7kx?7?*? zKZks+kkFX3q9|iL2#TK&k7RV0K9)OfEwv;4lTVxUwdPZ$6(1qjDjD4&p>b{WR(N1? z)zjlaRQv>cNF`%F6%rcPM$a5EAh~ZwM3kN5yQkp=;Pq2qn`ld}pLgQMh zdk#rj*EE5OpI{G~V~F`VIaSDC*WEYxZOoU<79j;9&)V=!B>>}!Q?!w9}?^#-(V|3>13WkJdoh;nfgJa_zCuq zxr~6%0|||j`4aI!g6~)A2aVz<*hA)Ij0X}LC-XkyfdoHy)DIfPPq0Vjc+e3_C-Yb0 zfdscW)DIfPPq2ryaOOOa&^Vcg6AvV~9i)EHD1L%Hs8{2;KI4Ie#>woUcp$;;IrW1^ z@e}M(IUaO`(wt@bLGeHW6+a;!sqrAqi^{Rwag+XBJrY9t*ER^bRy>Dnt`!m*Cv}M& zNooc|NS$C5KfxaK4JPY@NNAkYSK@($)H_D;6YNnr9&~r2(n*~t9!N;tW)wfc9#UDF zGe<(>q}~+|B&7Z{il1N)sgR8a5*jCUyLccWb+l3Z1ba{mm#hyWp>Z<)5Dz3|JYW<* z!5)?4LDy0%os6Tz0|^<|7{yPpN9B0X^*Bl=<3aI2LdIuC@e|;I<3U3xos4VK9?5vn z_0E0*u9c}v_>(w7<79j;9+l%kS7rDK_Kcb9!T*0O7o&d@e}Mpy;`z9h=j(;ypMPw!OtDdiyFmG7!NzQWX=N#jg$E+ z=K%z_AFc}b6YL=^obfT?`+Oo_TRKY$h9iCYlVcy z$-X7=!118$BQlDgU=R8Rll4I)G*0$ki3bw0AId0xf<35LOYIkRccRkCJ~Ht@LiTkT z#ZMRyyI0LzT_iM4_QN?3AY^}(hvongHU=M2HlJ!9(G*0#> ziU$(1U(hIif<5S-O6?bQ?XJ?vK1=aHLiRlx#ZRyYj_#1qIN2{M9!SXkO{4e;@Gzr0 zBs5O;y{0`3!N+yIv!8%#WyWeqXq@cd6%V;qhT!YtstiBD9`X&gB9u<{A&UnR{5`wz zpr2q59Ni(Iak8IUJdoh~)r|-J1ba|r$$Pc~?rV|IIN2929!T(W=SFvaf<2^VFdj%~ zoa}EG4jCjVg4=U9y7Lq4 zfulPlG^Q-OPeweDK*djpM>4uYLgQq=k9s78?7y)}@=1`8Yn6-#kc(9A??zo@$tl}`4Ni3bw0ugfTYf<2_NH1{qN z8YlbV!~+T0pJo(4!5%oeLqg+ZU!Qm&A^Yr%;wRXHTDW99h=j(;{zUOWLiP(9#ZRyY z%`v3*i@KIt>13a!cpxGB9*yEB*aJs*NNAkw7ZndAWdEj7`~-NI(H#;RC;ML09){rK zy3w7VfNN#OYDj3D?B5j+xmJeY>*J~nKfxaI4YnebPWB;-2NL`}yYZl(U=JMKA)#@y zpISVS;QQ5$2mJ(l@Y*2HvT#3$gvQCfaPdHbpF1}m^b_nMEranuLSx%rxmr6-aQopD zKfxZ-!Wj=FG*0&E%XuKd?VuYE`U&>H(H#;RCx1O49!PL|?nZZhf<16Nh=j(Jm5ke3 zjR!&T6YOFBHj)3&{3jnZj(Mi#O_z@z+4{wnmX_P7P0mNh{OjqK+iSW~TuG>s zCbqur`IZ+}Jz9m(tUP_1r(0e=sE3D8B_AO%cI>k)^&ga~5So>b26uj{W#$EYc?ebV zv}@KKHy^d!^i0e3S3XgN(5!s4u+yrReY^Gb5USvD^U>3XJ=OB!&(BpMG>fm*-&;1! z_45#_;BhUnfA5#75KP;we01=)Ph^~jDtO#{wD-J~8Rvn7X62(vYgcA`AFAMS^HFf! z@{I2T3C-e9xH9v;ata(yO69!O|bKKkQtm$jUA^7++xU8~@6?RDGZ>Mn8XPlW`3A2!S0SO57n_IU7JVii2D{r-FPKGx%b1m9OS z%RV1t)_mvj;OE0CcwBoQ&uY2N9-i=kcvok5(c0Ik#E1 zz53>$9v*^QGOOTmZM$;w2c;?mw^ugHw!5n@*vmt3D{2)yu5BOhzVeAG1h>03%l03~ zb?fUPxHqs09@n<>%YJ^Y3c>w{&9c4E$G-+1f_pNn;BhUnOYfJe5KP-F+n@W-gZp!L z9!PLc?LQABG|Sc{{_lh968C)|!4-%9`#?go_{^V{yQi{kSH;#P?i=JfDC@p*$FkLu zyRWz!^gkb}qzSI){Lcpxnq_NL|8vgOt9#Co;7Zp2oFk!G`Dou>tEE+{yjH5%de^lK z*Ie|Hv_x$Ynw5`EnXp<~*GfW_e1ycg=d6(ywJk!k^3jwJS4%HZNvM*Kka*+QHPSP* zMQ9e^SI=hlYEH>VNc8UgkN<(tEPEdQ{+!RlD)|Tr_Vf4WNNAS*KKykFe;-z{=V6a) zubaOvL4vQY&9e8EzrN!8$|`tV`~CatD{kUX7PQsGRzteI>q#Za$M72g<0c4C8!^iEYlB${_!C7 zgQDPZO@9^o$Ad^vKPXwI9}NBDLFxxZ!Q-0#D)f&Bk)VE1vP`cQW{w9%!Q)yYb3B+3 z)T@PVJV?b#`mEL9@q3&8Q%vI)DI@#2laND_mxxd zxTe3#yswm?-ZHtbsPD>nK2*Wunt6?k=K~4q)snlNo@RMAE1z0b@VKVGlIO84f?9** zsiih1%xtej!Q-0tD$H!J5`tPE$ujM3nAz@%g2y%OW0=|QCIq#+l4bgjFth&<1&?dm z`7pEpNC@gbB#ZC-XTz-Vpi}U;roZ|h2}}| zl+Y|QUy|{BaMkDLOOW6S(EofOp;>0$C*wKi>eY=0k>EN+AAb9%gn<`>sr}6)2v$3?jk`mY#Hq?5}IY^6Q!4^^q~2~r2jyIW(qU<4g3EL@`PPUl_nB z({qkdQ6Pzihz3kdR8)Kb10pKOUA3xe*SETB&pFKR7pa`8Z~fP^*4n#w@790g$?gw% z`*8S%Pn0`n>*oi9cMSL6|MJdWx9%5am*}w*yBvPO@C#Resd`R*^992n-g9%c|9S5G zVM8cT-jiycIngkp+E!AvYjCGQ;>dLu3_tty3znu)qe$%Wq6>z1ANHyGcdL*}d9A94 zQEXpZE7sSDIcXDXn`+c35>~_d_kMy=Y*S0nL*nioFC4yS<(Y{F2}YSc(YX*R;|V<^ z{^ZdY4ZnEM(}Nf*HJ&{Cnu~^e9rn3ZQr7+VUo`x?NA9z?*!K5wKVRls{2NbL7B%__ zdPrDFNy|wv%Klz!8+DSEb@p@D58wHyhpm?SUi6}ihA;X2@@mVNm+#q@|C??Hqh5dJ zg~JOE*rFrK`bcWU`9osUtrrY0J^GGC2u5*r4e)O~dD}^MbTxVThi~uN@$`*9>uHC0 zyuLf^ys4`ROM*n{E0%lQWw&+xws{TjMG}|2>!-uRcX(v&w^oB?F>3D@{ABo@*X))M zhur^&Hm_>_c=M^7y1k?&zWw1%lEdpd`2NQ? z$?j8aD=AqY^pG%(MF>W5=C`%_&@r33eTjNj+sSNZpofInOCxHOwJC_P)@?kYhvhD< zcUdcI-`s3F=t+pEm37#7LW2Fa{HJ%cdsNpBdJ-bhAYpcmI_F!rw|i7qD|#+}>g}>$ z)qRO2S#bT&ctQ_}@~f)DjrZhohO9M3@0qx)hNr_31Ru8dMx`?n z)U(>kHOof7c-+tGx;yim+mz2E_fJ+WJx@7oo6*)s9aE!Nl2xewXFQ>Y#CYA-qt`w& zJGYZy)b-bGHG0Ip?@Ma++*`LCo%_chsh&IT*!5vazXIyR8*lUVcxsYwb*5jg^z}sJ%E-cPlAs)e-ctO{N!w zRc$;W!6+M>gkTH5cKWi>tJ1naz_&kX2hfJ1l#UtXhkz z^Ee?mm!^rhqZ2KW-{4_cTa>J(_kH?jqSbe<&IWBqwHF{eKf7CNuRQ0RZq@Si z0iethdPqF<^1qcFGnvhBBp7wrTh5hCl#HNx>g+S3w$@5YT22oMtKlL9qpU{~;(zXV zXLo=1gEzcu=y`?h>+dTP?_Kxqo_xi!7{zgFHQ0+6FFQ|GZS7H()DrZNc*_3g4fpxd z-pQ^;f>HMOq_5~9VS06B(^}QC7{$5J5*#V(t4dS5CFmhxW3xy*+NgJQcl25fx%2ON zmxRrp&=@Nx`$rIMRQ(Jg2ooAl?!WE~S+&*kzT-}pRa@A?P7-``W+k zP6ll|NHFT&-+STksKMVP8upn-_1I@278UJlHP~_zFWviXvbuUSymuMJ+O`_>ka+bm zZ;>^aXpmqOd%e|Q|6FnMo4fN>e_zo<;wATtyM4E6j8$noA;Bp7`(!rn(nI39>&C-d z{u}GO)1b$QnoC%c)@Q0#Rh@*jsnY!fqpa7HcF;q@dVLXsQ8x2~=vq#XjdP8ncH0hm zNZ5=C4a3G05^Ypn9|>XWqk2f#JYIxgRQuUvv}8Ql>89OA$6mRg-Pzi8bp4f2sJ2{X z_`QJ|KUPYwioz4bUN=5s^vHi-ncO3jvroCNZXU7yPTE89ch+h!peKl#S{Wo+GzdoR zeDY4C$2@hYFi#2 z65Bs_&!Tr|qM^T-uC-#+UeDcqbj8^RCWJ)|C1;pMwWTD_u2Cnsf~1Fpwa@5aTB41r z{gx7SE>(}s$_G#@64vrmBU;EP_DHlsTK@P;mW{T5)N!k&ujKl?ybqrNa zj1qd&|2{7#6sWx$*BK;^ym8s+g}WVQw1t=dNbd&0sINSF+fu{T3DMrI30h`;KIW|_ zi1XKNS2XrWHKHs={lDK|G5Wzh8S%{{cj#KU-P?EQ`l{7t%jqGpZru*0R!1#TD@F#@rnb>c8=X zW4rg6+m7CI^Z&7OV{A0m3C?C(dBv!8>mEE>e)i*n7%L^SJv=Xa z#`4ilH$TRrmQpJcU;h5`o>{_nFp6_b>*KZJjJx6IE4o^7_Ot{&B+g&AecN)wy1RpO zk{KBF)x96m)4QBk5_Q7qZ(FVBwwN((tpE}s#k?|TJfVk# z^upac{!OAmf>E}kCK~jRuw6SL*o)F{KHE7?(Qa9_^pMcCxjJbF2}Ut1wHmCu%(1^d z{asdWJ$)qYU<*m;+&wF)6^S-#Dl=Hs#uG-#`iNTf5wfEEX%P~#9`i9L!6;e(`Anoo za!Jhg&~AH|8YColMLrHj^Od)QQOvFpFSCTt+{pbhr+M$JCFmi++V&G|)KYRHiFRiQ zl{Ql|iszMxmzK-bo$rtzzid2=y>BVk=ZD|)rlGIF8%{i}l$5O~dVc?i@i0y=OVJ=9 zHH?!}v_x7SWig8Fi+E|dU3t|^eeSx~%9yX#yc;F81T{$9eAJ1<{3JtyQEz?N>xQu> zhRS$C&w1-k9>)H3>fd_U-3U7NajFYo4b#7jF~wBhJ(j&l4( zFJ@&h;|V<^Slfsf4HAr!8s>AC9uocS;4_fCe<^l89`uml3~k#%qK$e-kA_5rdd#sl zuY`)OS|=FA`4;igyPSP8UtVkF0B1;sNu2%G1w#T1z8HXkH*NVi8zIJ?1hGSWbVt#Bj*o%_w z;$*Ru5hNiQHBL35(vCT!etrLQFhfb)^vnH*JHK)J;$1(#=i3h$-ty}mt1W%ljJZMM z2|XlUeC^YQpWOBll@0|Na}tbt|3?lSKKs;N65@?t*>8BpJ$J5_TFIFEd|mta1BN?{ zepLV7YS2SM=2)ziV8#;?jA90lcxeYcBs9DF&JavXFp7CT;_Ldr*y>!;Q*r+Y(nCUK zWiw00sx+REVAQ%B4jUeG&hE*0&_hDjO3dR@ey2f#Q9r--;Nfx4`>jNS9uk~AwFR99 z2}a$$Y&bmW(A`3#Bj_Qqw3&GD?)wg}dd_{Tr)OoYmHp3n!r4dSwte>*?)KI#qgE-w zDAusmpohd4pS17roC~*2G)ORt>%Y~o6XZr|t(`2ZZF^!lc}{;r!SZ>HvJ*$OEmsCH z9@Kw&>MQf7M(Hl9cWy0r+22d>xcp!FSN0EG9~)I&GN%$Y^X=~vtN&UJ%fTC`X^)ow zdKT4kN!XrfbTBQ!DBE`vf*#x3Eh^d+3e&YBVP}R!gFV_t)iX+rhY4vr%KgvkAz^2f z9t|fL#o1GfAFD`r0;n3CC3XT#H0U8=C(cC(M%jroA?UI5XN{uv0ROskdyOI?C6%km z`u7Tq>;IN{#j+S>`$`ZB6oTtc#-p6oEo!MF=!DLg)rkhzGoxgNmTTM~#)JBAJYn5! zC#zBY?VyK*?TMAv()EA4owIrvWxIAlSgx%eJ3mz0@^M1YL!w`U1f%RUkZ90Df^8b$ z-+01)mt0b=Wv$$$j5!I(UFAADsTIeZQFaxc5cEh6F4z4JpjIU8gq&!wR*ah2KL+}* z%_Su4M4o7{EJoR>KOyLmUDSJ&C0T{)f7)7+kl7QX8B9wsiaTn=%Whz&u#K{l*{Nn; zY&$vCzqbTEB<$={>3)Jyc9uvq=pkXJ{zQWWqwLBeA?UHwOO0YlZ9C{8VdtPkg9M|v z{#y-tNZ9Et(ICMn=CM|T`?=cs6oH-R6Ae3sSC5^RtKCn~LxMA=trdwjYAGif5}ebm z23yXk{!^dbo35?3J37_Yzw6nq)u4xj+Djueir+VCHRxfv{oi)ta|`X$De+`PtHCEA zNXX|qep>D)+Nk<`KzdFL4+;AWX$gd%8Tl;5Y_0sWc$RDSoSxx>k<)8D&(KE2r+^W! zXX@~f=>IgFpC~e_|Fdn@-9B;OD0R2b>#N1$OdVV{gA8Z3)Z((>|&NkYhYcnj^xff{AcAS47^XwT(XRFpKpKUq=X zAz`1Zg~nL1mT05obIvS_iiUeg*ynhmp%V4_JP1bF=bS-|74fG<#?@n=j9OHbq_Ix0 zRwV3`Sfhi{mU}xGWuN>8F;+^S7Af~wtH(Y?wy34liiCY?ZM2pz|J&AzQCyD^F9he0 zv?ETeF&A1w`pRb_3F)`y3evE4mN1H|xz%6>u;(&1N)~0tXbE~q*pnlb?k5-}>%ZJX zP6&E5i|QPscE1J*+dmQwmc=OfyZ8F6hI>fZe$}Jl1f#fLwHnMzlBxZAaA~z7p)=91 zCPSsoqHR>nw}|)I?(HBUGv902PcVuZb(Scf-QhHuJNtc&(XYM;n}ymnp5afZZ#YtWkA*Vl%04+wyzsPp=6`kn z%T`O&pI&tD{0Dw_mui>j9^&0co!v!UGCr@P<@s&Zp4K?vvG>nkb*_A)RBBkuEoF;6 zDF4lW)51LxwMU7P|Lg4Xw`q+ii&5n*#6|m>bLE>U(?ob$B6?w(V9TSm{Ppj> zxp>N3VSoFk`Om%SYt`-_^YBa)-|f+O(EUFeYJH_9-yLdAYEPH{Kbwgq%F0?fDzvq> z5(|CA9_DF@t!~+5Jw4l3K}1yfMTBk@%o6&o1RXU$e|EJh`m;pUC?1IlA~MG2h={5h zr35K0AimvG{ZR|W4^`Us6->m(wU)A zD@QV8wz>CR2@xKhi7Vdw(Gs=PTFGn=;=A)l-Z!6UuvW5GG)mXwRd4!QLde=y&&rXk z`LDkB<_A!#mbj+uqTfz5+FE&(wA|Ot?0C3GqJlW*nH#Kzn<>~B0ytdOCWrjC|&wSBde72WNJ&ZBGbeNBM8H1sZS{couk7nuh(sz60 zv)w#(W`Ou^k4BUwE%&H8kFAE&EidbC=;ws8iiUoEu#!qC(?odcit326Zic!iZjOj3 ztyR7c#%z#wT-vRVrOw14WEa)3nXQ%2hLxj;(w#cb46zIAe2u+!DJKAFlM^!Yb=S^n zf+lUc&oa~+Rv z&C8p>d-JZ9Rma1k>Ui|jN={^+ab!hlk1n-VBxKF^?wnn%BC77YJ^Q)j65o-_-rk)6 zEMqLBGqKZXi9z{$p4+2$OL-R6wY>cQJ>yY45*38#~qafJrc!pX&u=`M=%IEA?H`AtW`wSS+bzMq~+$(GqvYnIm7pAkgzDx*sbT?@O8{5BT^rwHkd- zT?5xZ}g8uC{mSAt7r%-wjAGs(;mf`pD;x9(%=(wZ1a@ zyzaLgc|`f!iliO%kmz5vBpCIMWB*|EtdDJ-XwXA~S)%Q$y>7f`bmF;>T96EI{hw^P zX8+6gtoC4V?`YSHcQrd0neE{rvC~bz9<9Cj5edOwl-%z75_4rJ$oim%gzP@~K1iaC zdfI50i$|l`3^y2rhlK2pu~SFAq~$>{>WU*)jsE=HgA)yUNWAYqSNEJUNHB_Ll&F*R z6+I-%WqSGi!%rN+v;?DgUWs_o;4FFg$v=~`Rvl-Ke@oCqVldbw{Z#3GqK&F&t%R^s zU-evh#4+7Ge#wJZj;{DepU0sxo}-6Ed2>O}Y$w5}|9sYqduBUNOSbN8e~n!t>Lk6( zTw>))AC*}cd1Z=#hlJIz()|RZ+EZ;Xp{@N%ndJ6tg1xrC@u%tR3{wYvV&t=9Mz)*DaQYK>p3 zwIv195{!D=ZCkC$ue{#=xvkdty`I5%>otBtde3p&tjW)CjR(a4{qojp@;gN&+Nf>U z^qob+L*n%h-DXYSSu_Yno%xyvukrg2(Nog9?9o3taH}bOa^H$IamMZLCy!c!{l3+=w_M|QRajC>&_m+*-w*jN0v+E7s(9IT>}#W0!R^qo1IM zgp}m7vTZquHmc6{GSg@8A%};A^g^C}?DLwsZ_BFn-AC4czJJgonL5s&eQS^!4N>-z zz7sOaLKIh8+gFVT#E1V6YZy$sJ2R?(=VZ2&o!WCE*Jdb8pE5{@M!u`DEJiiEHblmA z^pKD?<-0S9CJK8yB+Aao`6H_~_P&^JEn#C`=O_uuE57gc6Kxdc0uZ_W2oDL#e138Q zP})I)QJncLk<6>QR@&VsnDJcW(V18YoB7p_c$p<67-cIhA?UHXKY&`1uwFxd_21+vgL4Q8I$%^jf3(33^D#>?x<$M1usQ?EIJzjFP!q&bT$IpP+|? ztd)}I6Acn=RJ|@qh`}H{BxE(0-Cz-dQFeWm5cH6cyi#_9MF>XOE|CznlU0xHiPg5f zDxFL62SIJOB+6c0x`xSSv=^`8pxkKX&b0qx$=*@#y|q3EOvDjj`+oBpAio zw)+P?Bfldc9l{IyDF-7vp)i9&sQYuiY%!W%VLy_W;t;r1U)ii z%E{sZ)QW`6%5r8%G*~M}Nne%Iaz?--y<5)F51>{gWHih9I@7=>l}!{*92kyz_Nn)c zXKKQGfGt4}d%->tNNPobQT&{$)!s2 z^k@1l6l6uQToU$qLZU%}QTF^qLeOK+Wjugdk+5e%5)IahQT8-ULeOJRp*(jp`r4@Q|>lY!VIoY@&J?Wls?#1U>dirA38yJ4>iR!ag@lG)S~j_4C1$2oDMS ztZ)&6QTEwnLeL|#GEPXLJ>Bx~kdT?*clHT_QTAznQY(9grF!gXh-%yO6A8g`W!3r# zsb7O068029qCtXD_MAgPw4VA5LyfX$8x|qjsQSD{LfDfWGv(Sd8jBE&Vo$eYP7eut z)+Es&!KnTbq{p7JspWDmw6&s#ggy0?)QSY7>`AVKpofG#i?s;BD0{vvA?P7t&y+1f zFv^~jO9-jEpS+~6{Cw5!^U=TUXOJXhobvM(%VLy_e}2AV-R&v8TKE2T&_hB>D)(NK zmXlxfg=wcx}CVx^|Q(vAv{dxp2~7^my-fbRmrxd+)B; z>Jz2RJ?78&iyi0rF2z@U@00cKzy7OT3MGX*K@W+`{_NA0xZ_{tjWqgCNAQqueXM$( z{;h3?&>K4K-*ys433^Dl_TVk@-hTb3#O=TO@2XMSQT|(h0jho{>ik{*tNwkKXgxvv z;X7}t#BKjtXK58tjr;%Vf2!xc`|scA8uDE`|9c57e*M=H>QN2-c3$W$PDuZJ=FzGx zeb^GMC(3Pmq%dReU9YdS!|4ORwe39H)N0T}0vd(Zf7)^qjPhQeomceu80cJLzx8R5 zxaU>hD1EfY{3W~o_GW6;M#($R{7p)&MtB2WWg3kK#KJ%Q zTh;j9&!4OsV;@0!E;#81ZN4JnIJUc=cn$h_ov zQ1ZvpYDMC~@4d2)=7)Fv?akDxje18VW?Sy>yb=$I2Oad;N<8&|-5~rLZ>m-#809l`wpR3z@OgaycKc6hxJTB36SAUQdv@;9 zLjrA@Z|4<>HcCfuR>Q|bJS4o=v+NUPG0JD+tOh+Ke8$XXQ4);uc|3ap@ZObv_v|C% z%yDY_iXIZkeC-I1NwiU#k7s9zzGZWddQNBv%fU12V@$$xyGF&n+qT2^!K#jOeJ`0^ z=Oh^AJ6v-vsi#-VQRSQ7_iwbZDSfkk-v3@|6n)hY;vwO7(^tKOL|IN8HaW2&q*fk< z-JsU6>#It*y40P7?JGk$qxKVwvV1)3P8kK$lfIo^YJKfoBITCa)Dg6IR;h|#8-$01 zomYm<$+EV?*1=Fl%4;G~-oDx1rH2ICG&O=G80GyoJ06yOYQI~)8cK$j}d9t;wR=4z$qn)ll|Yuhs0lqKAZK)M2yNRt*x2@*bJhpofI_ zTeH_z4WHrCC%#sswLYh3dzT&(w)+g5J*sMuXrt=>SXV)tOKh*L9ul@E4x7DJ#{<8- z$SCiT*>=!F!uEC<%`$tKeMm5>UBM(c6FuAE>Mm`0%svu!omlskwpN_sZB*pSoRIlL z!tD}WYNr2Y^Dd*jhO-&YXPjg*pNY6CN?Pu-T}Fxo*2>g)kZ7Yc$IOnoof)cnL)dE0 z<`v3nqGFu#zN+dVJU`B^4~`(CHj{no+objw%6j(MC;7u?=;kv63C!cEF=ttAl&;!Y z4PUk5A>pel+YO>DMtR1V)u4xjXNlQejRd1Sckv7-BRQVad8P01(O#gfXH*|^CG3~q z>*>{g7oyt!#%{Jl3H$Am)#9<=E~z$a+iINp<_m^Dyyxcn&ZAAYUNF4$=sT({HH^0$ z1tTk0-w`bu(k6eK5!)B>(=8`qzYe}}wjC^sQ7`}S?ZcORetAOBbKGUO4d3~wht(*S z)L$zSm%Zz!!^3xYWTL^c7`68celq;dYj#Tr|J@a7;ny$uKo`aFZ)-&liRYd0cRjTt z!KkyJyT0p%R)h7u^1(kI-n7f^51_9|eE9NP%lh6UX*v6fQLJrSD|$%yZ`#bx5)zDJ zueTcC|M;fi7q0$NeXrJ=Pu(OlzuHn;pT{jh4~ZRi-Xv?K()|RZIFDQ6+aKOEy!)_E z)pcij)wbGJyCvu$VKq#M4;`~<_}QmlFp*v~yGAYl=^exOtUNOzSSu3LYimUh32HA& z)EZhz)lP}(VYyb@MF>W5F0>k#KlS$EUWa{dgY?xo-@1MH#e<$+%kA$gdJ-b36$!Iv z+SFew((=v2Pu#Na-m~k29uii=xy=)dvL0DAOT7Nf3x^jTu*GWe_^+pnt!uNKC5qj) zgHe{FD&0@eL&CCMrCSXWjIxZH5Vn6*kFC^db56G!^pLPMpY$#XM)j{+%eA#8mbJTD zmAsquu4uT2gzZZ8N{xQrmq0pofH=wUW$0f>Cx-O9-CfjIOh9m%}fR-7cAlEX$&5xzui3 zP7jGaUUY%%T}iD-Fp4!yHEMlH9J%g-ZtrS|yLY@$cCV^#cBT6XdJ>}2tp*9RYt+)( zLBiUUXs|3s^^f4Queqq(qhvPz+b{R2JAnN?$<*wtKY8>;-LA%7Xj@JX32OHfj50cD zIXxu$+i~yjy>NKc;BRVKSDgIj;V&Ndv)Wqwz0^d59ul{&{mb%ODf=%%FzS8Boj%<9 zsACes%B^PxtKme(#pr6ceMJum|J~Qwos$HktX7EzJtXeG?u_AUpQ-Dntrgqxl6%I( z$KUb#nKrcq>rO&`q5GEq-a9#$kYJSkJ?UL~NSIzS+et8rNNeH?7;n(3LUb^?&hUfnAM;0L%wfjTfJ{-Q`6Fr3dW{}J{ zi>kJ1n;mVJdjR^2L(_!mEkZDgvoaLqt^qwHtQQgu5{&Af?eAUp?rx+WwEx+%Cg!9~ z%*So54tvYFl5y&qcg@a>dPqnwZ2zd^me5xo#a?eUSYP=~clo_ksXN=(67-OeU!7lm_T!RT zkzmwid;G~zejRwWujr9a9pu+9mtHFp`Z+~*51F-Uqn5HhNZfqXiCqobzT)~|)LS3+ zx}KKPbKbg>(W6VL6^WDn_mpll`)kE0=9QL^we53BGK0@uX&-+*!YMt&xrc;irExOm zEQ?W6EBXD}*;zu5wBv-+-)2!usTB$7H~B5&Sq;{TQ8G?<@Ax+fL6402U!VT22T&^# z_8D8E!CEou?q$Q_Nr%R-dBk`y%09=d<@OWwkdU>Rx10o{-v5yUhtEEBm-^|V*GT?5 zo}-6^WQlw{-uRXMhG*P!XRW(rA0P9zk3V3z!{|pzU(rKCGG9KgNHB^Syln?PBy?xU zW;+Q+G0(ReH~n(I;m&W|zV_mtZ$Dso%ddB=c7I>dL*m8PK5h8PZ6A@02MI=ToZ4D( zJPzJ{-{Doyxo>7{T7qLh;p9ujtvS%hGet($~kl&zu~)lbkv!q#J=L4r}1F%rUd zgX*#U!=mCTlD4ljx9g`bBy7J*G)ORtE43tp=YX zvHj`+^c4x)MUz^wuNcK~YHP){W>-aBtrlPBB zgIf(|0Lkr9?ov(}BxEn~Hnkc&moQ3lqW4Hk&?8y2T%TKOmr^Sdnzfw{mGI)0gH?Wqc|5@4W6TT0_48Z67)B++247$wiv=3`C|iS6FL!>HVO zNi;|>YTY_%(@_cW_)C^`WgU6rGSnU4Z^01C8VnDKuRMBN^jjc8#1s7g@Ap@X%H5Az zlbuiAY4n(<|ueB`-r-MR;lB6DuhGlJSD zt7~heui{kPN7%E@b#;=EaVq!QlMy7rsCDa>&5rq4`idToKTB#`PR}%vXCD$`dz3r@ zmCyFp(-Ka%wIabMtN3JHOVC52|H(7X>b=k07WpG;*lMt~B#vJ8;NE-{Wid+TSmei0 zkr51!%u3Iw)Q)%=b9zX8`TNVe_1I6eQL&n*iSUp(f8BOv{Lf0~ZV-&(nr}6@?xe5c z?6Z^=MMB0VzmAf=@;S;VuI9E@%)7Ejd1jEj;u)hQ=#kd?X^ADZ1U)3Q-?GyZi8dp4C{}mY|1(?1_<4gDG!A#GcA1-KjMnN4%^LdgL_V zGlM0y1U)3=#1XSHn6_4o;*5!SU9~IA%F*9`V>xEQ9)U}0-Vvj^CWR}=YW@XjA z1a{t666GEeH6N$7A`wxt3ZkT_m(KR^1Ysw&M1y59s{K|PHS8+BmSy(QtXiiFx4)nBXD6Q5M_)3Z>JF(<(&_DDbd^j?upNSjm86F-EqI_c~*@C zqu9Q-9c=AO@42UY!jvVo1U)3KyY8OhEr&cYdBT(gqwMc}cYhOap zWBpTW!jjUK*C-O!(~GpDiPF(b2+k|cC9Bn>x38*)#K(3XjLI{qix7-zW+<9oc23mS zqH5ij)>kAH6f*u=>8pV>@TG2zo+L36GV3hSj zLU1-%J8F)ylID6_UOgnN50ebXvKYnM_P3mb+!fj9$ysh^S&ZVyPHWVeQTxQ^mGw`Z z?Pdp~*XJcO%n&y77a`iH*r`K7&J274)1EchsAEv?4yPL7nI__F7b?<@Ab9q%yTge_ z>xr{Zdpe^A2}bd|auF{rr-wxUH`eV6yY`P=t5=(Iq1CYaVl~R{uvzc+jd{CrBC21b z^#ozp>ZTX<>aIC!zcY&Mi+JfPw$`pp7il?bMZ&Ie7pWDa>^eFj=&@_{2T&^#c0VA| zU^^IP_Z$+!?haOu-3zxUUM)rccK2Rul-;fE2w(pZFXLgmS{*?Wc6Zq5U|NDvcK<3N zbWP|RLFBws?zh(K9ksJ-9C}DdZS%}PqK%4q9IcpcIf=HXgPCo)Ka>_Y)1)ic$7?LP9Y2*`3=OCB5r&I(kZ06g?!QB!6DKpJ3F|Mv#PLZC~@V z8a_uE#W~#)>=RkFF<+N59wa17_*!W-I3A4RzA{b39Z25sTv}g|5W9Z_y{{O>k!@?$ zdRT7Ujb4aOJbBrzM^z0HZcCJZ|6Dal(325%hJW^HlQ(U9-qq3$5^hVB z{GWVpUp3wVf}V_MG!7CC5^l?Xjo#2`RDzz2kiQKE*78+oM=i@~iLzdpG<{VGdNM*a zYy@WrrzOfp(=pG}n8nQmdB-}0xg zo<$p?h>hpyA>nUg+dRQ2e~;TN!TIBF?vW_Yx3=Zr?CY%~fwo+H61e?MG9)LQwwIK|^{^%R>c zt*sS3B>a7*jYh2%2}b!lQyZeziXMM2>(XmQ!rz(MXw1}#QOrth%eiW8{5MLumhF-~ ziXIZ|kye8Qqx?;kv+baVM1O|kZ1A@TO1YdpZLR1b;cqRRtrZDI`4gM71aqIiT~4Cd z>us&*A>r@5o7Et}D9bB#G+PaN{8NXe*NTLHHnI6yG0O68QY-eNKkF*xve(;o&_lxC z*Em}%5{&Y9Le3J*eg4)uiDIs7Yef$U+k@>)9n5%+1fy)`ub!tU>*veU_gbq;Sh>}c5vpM=Uxjv5!fA=JUN8+3^kjr;*a%h) z5^hVBjb@p9(hd^zWQ1ziOq`Q;kZ@a~Y*v~E33@U@HEcyy4H9lkl&vn)AVE(?sD@>R zszJhSiLxwV8YJk+2-UC*S2akuEm4;3OoIeH8KD}MsjCJFwqt|CS@P2Igy0h66J40 zR1FgJWQ1yzOg$<4VAUYuwnX{c7gd73$CnHqDR#ep>;kHEC>M{)y^kjr;SZ1giB;1xL%MzwR zf}V^}4a;yW!cU&NYIlJs$rSBYLIYSqAY8h1_^pHLN&^+COb~mAmO$~=~bA{ zD-yiA%Lt|a{)CrLE z+Y)8(7BUSI^kjr;9Q7NgOul*6AytEf+Y)8(nJE1!Ymfvz8KD|)e&MN;Z(a3+niEO5 zEm8iia@8O~Pe!Olxg$}>y9~#Ggxk=td6f{=lMzijY8JI967`u0tD$LFJ1Rks(^9Vg zT{WzCYld@=^oiRNWj(#R8IMZPlM$+6vt)*FTB2;mm<9=YGD0vDek?{bbClz$}LmMD9A%QQ&PlM$+MemRFeyPQWw zgM`}>WzTz=1_^pHLN%UI&eP*^t`-dvZcCIsM`ju%=*bAx*ifzuE-KdtqCvuKiL$40 zO@jnI8KD~Gv^2Ng?#YmFTcYgwUDF^zPe!Q5>E$}@@VDuykA&M2TcYfnFV>Et(Gm1y zgld$QZz%g+WQ1yzOg$<4V9mQE+?FVN8s9WX(326W@quzJ_~2L6B0}^galw>=37nW*}peG|# z!*YA=D-v!?lw@srgPm%SpeG|#!*-miLBef`(%t7Q(;z`lMyST~%k|(z-DmXr&3mnH zd<);-4WNG~(RyYH)hKtPy3goIxGhos#sbwKK~F}gM!BojeMV2hZHe+XFQ^6ydNM*a zzFR({zuT?{Nw{63?A;KmLBih}A)bs-jr+?U_jLVt46t7 z+kHmw9x2OhiSjpks0ImoGD0=vq<@)R50Y?OqWqmBszHLDj8Kh|sqq zEm8jV6V)I=Pe!N)KXE7FwnX_mSyY1rJsHtx)O&p-+(tXfK4zay$ddz=uyU&>BUHm$ zUixP+AmO$|SudCd33@U@HEaZ{1_`$%%0{!~G-(G3dNM*aY$nc0J4m=KQ8p`0g9JSp zp&GWLss;(SYm}}o(;#6hwR$o_H7qk!4H9lklw}FiAklcNCL~nDGF;Ul;kHCswlfV9 z^kjr;Sf;KTB;1xL%i5+vf}V^}4cl?51_`${O5bIn^NNIgb5h<%C7z5>+CI&w8YJA7 zD1Uc`YLI9>sz*XKO3S;?=t;OOQT`4P)gVDnMySTEdCg{zKrB65^hVBzqv;>NYIlJs&Qkv*Z!t6^m>ql+Y;q(pivDH z^kjr;{Cznio_C7wI3(PbD7hOc@5NCK67*z5qftNkA>lUKQTkK%57VfGm0LX-p&Him z4Kf}i+?FWo1=AowPe!PQjbPOv;kHECXqNdc?I1xwB~aFr8N7Lmp;kHEC?{t_333@U@HOd{9xpH5$_7w@YCCYyP!!$_HlM$+M>!*&G zd&Q0V`5+0mCCYxa$uvmNlM$-1W~*1v9sM%>e2|3O5@o;hWEv#s$q3buD;EEJkc8V3 zWxpR~8YJk+2-PTeIp@lK(YoW1a9g7M_fmBYlAtFeLZjT}tXFp=-1c_JJ5oZ!2`Se- z8KD~1^0LPb1|-~;DCq@xM~Z5YpeG|#?<`Uc z67*z*YS@mWV~(<%mMGnQ&N2-W^kjr;+*;Q7dV6M@gxeBjzW`?%BM??^i@aDlM$*>MsS0VISIEV%6=!%G)T~s5voyU;>71J3AZK6ep%2oNYIlJ zs!>){_xT_RwpXc#v>gqU;x(d^|wVlM$-%lyWBdu|2a* z!flDN-+3|(67*z*YLrafeLhISZHe-Cbm|%;K~F}ghJ4!RI}QoAB}%?AB){XX8YJk+ zh|uu8mW12hj`B1NG@Ouf-IEcjVJ)xMY9!p2DCvdroQ!FZpeG|#W1lkS_t_KJB;1xL z9nICIL4ux)Pz{^AlR^1M!flC?Sy`TwF%1&*WQ1ziimDnU+?FU=UFA6$(;z`lMyLj# zz$W3gL`jw?&&iku33@U@HOfhUgI^nva9g4z+m+{JOoIeH8KD}M+iPEua9g4zYnSI_ zd^~hFs02M3p&GX1%n(jXlWv4UKAVE(?s76^) z&Gn#v7Voq~*(uXBNYIlJs==!}5^hVBot9051U(s{8g|mJd6$IS5@n};(;z`lMyN)~ z)XnvvKjY!FMA_AgX^@~NBUD4K?)-@q5^hVBU4@wj33@UjH2hf{5^j4t{Hf5vKs20? za@~^=s$nhft_PiPTB4*E^5;eA$q3c3EBdNI!flDt(OhkPMS`A;Pz_$)k#Jk0WLC!W zq9o|a2-UC^H8&{#NVqLgvby4VQ4;iIglgEGqN+i{ZHbaB5zmW~peG|#!|r%h4H9lk zlw`YjUX%nq8KD}MsjCJFwp@>@PD_-XGEIX7JsF`I)7OKZGn|$vJ1zTo%v=v@Cd&xbu#)l!@*F71b8rJd+gYu7r+Y%+c;Ae@!fCN1mp&E8YUo}X$Em1m} z{=6s&dNM*acy&j@ZHbau8PAK7peG|#!&cNp`ig|x5+$q4{X!@6oKK~F}ghTSQe zA)J;d$rACrC<%HpLN)A;SJfclwnRy`i|0j2(326WVVSyWkZ@a~By0QC(qKS>o{Ufp zUfq#!TcULL@#jTJ(326WVc)c1xGhok z?Ge);K~F}ghJEv;YLIYSqU>8Rra^+9j8F~x22a%>;kHECw|Pv11U(s{8um@3szJhS ziL!4cnFa}ZGD0;W#5jl zc}0SrjOaAFZv&EWTcYe+7opJ+^kjr;l$Lkj1|;FOMA^4TOoIeH8KD~X&6nC&B;1xL z`xcC8kf0|cRKvc(Q#DAqEm8Ju9@8K}Pe!N)ukJ{=Em8KZB-0>4Pe!N)zYR#jZHcmP zSD6M0dNM*a?3-aVCz5bmqU>8@ra^+9j8F}`VyPM=+?FW&wwq~?peG|#L$2=p^Fb1B zOO$phu zk?)LF4H9lkl#Zr^I@-_xAzv8dR$eW zbtXYiPRP^I<(E(7H<79aiLlqt`>$1~1_^p{LNx3bj_L`SMA+-=?;QT!BljuKw@W)n zNME=oC!kTU4M>FDwWG8Z8kMket0yPWR~uw~kO;dQkGZC=Dq;OoJvkv7Hi9!m(CdBt zO@oBLDO=QYLNxTB{;rI_XIlt=OSjnZ_kLo1Lj-N@kl#eA?eO0fk#fUcKW}fkj&^he zJvkv7_|={PiLlqt`>)4{c1zHc6QW_ia8zdriLfQ=_Tk2R_qDl8f}Wg!MqM8y!tUBp z`cvA$-(9kD&Eqv8fxcQLV^1RNZagMUUsb~Tr+RWiG|Eiueg}(0*z0}#O@oC0hJvW) zglOo$_V>Kx9+|%#U2L1X8?_xd(arV}MOu0{{*5Ow`?^}y`5LQhnxMzpQ3>m}(x00n z7!_G!nxKb7~$c{5NqV%74K}?8u4JwPH>D_a=n!U#<|l)$m{1 z5Rd=*kk~A#CFmjHzjidML4r~JedWJnB4zn+mx!IML8;w%LJtZ5ou}Dakzkbnmeefa zziA;J|D7MP`^SSG68^hFvl^TwoEiR0E3*XWlK(Q0M3HVskRB5Lt3|xB68fHR)ZcA{_7#L8YCFyzfdwuFfaLU@JJL(>aP_E|IMFS4VJ|y zX1-Q~8Nh!5O3GzVw*);T{I{fLYej-l{(Duk1U>$nSWB-J3IE-#Sq;{TQU1$dvjjaP z{MW#GiPhp^UNPP4GBjs|2wgf#S zEXQn|trZDI@ib61#;P=)`0o`-S^gVEVsmUX)(Lt@_%B1v)`|q9{MV;CqN^1>{tH)2 zuN4XZ#j#Gq8Z(}-R*Y)*+C%^DqgS7_i~bgbk2!zIO3uKZ=fxfj`Upn3t-l|&_lnat zeDtUKy&`(tmU4afQH?%=QEscoUhnv~4ZB`{Y`JO}4CrxN%JuzGHTnofxvd%>yJ`E$ z{kuHBYS81hl&?qqKa^`f5y%+fuGyS*Qkxfk#PM zjB;Bw$_UQcn2+gkTgvroAJqUc@F*#ZQEscozdrv>b0@!4=Po^NOSyhUrW$<&quf@F zS6}q!b2mIw*C0J^OS!(|s74>bD7RIkWQIA-(;1^bw45TQx5Jizm^s?kR< z%5BvsJLf9jYw2-Y%Jq|zYV;9|a$7Y%zx=dS3wCCp$89Os&vvTOM=;85)fj%@qX(U6 zXCHdpmU8{vt{Qy=qug#ZCME5T%~OBB(rvV3W1}I&z@wxrt5uD1yXmW{L66%~uJxN~ zSYK5QkCL(&<+f_r2v!Yx+!hTRf71Xl@F*#ZQEsb-&BUrfkK3YQ^Vl>%3_ME8VwBse zVJoU?(Brmf*m^V#5Ce~rvKZyIYFK8d8uYj=8kSc~1H{0iq%20cts0i$WUn35Is7=Rdfl$6CNw^hS3b=9E9Z7J9CylH?Kc$AdID7RI^cATm~kK3YQ`;}>c7vI{~Z`4SL)b4Lcc_Mjyc_w^gH@mgFQ;HRy3$ zH2hAO*yX#gJp`lN?lj~KS2gV9Re$Zi*!eofJS71EAHgWMRl}}Wss=r7 zi-ukAm_{GLD7RIkWCpobs~YsUEgE*+X8Ed*V3gacQ8Judb4pJ1>%qDYdX#9`^=IV7 zlwg$Gs$o~cRf8V4MZ>P6O{0%sl-sIdSM*hb9=Aoq?gyAgAHgWMRio^jaxbH5(Brmf z*nJJt=pz{AwrbcNma0LI+oECjXH27yV3gacVRwqE20d*xJSMm72fMujaJc6C?t6+L0| zIT@L|eS}}PNln6r#+>Yf=2s`~ZzM3JdcWYGG zqG2Og33|fr=9Ovm5jIO|RM?_nGqGyW6Lz;gOrwvm*3M6Lyz(OFd*>^%0guYgE{xVVSyW&=YpI zf0#xeVY@+%3R^U6$Eh0hgx&3frqM^(u2!SM77g1u>-~0m!tQow)952?cdk)ki-w&5 z>Y19Ju)A}KY4j0x%BWFci-w(jss=q_ch3%*Mjv74pc)mnXz)blCojoYVXvR}^PJAB zK7vtUiv~}Y^n|_MpJ&;q8hwPHUL`7Q(J0xcJ5$pW_WF50U#mtR!KkoBgC~7@!d~ys z;#fQS2)~+;nuIMHykemz?Dg}0y`$~uBN!F7Xq4>JU3t+H_If;XC%L4L@T)tiN!X%M zvQKx-Nl)18=l%Lq+tEibDs0idu6g4rlixdTuFl=t z_T6W=+grCRe_cQCw%j8-c=vsWS3T!GyGPbXFv@M6?QeM4YbOsn^wO$9kK3a0#;@!* zJma1_O{0%sl-sKD#Q!>Kvim>YRW;~wTQuw!;Z38DV3gacvHYG7UHxZ|)9(-d`u^t( z%abg%uiO@mbvGO~Jm#F;>v!V@gFb>$ZmY)eUp#5U8%})vWKjOmhNZ96tNhT}-2oV3gacarnk3Ob-3rs;WVc+oJK}Yo9j!z z{Nhj#!6>&Ijk?awQ`TXZuZCzxwL6U&!fMqJOh*gQ6kK7vthtA?$pszHz2qG9XNH2Mfexvd(O z8L9?7Zi|NH71QV=80EHVSca<_^tde=mLE-{k6@JBs$rSBYS81hXjq;%jXr`=ZmWjv zI8}olw?)JDE7RyB80EHV*v`2@=9TS`tHtBCXxP5HTI|7~k6@JBs$nO9szHz2Qm&mJ zOrwurl-sIdCz+~2kK3Z*IY!&jM=;85)sVM%9AIx;91K>L_gtM&&kSx$xljAlV@99& z%~#mpNwglNNocM9r~KaCzGs|K+d;x@iF*3Aj~*TW!RMI<33@U@HEt~Lbp4f2FbxueL3lDk>Ep{- ze7TH?^c4xWC2Fr5A2E95zppe660Jw|NT>$iutCCYiQ4((okov&>Yk=Sf}V^}jW6My z93aUvw4PZ)HLT?`gwqmbyv;*82y>9rD8}2p@65%1S zc8a*O?1S=u(hd?~uN*!1rfY|9d-zV44@iWE<*uC~b}DW7kGdDKEJn#(xOVvUXFk?6 zNQ8%kj6aE=m$CR>-3wV3qgIYywEb6xpE&L*ra>Y+B-Tz5=a)J4?`3XDUy%rV<>)iZ zzdU^E&Ig$WiSV%8wNu2oXMF1Fch>h)u`EVO`>q*oH&|^NB*H^N+B8KRuuQ8YRtJS5gm5oP_Yl2s*rMI!8#qmOL*0>*E;`%U1p~)(463kXSoK99Mq7=8d)nNrb&}bmXf(k9AHWJS=zZ z6j3t6+?|$7NQAv|^yTXpkgrIDhvlxFB1(pv^PET`?3JSrykr4+mqd72?%FA$%&9rg z?IglpIeNiwEMWg25gwMic8Vx_)ST~8B*K#O)I&n`g0PmCy@6#hO2=cL7o2VyB&0{xLqhv42zlf5$6hYKXUeh|rSs|+ z_fJfNgv<=}kkIiDqO89;SyiGzB5YkB@4ew}(;y);TsEW=d|5@BoJz5ckTm<9>S zoa$k@njeF(OkFidgsnOM`8ywE8YE-~P!G%1JRij8|Kd{zU0K$lj5&$0rLV3T-g^I> zX^;pH%at}w5m&oLco?O7a8s*}kp0}-K|1~}v&2pSwH@Kn-C1cpOGNLIkduXv2kH2` zXp|9@vrp9skDfA=mcF{yX3sPc9um?EB+5*bGhEdO52N&K*Ua{gkaME157O~>sg<29 zt44VA)TgwbQDfDTkQ1w~bJFp5(U85|b4hsg^s2O;wVUkI5pr(#d__9`E*kPCTF;5$ z(Nnn6dd<*e(T&5mbK7!`M>)xYSST%*`$1^=Snm$`jFWObN^GB@AkYrU z87(1to)g4vmMwGV6?~zRtz7C`&eogLUzW8hp zLb6gmcey?yiuW9*=T)o&sfpi#T6(R5kR8tNs?D^#TZ0kBJ8aXnD(xsM$7lOB^SbWp z3ZD1VYt<;LN&eBZcJ#vSzcTNq%qVGd8ZB|{ykCFJv;(#BsJc`4%*4{#ZZ4JHwOm_! zx0KW~=H{v6(GgO^e9Yr&tG!m!mS-9~0qBhJp6)xz#2LqDh7+D$XM5Mnazb;kX#2hJ zws&RS#hLmGHU>-0C9>xIYEpJMzy4@7m`ftc$0N&EF@Nf5pqp2+Q#UhFCt}UcF?SA-AV0lM?`6D^WK&7xsFu(8B6JrVQ;=NPfN&^ zMSf0#!K4d2PS)@eSd1tBXqb2^Otb(Z%Ssf1@bI)oXX)w`2Lt^ zbcFU>*N*b{p1v|qZAY=4z-}!)+oB!+#&btM zJnr?Q%l_%|jnR(p)~M|^y>T@B>)jKg^+?N=_{{RZ7=83fYKKA@$vF~?y6XvlIr_#a zFHbb+A@QQ^Pa6H+XEF^EjJjo~w~nsd@m+}qJtPK$*NxuuzV9tUFp53hw!HO3xqo=m z>qb}n%Polp2}bpgpk=Z;um0$RCyze9>s__nr|x%h8JoKk4SJ;9i?8^(MRC4GOJx3r zhlJGduzi1#Xpm^5e638+-B?A-7h2+Vqd)!QU#1!?E23mHuYTsQ5`w*`y>M%d;<|}; z%iN`hg!J^`-}_ObL4r{a`P%zNSD*Ut2|*8ufB3=4qj%o=lSK$d{o8&Qk6t~(AC+j(L*gTwUfZ*xNVHK$jds0w*F>ZI_HpNFiP!e7^B@L; zi2BcGy?C_t;zuMJttW_&tvsP8Uy)$cr;mL8=&@Jqm}t;L;>cJ1DKaX@g9M{)Ir50n zV6Y<5poheluRp#JS#Br6sCOLu2cu_wZ0kgW9ugmT$?@G@60MLmNPB5#PNp zneFtDc)@QR-?M5-v{8PIGrNC;rzNDXvJ9tp%-s`FLg#sxr=`6gank7Be|Oeo`sCF1 zm9A|)v9!cVqphFxm}e+$%vdv=tZhHzM3k(@{Cw4Vf{^yb`I;JRp^QiDWYLGy?FbJE zoiVzL_7iPXQmcYW77Y&xnfdwYl?081?iwoH2Uhq2q*TJ@vY_MoC^NIdKt!QSW&Cc=Wdq zA0`AnB^|v>e-w~4+-0~6AcoKdd`MFG@68Pu<(CT<+A7 z-DMx7heWK+h@aj$Su5Ldl6G*9VpO~4Lq%#88NhZ?D|aciB4IoABDHFx>gl70D5tyX zAz|l-MF>XOsU{)lv6GWUEu~g1QBRqPhKz@|V=#y)I|nC3>j^^i%9ZdU1f%RcpX}%K zkdPiJ_n8t65{$Czl0<_Z5;`__CmJLeW!G1U20bKX#+18Xi3SNq*>z%~K@SO;`Q;v2 zqCujKs@J=ThFv>XPfOHm+(d(fT|3t(yKYZ3T2GWKnW5ZOOEgF@%I-fT8uXBmOjPc+ zBpM{zs5sR|wuBS-Jf5BpAt} z;UTfxy1R|kz>0fP z>j^^Im(N5JjN0qQd*rTKqCpRdOSieR>yftQB-*HZ<=$DMQCix08e)8>+*M1*Jct3J zcDm`;a#tMjibR7R61rBh z9ft&?E_me@Ysy`QQ2R$TC{Q8f2uDnRJQPB&bpnGk2NIc@ZKkd2l(%h~+%BcR{Wy=TS+q*GmueY^o zJRn~9urh*n9oR-;hspmc%qds=|ZQcIbPtZd`$2>a$kYLnn9(zO2{Stae$Q+9^ zO0<1EM}kq0e#mt__e&`@>AhU!7qsFiOe9!$7dPocgvOcoxLxNHJpYcyU zcf48;%U#NSIBM{YUfc546B^Q{JX4ck6thID!JHxUDt61rF)cw25;CXr{hUM_CF@_$ z+S3~0X^65O`_3gn$U65Zo*!Ec%i;5K(zo1RZRY%zpr;{pFEKip>GLjkhS*mkUUMQn zBx^YLuO#5~B4)xps0|gkY4N1{Y@US<*woPJoF92}aqeHqoGm zgq>s)4HAs9(|Mvn4+%SwCmJLeWmg%QhF;554+*=n$TUE-QT1vm(XcD8>S>6wHv67i zLRpBitG+~|@qm!rl|Si3f>Cz$nrP5N!me18z9P{^)eN3!*cE;C%o6!?GAv7Mjk5az zNv-IyJ;S0{QshxN>4&EwboWU#NZ1}_QFX7)T8^@8A6$&UGj}9xr%r1X>Ws3JK|;Lm zhyT?*BYMFdH+IjC+L_`~ ztGE25=P6bajIyhYM1vj@EB@n$Jx{TcXrjto$e%E^>zb-gV%Hykx92HV5{!}=lRp7L z4++kN7!5hekYJR|vHZCVdPwxot9`Ej5}sVFC*;}-o1XY@Jx@)xo*?WxAsImujN;61 zTTTxNyWUAONHD6uy;HMh00Q+UlXB`+a;@cdhR^4}VmRu_k@g0F_4Q2*Lu}9jzitppBScvbij^0=Y*UPjlmJvkv7zj5eJldm3qMAaY> z_VTF{APJuIazZqI_sQSc@TlWnSv5$6y?lWuz?PsVCq!fSQ_kP;8LNtExucytuzT^{GwIsq` zK6Ng==&Ps9eg2+TU480ZPg=z&KEKU#>0q$zuG8j@eb4(36phvsPkhJUrB>^nbL!k) z|9xwDGi6IKiYM8YpeH9pfhdOPTD~t?Bxr*7HJ83azZqI>$m4<>_&kOZA)~DtH`cjxDxsQkf-#=C z|MHgGD*Ox0S*AqDwDM0s8AA!xloJ-C-D4;ba_?@RGayETD1HLrPojjiRfo5g5+V2Q z_K6PKszK-{H{}Flpa(m=&y@(dcb9&mQzTSVPA~?>Zr#VO5+S4Jjo)UmKa@~SIl&m1 zQFWh#N`&0I+h=l0=x1-`1Y=-jsQX%?M996n^fS34p_+1nF|a1qeN9v%5 zO*z3BSgGs2wkr{G?{1%}DxsgAmJ^JD9jESlloBEL?$S?Hi-c;*3C6%)Tlc+IiI97D z6+cZ-LN(P3ce)-vaU29H+)j+)8t^~f3t%C2|%44`j z{ZjtcHH)fCW`lLa5rv>45Zuo{TJ8leQfd9fAWxs}Io zjryg$&ijv6?>g@ai_we-tAVwU(Nx)?C*RU?dH#(Ep;5n-`InWK&aSc;&4{pKTXiGa zJ%(%4FXg9K=#+XOMkx_i18X6(9;@M7lwP*Ba*g_>JY(dY(jU!;uo_qknK5?2HzUrr zK6j1!rJQBA$+&7pgcaLL35>+Lk6qWOU&`~hnI`k284*?kYaz29@tt>}QNNUL-|YsO z=go+)8dwXNF|ab!eJyc~`lbBZZr93s)r<(MfwhnsgWpo=Yocq^FXgiinj-6NGa{@8 z)cz-F%P-!x<>s{#a&8JJa!;TrYp@!s8H&pK<7H6{3j$tpc<5Y|>5UJq*2FJ-pj881I;F`5x! zmHHzH>%lyRTd7~l91EW8coOPOPOgX!B_jAlew zrTGyAzbTfpiZR?u{Zi(v9ku$=7NZ#vR%tc|VJkx(!>!aWWv(&%o%?%>(ToVIv|a^q zKi0(C^KZxtjryg`wQ}~T3oS-7BCOK78^k52oZ9hG{;hAJQNNVA=FdFu3X9Q<2&=Sz z1YtW)-d1jX$Ni=f+btCBiE0+CkiebLa=wR&J$! zDf2ARXx*$C5mxD362uKS``l%H?pErTGS5VfQIa(y!isIB1V$pyaMo5yqkbv#)Ylm8 ze(LK%gjG5X2ElWv&q23Rzm$1KZOq!N84*_Lyc+~ohKjExZl!)H^Az4#eX?dmSf$f> z5Ln@u8{})ETd7~l%o!T1sOJVfh_FieM-Z0d{b$-Yf5k;!`QXdeDjlTm6T}tz1I5M*UJ|OMkZWDgT9VtDL}C*l6Qlln@*x)Tm#| z95G8~_xu;atw>xs@bT*O&NE5~*Qj607wq$Fb@G!R{TITmNDLf5ySni2lS>HKs9(w> z4w+ZIwBM@t^z1<;+=|2{mpocM^|cu#F}uE8O-f=Y;Z`L6G2)?W*O!l##Bh!JrToge4_8O@Zz+kPgjoMm@68COcU6^U0)sW+J)u2H{~XHJ~eWPT{&RwVX$slCZO zca8d`{Oc=jZ!*u7a4Qn0pLchY^~yEsm-67B+}dQlQo^lBTy*hWP1ar4s9(xw967zo zx~qg+<#cvell^0`Y1A*}UH15EzB6R_SKL38a4QmzJbY)9UClM>mook`{{KL@6$!>J z-_Kp6em!3Key#-TK`Rn$!}4>9Yt%1gwsiTqLX$NihFbrYk{C+36$$QFLpFY*B!+9$uM^8;LrY>PL77%0xCfWl!!_!cGI#3odMM#m zBzTr6?+@3gU&=gjl=p`cZbgD;qVjR&8ud$=C#UjprG#6N;MuNxez->cQsxP;e10h5 zRwQ_;EuZJEQNNUVk}aR-O1KpX&*3usEA9raQNNTu(<6~Sd))}1q*CKq5x-B`WtMw> z)sqNK5Tv7=%tCyEGX%fUDEbO3mV0KIVki-sAQ&Uc$vlWpaK_ z%E_#S@2UP9K8-5+3M-cTyh$;X2u%=-5#?k$@qOFxp-+mw!iwcS|5FSlLK6gIL^+vW zr=8kyKgL$kS6H#!*Rd2siO>YW7*S4!bA!L1DEbO3miu~~Vki-sAQ&UcEe3yUna2oC zSTTn0D~%WpA~ZoTMwF95&0D>#LK9Yu;rnBXp+sncV2mgybI9nYTYD{?`aCpY#TdTN zrx;3vCJ4reax$Zy>RY+S#%^fBiZT4Wl42+knjjb>%E_F8Pf|zQ91KlZF@~SiQVbYW7*S3JD_q6b#L$ElWB55Z#ZV$NK`=&?lldIK zr9K?L(J1-~E0+6tKE+TXG(j*%l#{{SsQ4Zgny_LF&ty^zB|;MfV??>cXes&%E3b!t z*4KEdoZwR>O%Ps>Agt!CMPKQuXvK22u7B3oXx*F$O%UE6L0Av=Ae?3ljs^d$uQ5t; zA~dN#lHb(-LCnM3C@W(g7JY>k%Q>d~v%V}-A~Zp;9#PKz_yBW|KSf_*#d6L~|E#Y_ zgeC~ah;qijZ!#*qF%OHr!iwcwWBjweA`zM(7$eFV<8l0U=@!hxqOY)GIoC@6tglFf zCJ4rea>l^?YvtG~`U)$SbIte9`iewof?$j&XAI0g?l^gj(1aCZaPRWZ`iewof?$j& zw;0@O^BAECE5_jN9QClhHYY+81Y<-wV{onVwhB#HF$PZ=(H}~LCJ4rea>iI|pQk&n zv_20_STP1qOEIpL2u%=-5#@|=0nVWt*w_tCSTP1qeK9|j2u%=-5#@}*b0|)idFzHI ztQdo**O=!@geC~ah;qij%24;UBs5{g7(9g+R-XnDnjjb>${E8>`uPeMny_LF|4j<* zi$rLGV2mgyVHryvBQ#;f82?wyp8rnA~ZoTMwFA7 zf*9*h;BPHCi@G|~?;80R=3O3K!*{1PzKym>ghq+{dtZfk31{}zkqa7)pdZxQ6etweOQ=3?)LNe)Dft7UCxuyB{EzVhklh z9$dq>?KZxrI?I#@jrz^MZ(WG7n1kby6EcPpArG$cTh9Hvm$OWX(5T=1+nR+~6?K@4 zx-fX-em#K-81SMs+k)R$TfuJPN`{rl*%Oo`Aak-j}W2#zU^ z6xKtDkO$ZJ?dj?Jy;%<>LZg1S>qcC7>MiYOVU93{5+UciPvcv_vrGxBET&Pvtdp1X zsX(-NjL@jn;97j^cy}T+O6WJ6leiRb<33?+r9{YsYw^A4-HFhs-|e~)=)qR+b0tD% zTm3`El@g&*zpRrI7>N}hyP;95!L^;{|D!nC8$@W7D1KLb<7Aolxe_4{uEjUav#sp( zniHW>zuR>qurgG9Em0!m!L^@k^hj~_X%L}NzxlVP3xO4`;%lN3ArG$cd(r)S!}B$< zL4-#A7QbmcU#Tm;wkr|x;97i7Iok>|wn2nO{chKdz#dicJxYm?Ij;QM(-}jF(5PSb ze+hxNSk;$WrFtyby;uJ3Mk9Ics|G&N`#!|`L+F4#jN8$B{)-)M*XJw7=*1Qc|DW}IjvX!-fAt2p#)c-q*1?V zT?xWgxIBguA*Xfsk+GXt3?;a7CXM<{>thhMw&yXF2s!N^JNIv~7)o#lNE-E<*7+dr zJ^GfGnV5&{4<$loTRqshXmQ12C=nX<%Q|%<+C4^S)GF=4g{Nu|+>yN=N=G?IiJbuQ zdW0tJ&WTQEiD+FVc(U;RP&&#P13k#IPaY#Q>6DRZw$=SMdb$&#QG%_Y1V$pyaCwZ- zs8u@K6-Il5;7QNthtg5br?Qh}9wRjA)R*XVMvYmk1W&9!&y|jH#^7G=Ye{I*={3>m ztX)`r8U#(J5z$byo>y5Wemz9p#K+8B4xWhbCnczV0&L zDeMN!igF?}N~C-z2+P&-9Y=|fIj%f!<5MXS8uiN&qXa*X@!K4DTRhJP`Bo|JO?3MG z!H^ll-mOJF@*5Sol@gS3*P*lg{-FCRTIKg9gs^vn^BC?+3Cg(Z&{=+eP>Hb0Z$}8B zw*lQs{ZhtVhtBf*gGz)|emg=4yszE3Kj>EKmon};be7*AR3fbMdlN#~yXTm-p;5n- zaU-I${QjW(En4NbBZR=suvWiI=Dw7mj2jW1aeuHG5mx!_2qAF8t<~?uxt02*jJpn< zaeuHG5mx!V2_f`0pj)Y5%G^uJ?++>wR{6b&B9VW}$^LLF^-CFd9g0s?N`zH@Z$b#% zob2$smTskfDdVn#v~DvZtnzykLf{5yhu;}>EA>kmw;*JcG$X=_Euw_o;K|3XYt%1g z+;u39cDZqwd=;(odlN$FZ9w;>1ZCWHD9+kC?@q7>l?bc+-h>c(8_=!PFJ;_yD6T$@ z8;44SReoV;eu5nZgVsx_=L$S z)guVK4d_*84*^gKZ4NPfNrIJDYIuAw`(tF(Uvp|=6uO8rvi z-c^2oP>HZgyIq6mej70NrG6=MM{PV+QzER=ejWsFPPY18OSe+LlzEnDv~Jdn2&;51 z2?94jTm8xjhKW4LaCXZl!)HGXrR> zqJ{f|N`zI)KZ39vCy(J)>X$MznZ|D5Sy2xntWvfV1n#(3{EoX@sb9*Tk#QHyvSvhB zaa^SwE)mVLJGb(9<@X2iwn(SnAH@6Zoqm51@0xTreNR8v@Hdr8;0^rFrtj%D2)D}V z?5@tH_YHClt(3q`g3hM*4H|@7k;WTBSe4RU%i_DWuA!9@xDoL`5N_r5@Hd2tG4M`N zr@s}X1ml(8A5_Av7=!)cZwM7*xW?<@HxAiu<@X1ba4XUr3;sL$Vhq>NN(uIV`Tap9 z+=?{b5bE@I4T>>bLn|e4BcikX{-6?WMH+7ib^1FK#Tc%kl@hoS(OG_fPzkppjW>ik z{oRjZ4A;;~3EYV2EWbafgjSC|{h@?gk;Z#KO~#dLXr%;hL^K&!O1Kqiya&`|ez=BKO5jFB zllh^9Tam_lKuzYkYiOkeZbUSh=SsL0X}ky2WW90?t(3sMi6-ln5^hBr?*TPgcU?m( zC2%9V$-1kATam^aLisMi{k%9oTth1*aI?J0{-K0hk;WTBO?EZc&`Jrs-Sj^YZsqkT z-_Q9})X+)^#w*{?m2fN4Y{T+%iEF$be&dksR(>u~!mUViER^3LbWLt$ekrs6%kK{= z;Z`I#rkma?$~EejGRJY#dqoYxtw?ZgHoYH}Yt%1g&c~+rqZ));k>DEB^qyC)QNNVA zt~9;p)gau81lP)@_tkQZ`lZbEvFUxa2H{pDxaK##cb99_FJ-RtP4C?`2)81^{i^Bx z!Ca$$omi&X{lNx7zqBI3J-ECcu2H{~x$lIXqO${7XkYuEjbNoc}~ zF*N5a5}^r#F`}F?>>c5bqOY)Gxwi=Ii$rLGV2mgyp|=4;6IP7j{Y3jB5t<+vBg#qO zCQ{w+E`=tn7{kXK?TbWcf?$j&CxIJPb-#lZny_LFpEtBG5}^r#F`}FVZiaREU9!-G z6=V4Pr+twKO%RL`l?7&{n@Q8k(?T z3_UXxiO>YW7*Wm`xXD`ayRV@ME5^{XPmu^s5R4J!jKMn-eupe)kqAu?j1lERv=n`XmDj^R>ubcw2|iWQ1mX1v z!rCg&gp_cZG1!LwSzn{A{8ox-QawCgk${7Rmui|%?LK9Yu!MW+5^%aTG1i=_l&KS5+Rq;Dm zp$RL-;2Ptf^%aTG1i=_l&KS5E*6Mf3LK9Yu!L`yq>njqW34$@AoH6wNU}(aMF}UXY zXMIH?G(j*%lrskJEpZ+eeT5avxp(YW7*WpmaJJ09Yl7@j!_u2IgD^{7?%g%;nI(sfeEG}H zEMvJ6MNJvO@3)9IknsCm@f9+@!Das?hix;h7pxgW3DuMnj1g~AWtkEo_wHKeh9yux zenSjnD508if-(5lfcaZ}wv-Yf_wHKthHThcGgh$}N~orsU<{v4jG;uxh%x^we5b|N zEk=P5O*z3B_Kr+m5A_u?t-io_b9~EUD508if;9gcFn_DhdMFWc@2)lHeS+^8`Hsa< zqNwpFQGzk>SMfXeTYW}QBIMp({f_^zcG!NaSqvpqQ%*1j=0-b4d>%uIkZJXP4P(k; zD508iLSoce4tbKA#Il&m#gFT3# zX_fb;#ZW>uOYlnA-8f8eYr zYkN-EdY)^_3C6G;2lv|>`$tX$O{;wOu^39Irkt=C70xPzXv;F*sCd_Wx!k+!yvw$$ zVIPbb4Wg(iBdo3XElsR>n-U@8`#BH#IlhCZ7vfu6H3-#|6O6$%m$Qm7ln5E$in!ZI z`0ryelu%7M!5A2c70xQgP$J~sUAOJFa}E2T#ZW>u8xp&vI+x#E* zL5rb;YRU=5KppHa{AX=SgiNc^+y^a&5~?XDNTV-WIjh)KN`&0IYv#x?+y^a&5=D(a zi4u%~G1ba>$QVk5+`H@P6%OG(Xfc#fO*z3Bm>VseRg9rT$h11j{B!Iop_+0+VpI?V z|8igONnb8E>S5&;BPY!7e;}l-dJsW3TGu>TTjhkcPp&B^7{hw72N5)_^4_!y^b& z!q$&mQ%*33t#GXzRZ4{1Sa&Uk61EQJnsS0Mcn;-AVGJcgZtNeOg|$5=Y(394T7)pdpt9gAKWB_vHuIX59WgE9dt* z{Sv=TJo@-qcN8^2OuTGx?fdVqMFKw;O*pB3_bSij`?(ToB{E{`DMK|Pcb#?6TD1|= zeqb@05o#qeVsMqlJmk)qsYc|k*LM3pEH|+j%?Py;8Km7QsxyXaMDDtMw;$k!(oZc$ zGeWIIMhxzn{9z2$h}<=Qn~iGQUejtZnh|OxGGgF+)#`jQ#!!vO@V!~>o7dDVMl+&l z)gTaqeZdxH46%ZyVbwKbWNU5Qgaoil$b)rj0RaqKd~q6dY@#HyxN zA|rC`2Y!@TFD_8Rh&IK^yI8UDY(?t}_o=ept*XA<$Y4tD0Jg zj2O0a=JimG$oOoj_pn$Qgvi9IrdA>&2I|0XSIuLnMr3?O_BD(cU*Uwnr%{dQHMJ5M zF>L4LD%z$Rk?~nypJB053xQA78qsTNB{E{zUYo~IjmY@Svd^&CafHC9gN^7lwGtUI zFw!fwN42R&@%#e4_161RE-i@wgOr=-%-2ry|&_etrA7627#xtm7#*x#lL(7 zKq+_UhV1JV%e$Hrw)*5&BIEzt3YW)FjmW<4T8w6dt)jV=$oT)ZQs*&LBXXCm^A@8S zQMAf;1`_zO9mm>AH4WMKL5tChuw5;;5*h#BcFsJ8YDD(^++s8%Y>u|J-6*LVi-$gA(Gs5=7+)8A4vYj)Jp&F5W7quA82-_2LE0GbycFsJ8YDD&3 z)M7LvY){OsL`DqTIrAB%8j*b$wHVC^+Y@sukrBgo&OC-{MD|_OVl*RcAIz;pMhwhB z`+GI~d^g{>Y2|yk`OWu1lbaE?b9N`X(r8NmiyIe1mmT)hYMY|8Usra|QX#kX8g|Jg zKTPFg_(u4tt@x zey;g^wPlCxzvg;owLDH4>y{8%78)hSthHnT(`z)eS;(~jZ z8MZ>}24znrMA0gqwp$FThZ2vyz09yjw&Q02=vn#4TQ=cKt+WjVKs~fg*jAT4yN>w{ zPenpwD8U$mI@bO#PgSr&i>$klzZvaO578*WI&E?*KVkV#gj%uP-tSzqjKF9gGiHsX z!Tj(i;W%EU&B~?fZS{gi2#y7(1wiW-2(jYG-|peE82Y>%SJU4coSsnVVhoM01jqEf z!;Kasja`3UwQBxUtA4Olqi>g9xRi{NC7aBsEDMbimp;SuL;0)?Laj*0oR5m6^~!tj z`c0+Rv~L37tQCzCzk6rtCjFs=T0Js#=_akKn(>D(9X%+q<)OMgl@h<+eCguYZA)CS z9!0BY!)`I8Ka}`U-=&+)C?V8J$3nLlsG;vTtcS0nY>~p+-l&Ia*t(59Lp(K)p#*!g zv0n+2+RC4*U?sa<4m6%hM;vSGyN`}(3Bewewo-!a)@-GYo+?=VPc>J9z1d{P5npPh zedG0D9q>x+#51?fo ztN%{Wml7^Z3>#Oj>6brM^uL!kC#dm}p)||!uPy&yth*0yw`DDM7Jv4BT??yQ)Eaw9 zfhcN%*niDowetPrwvC6^dPddcuwjLK$&T9J+uxe{9Q z6e3HiN!*|GjU95+%iENSBCBU>LF13|w*rKs#gs0{)lwjYK?;mVk-}Q@DvHNt75t<@V z!yT+2V&wFkQ9*EAxmAx{tx`E9&~|`aV|$5N?TG)bTSC~G zp$B27f&W6Nm7O?B2(7v80A>|+vMS{NY3!W2l@hj>l*G^$En59AHCMuRxY8KmORcok zi}m2MV>QTqu@x}q&2K($N@IjZ362G<5+#JTJD&tI%Bo7)sc>YgWx_Zo7e5g|4R=lVe5Rvu*xt-_);q!J-Kn?spuCc;oKMNfjps6bL5|; zG4k_O55i7SK{R5hhJAnx;{PLt66{T!OCyHVJf5m(^}nptMIt|Cmc~$DVbx<-Yt&rl znw{ItZ}gK@A^%UY2bEwCBBv^Ss_<2`iWcb}BQ#2I#31u3jS+-e>FDtoZIvVip*x(N zoDsu5nSgP3qVZXVJ&CtE%L||N$yr3#`H0t?phkBYmxa*JWExN6GdSqx1U0cfhRpKx zkNwSmY87i&ls6}+QNm@GcmJ#}o;^lP(A@|;mHJY`Wg+ylzFImbYXARtBGn^S9H&{H z{@Ex=pOU8->C@9BH_Dq6&?wQ6NfgFaL(>nM{IlL}@tPCV2+@#*uyG|;h!=h1<;@9b zlxWB#tgX_xYG_c8^a*{V9w}aP0vaV6GKs>tYG~M2`EMFhj7E7kBLCe)L>Hn#3t{6* ztl&3BiI+Dgpi!bBlZbzqhYbztk$%se>VY_Mjs3p<|Kq8Yus0P-V(3#9 zt)kte;`wKP?$ngf)j$c3 z1$@F%RuA!2u)-{el_(x7%@5ZUi1a(*k{CML*;bL=MXN^yeg>c`rxNU&X4zf%Dp*PV zy2TKU5*%YqvO6KvN_(~#!+xKgw~75`+}g+2E3TFCk2MdC682U{N$V=1R;2O!k1|4f z%6_Y#tp2AySHj*RD2pM!)XLskC?Qm1zh(dbcq%3A_w^B@EwylQ>=vz})uT7kNDPe< z_7*|JFs#^vYNcbLTMV?7?<}l`XI^X({DvlCv?Z>st{S#(BaaeK&0{FR-fWUbiLZi{ z>~MLE##8BtV{Ic#i8k!^R5IF?V7oQTKf+hRN}je`4ACgT-t>I8IiXhCH~i~Vv-TAQNNVezW?27>%89? z@!;qQE!W_O^-vpglp6<<=H=8RGrlCY9lVj6CH~uV+Rw-Vf?y9G1L7bfT%&#|?|J!))#LY=WyEc0*+pn!#!w=x@YnvEgapnX&8K_$Y9Z8g=#6$#A0cFw~zN|HwXQl7l;Uu;~F z!2E0HJnT+{)!^FV>>8OLn1Ah@ha_C1ekuR(p=)J+{A2WlcArs7gw^2Mm*2cX=J`h; z@RP@Ijryhh^v@>AJfD2;#P%m_Wl$ol2G?$AyGYinsUY4q!Zqrb@|4#vk@ae=y{EMQ z$ks$9!fJ5sywT^|y32Wv8QcD#t%f9=Ot9+K1XotwdPiuNFRYZocNH zIY^>nglp6<zCA_JNp(>_H{MisS0sYWlt+*5hUnH_l6hYt%30E&evK z8}Vbz!!)jvucB3oJ?p~DaQgJ8`gC3*_*B#=;qgv;?tCMxt?)Mi!dKBM^~a?@{pLL> z#vjmDn`0i5VCzz&1ZB4L$&*$wVgUMlNzB9UL|CP9wPZHhh#!IIZ3IUNHR_i#N6cq0 z{?dqP7>Tc7RxySWVU^~`GGCly#FZePHG-p^8ud$=BfmE9cSgL58P$9533&`9!Ya+? zJ{R9)#5o|I#Sfo~vz8k5OPMqH(tcMPfqk$Y`(O_utkQb5+n1dnxJT{zyY1T_FoG)? zHR_i#SE31f%ras#wCw(9VLp`-VU^b1SrZ<&r}`Jx#34p-6{SY~Qs#+_%yb1*`t zVx%yJ5@D70k2x1FFk&8vn~mUZK#lsP%$;HJb#sik0CS_)c>Z0d@Kv;8{T{@OS_p!3 zaQsuB-o<&CYMwMoP$u#2i%%MX`8TAD2&=RQM?LysjxTRd#r@pt;RIuFKaYAmiIvA| zu0&X+(?{wL_W9!=+O4g4F7f_wf-!jFNc};gAJ*I*tp}9|E4J0k`RGaGip0pqC`lUi zOPMF97*`)-C%CII5`ze#h@w!TckwyCm+$N$CY!sg($;l>4OpgY#n} z5ED;KYdflyED?j=XI; zh_A1BMC;2&xJLa_9@zCkb=QF-5QD_5=SQ`kfA%+8)t6eaJo2_%KuiU3juEa=g7P!B z{j0jdqTe6}iL3i=-g*Xp)R$VZJo2^~AP#~xe^jFc5< zC)|qVTqRO=HxA!%4=;qS?2k)=SOw?(N+c}+=?+GZ)1!Z zATBh*HR_l0OD&hndbQe$M|9k8E1VK;#Tb#d{RJ^bfas5zs~Yu7dGVhYm}hOk-zey-&l+Zn1i?DM}4Uk%Oh{Q z0Z;WFtofrFB`9+SAN<6ni1B9-OP}+Nj@}DL^&s4eo+5AKnz#$+ zZbpomAbx?CePM+odJt|!Pm#AV#uyN98sQrCOPMR`5^uF528r1iAs1n!s4ul*d1QB7 zsTYE{!U)$WL76+lw!Qy`7$lxQ;*PrqW5la3wPHEX$N49MK;~Va?M*ULe`6`VoKGkor6a3mnq7rV!7@mb? z*-apB1>vLJHR_i#Pk?EDa5upGYn@{=N(r}O44!IJcE=v%uF2g~HR_i#&%0@!b7jCj z*ou9y2jNzETQ%}F#=t(&vlzDEC^{OvU81LB%r-WNEhG$_}HVZNC!zpI8 z5w20cl$lwib(ixT^RIQ7t<*}m6=Ou+#@*m~5MLPK8ud$=8B*Fmxa0g1C%)xy@>5@G z#d6QW(v0G%@-W-gT%!c#ub=T*aUX2Oc{JZ^m2fMMow7Ub&f6o#=|->~)Tm#N$4n1- z>HGugOWruA^}Lx2TU0aY?bT~LZTWHalHE_sY0ulTY;6!9-!P~3Pe!;#3Ciz(>%;0h zJ1;df%hm(Y_m2BoFFp1rt&E|BTd_Q{yVXDp2XT!Nu2H{~XPx(6b(w4^Vtfb0&_}1Y z9-AGX$56tp7$dT~H9)Kl;vgejqkbu`bN^e_3!gj&G1dezVEiSm{83+O#d6QvdJ?Wt zg7W##zFNJ!-}#8a);$1E)E7^tzSN54k=?BeVkC&(Mz}@^%J^ik`qEa{A;u3t9E6r# z1ud+;)QaVvw`JMJAhrbY)vQFgMhVLGgP*S6H}*Ef*a$>FjF3k$Qq-4PvE1{vG!m}@ zu>?k=YLuY-(9W}~Tl8nn$+0_d)PRek0WEhL;TrWzndNx# z&+75Pt^?Z32)AMk&)d>d9SY)8i{TpeOL@~9>r#)O&s^Bv%WAHKTQP>`ZK-wl1@Sj) zUDv2z%C$euwEkcZ){gy2$71V2CESWJJa5CB`5>wwJ~zTO>X&ks{nf@5iS@GMJ6?Mv zja?<&iZMKI%d#JV*a*bGjc|?nrF_VmH`x66A&7sUcu5C-@;+C>tr)}ewk+#TxJLa_ ze&%Oa+dL=n)g#k8zGW+e5^lv9p0}kHZiPpucWh;ZYt%30;fG#n>(vH`vCJL!b(~`> zoDy!u7?Ium6vV<=_jL?2!Zqrb@=C8yg1(((#mkhkf%G2*kwSze<WHxz#F3bXs!_j`v+QEq2f0#{n6k@& z_U?pRc|FqZ%zE4oq80N{HR{*nUBCNj$OlQ(QS%9yRow~JgH|k$?2bM742YwRaE#S*5|u2F(AN6c4?D~QnoVh+acg2l(> zF_dsC#)#~Wqy1|byPq538ud$=Bmasgk3kHXQF#m{+=?+gZ|h08M*ULe48E%0`4-~~ zJP~%aJcbf(#TcHqr5gt-l)0ilIQBNgSQW(2XDw_WdgGiPgj>;5WOv-vun)FlAIu5Ys9(z58HV>~&dK>P z8FS-HjCl2>RxIa!m9jhT2Gf2up#3f*T%!bKmVdFhju<44#2hap+=?+gZ%a@0{I3SI zEU|fdD%YrA%G{|_Jy`Qzvlg~|fmx-#)QaVvx24v78*9~YYb)0%L7C^0)F14@I#$p_ ztOu2FE5`7=Ez3C1Zv=szGk+@As9(xFU!`%y^KO6a1OsjCD&ba);dxs+^{obCLnBunC6F^Mf0ap!mSv?^R~iSG>sC=`_wOGo_Etc=eSxQr^?;1L#r>fVmZ&+DZAs! zz;ozlwwAa?3CcW?r}c_!Vn3Wi53?0c3AbVl&)d>Te=87kjBt(mrOeDCt-IevjIZNt zHQ!chCESWJBD>>Aljm(|MqxI!9%s9nYm}gz zWuMqS$kQv&p&QxGsf1hk)28f>J&0AI^*Y;~{WpB-*W)qM!#9~9KC-^-Mk`h>IN%$t zs#!2-_1dnzKCB+T>`4`td)}61$AS3xM=MsYFv2xTP~Pps_p3i&?=!?W0mMdQdsSNI zAD72a!mSv?^R_HIA4DGzn;PL7^-K9D7rj&cPx#{i5Lfi*b*%} z0xhh*)QaVi-R%Y9SP;K5!Zk`zo-t)!^{}~oQ+78H(=b8?VQi@{wPLyFZCQ3Si0wdR zMz}@^%0u3Lth!f!=A6fX_~ka+x7>1F-#msAZk6ii+1=S7h7aGqi z_JSFRaTbWRw%NYDjBqQ)@VqTO)p5hOZ@~1WGV?YdRjFO~LzmyLh zJl)3Cp&*`p{?8pdHAZ3(Zp9d$x1~Ox3!=pc*Qj60dt7m&%@3P{9X9ZO7w>}EBaEP>PxLWcG{hf2k{rg__Gn7(JA5ac376*4Kp6Z`)I2Pm{saatymt}owx1@Mz}@^ z%53R9*82=GxDWmSJva`tN`0vn%RO()vOPiU0^$TCT%!bKj+pZoY3&c{f61hYzg zsTIpTZ%aM61BebIT%!bKj{I-;ABz|=2lE(8xD{h~-qw?Fjryg`8GK5=KOzQq=P7ui z{qbb#ORZS$d0QG+H-k9D2-he$tyu1PTbAtvq8)qGD@M3R3Cb)#Z@~=2;Qn#!*4wwdT0*!LV?=hx-5L8}3--bM zsa&IeDRZZedSD-H#Xi`Ba4W{}ye-TAgcw(Y_=gd$QNNUVE=m1y0f>=UbC;#85Mq&_d#TcHqW!Y&UE(7rcBV40?Df66| z<_AxftKd|LpL~8O;Z}?h+1(K!)&;SH5w20clzHAw^PD4bG#nWT73_m~TPfjIj1k!# zcY_ab8XISXYt%1gW=LuOV2r=w#8<(rQeSGta?jiF1}F&ZgO$sTaE%g_2haRa_QAVB z?0{LNzSPQNr|gca=u8m%8R5U-Q^Mmh)625!rfyRI+J+le`rJFDRW*kW{$6eEejikq z?mMo+a?jhc>}(Kgg7~N_5w1~!@_XNUuX_3DcM#(=5Nqr;xN^_7m*g>&a4W{}ybXI4 zh)qG%jc|?nrM&osx2tP>y1`I<=L?8i&h1w@V1?Ov3?@e$;d8-Jkd3H zvhIXiu{^T7sUS80ae@)9QNNT2KmX6_7iV0A7=HzE99p&)T3CIl70V;LyBEYRAU@eM z5w1~!^70=&RqYyk4Px96;uMUKe{Zm19zzMYVhqpQvh3#|Ud1Tf1!GG!>X-7l7e7{= zvg1_5*cQZs*T=WqH+7R9gj>-Q_p6lMoe5&%tK(bn-<)ub`lZbB?|eE9G0p&S#_QwT z@!uYVTQNptciVti^y>Kb2aRxz`lWot0ryxvMuK>yYe>f!tGNyIuFCv1C3$9vX;O1Kqcc;40+B^^FWT%&#|FBo)-jjNjwWA_zi zcZ{`>sDxWFhUaZK$$&Tn#PvqFM*UKL@r9dgew+m2(AJDUd4DM3R*d0!Tb6YvT%&#| zPnvL@&GX+N#>MCMs~=`7gA#7V7@oHwj{ zUuwm2?pG_1)?6qZtThWu}ZCQ3Ld~b(2evrj*jryg` zojTQnXVGo2@+@mLSHi6r!}GRu>Kg!J3nN^kekt?Bk^18Z#6SU|SJM#cr8I*7<#_+r?tv;uK7-EEL)GuY8 z$kTeo6>g=y23Mxp3a5lyF^1=DDVz8%h$oG3jryg`%p$G3p0RvlE431C#Tb#@u|HPE zX>6Jiu2H{~nIWb9gLCj;ocK<{JXBw5#q!AR@)-r%ZYs!s9X1!@7HP-}>aoMpQQ2YgB7dGpIJd?Y-(g8ys9=x#w;8 z>w6&10`UtYLK6hPk#x07->IHH=~cvd3B*?;S}Xe;H$9J`gj+F&=WX}~;$!;OUjlKE z5us7PgK+!wt?JU}uQN2uRs^x>SL;gX@eLyTKM?1YwGd)wALh7xYY7@oJ`_q8BS0`X%bLZf~M)jmDw zsp|Lx`8&w-K&(D`RO_u6DMepl#d6Qv@b(UBe%79&T6Z-fG(oT)<3>JKJ$Na;_xd9c ztL!(iWv6vV<}s9TE5`7=4S!h+Pqk>w#Fht)2#xw3loKnQ|7XNF1;m*BCbs{hgdj~T z#_+r?%YKZfnmA@+`*0&dqkad~&YpIU)ng+N=kGPDW4P5^3AbVl&)e{+GwZSEsE&t> z2#xw3R9oi4JFGw0gU25?y<=1BK_%RZF+6X}vP(dm0OChRghu@is$Kc^EjF$$0@&t@QwG9onUcM$%%$JMr8ErmW`G@`Y> zgRO8%xD{h~-j-$G0`WYE4U7nl`W;kzasR7q-CY&LL6427e~wvI^c7YtkL>PK)cjZw zo7>tRnjkm_*F5>kd}qkAk3k&0?#TKB`%i2s`U)$SM|Q^;M}g=tA~ZoTM$7ywY#(%D z(f$+Li@w6jW2fEOpXya3SdXL$!s}7p;9%rxpW&${pyp3wRuz4vr=k_hJ#WLiYSy~% z8xfiy7=!(B!K7CaObAWi|nnOoEZ!5AF*{bufp7^i}G6LXM1-3hm1d1QCpiO{Iu zG#{t0&O3@HBgRkui6_F76@7&j%Okt{9K>;`!*C-)69ntQm1y@b&qIu5&>ufW%f5|1 zDf$X4mPdBC1c(+8?-~)BAQ*!y>Tw71caWUtZ()QSjj>hq6;>>d?5+d#xCpz!?gewDI2j`k0*s~uxRXo6r2mM?$)pAmy|@M+9g z&fKD}uwuFAZCQ3Fh`u1E7!jHv7=t@?st3=aJcr^un#WMWtr)}ewk+#~)@=iEuo0nA zzv=vt`hz_<7%S+9)`Lp$^g=7f@VpIA2x2`D3ycs=e%?ub(>W-Ot8at26FWhF8;MHr zd_^n9i0p0>YTgNAyb+;Mzv(=e=EpP;Phk(lPu^Ba@H9y)#_+r?%eoVxQNQV2n&x>s zV(f>#yxmp?C3q^P6=QhbhHricF&e~8MubNFrt@`LujYWraKgCIRyZYiZl@JvFlR{F z-HRYTL2fX?h|s9tlqaNh_h}Fp;H31ft<*{||DY9PM0UrKI0eK8n1@A;`c3&x+CMl4 zG5;#d;pEqyU>@cBM`U-LgV;GM%i10l8udG<);0M3;yzfp-*!$V+{$C8?2dErYQ$KK zQ*u$Gel>4fv~CSgv_77UF_Z`^&B9&<@#VU`D&H}} zGdlH4`L`!7sDAzRvk>DW5WAyghoXfULy54`EbK@SH-OmD2+#Y}FXj7}e5$(LXO|$x zVIa1`2$_eG!Wc?~m1bdIqOCeWEHc6~I`vC=#qT^;{rjGi5n~0!xa-BqEgx)iKpsPh zu+l7S2#7Ht-Y|mu9Wy%hOPS^U7hH`PKLc^wi<8@5FCoH8v#>rO4gv9RBRr#1zmz|C z@gA#32BNn6;T`W=&6Nl%&B6``aSDjXjqr?4{Zjtfmv>ly90lU&misz(vmR6;tTYSz z1jN}OHZj68I`vC=!l}2~xOxf1;Pradm$Z?nL|ADSHVVXQAbwzkXLRb9@~Sue#pcKU zAg*3-a2-E+pDPhonuUFy=3w3Dpl5XIm+}c${@LdFQi!qThOKoxSsp`)uu7-p^l8*^ z#MlYMu10u9r+z7adK%uj%hxNea1+PwROhVX{7@pSGz&Y@i0h4Dp25%C)Gy^jelywD z-HSkcSsPvNvqxInl?W@%!nn4-0^(>}+dc17zm$Le=Sj9R3;==oSHJm%$t|ph5@DrT zSPO_ZK^$a+=Y8sz^5@Gr zQ@@nCqVD+FC5Z7W5F__Eykq%cqw^R_gq3DtJTpwfn0gCii%;cwpZcZDo#EjYL|!b-ESF^F*s2%m$V(Wzg`Jjtecz6prUu`_?eRt6=)O0zJ|LCn7j z=OOFi8J+s2%oBN9uh_b1*$P@XUlWxGE6u`qlGz=^QAT)1r+z6jvqyECR zxze0Gh7xYY*pau*0x=H6?MApp{Zjt&nMKt%J{dGL%jSSsc-e@`7SFAaKd%yQ#Tb#d zT?yh%5JQb{jryhh@e{9BzyIFP5#v%2LtfdSvIl;h~4s749OYd-fv z_0CEBn>GDG48s#G#*=j?+=}Iqw;c&$eGu8@iExejrTm@M7F0ht;17sFVg_3FB($*l zQY)56-qr`iYao7Oglm+beBQlttFwmjom7sJUtom%9wSA4sTIp3Z#xXcnjlUw!Zk`z z{`iYWtIwRy-$9NAG3V&1Evt?>CXba=!z62z`XxJC)e95L^HGU%QxTN%VF7`q2!R;e$wVtM3klR?}E;#ebGqXcEn zk3sMK95G}@6Y>6j&0Z*pB)QaViw{fNZ zKM*(t%GhN&Pv9 z^)W*B#YjHS7+=?+GZ{t&42g0AqHR_i#cj{CR&Oyw-R?b89 zrB*DDylo^}_d*cAG{QAXQ0BQL^~dHQCSe8L-+E99w_=RQ+c>Tc262uNu2H{~dA^Eq zwK;Zz4{anW;Z}?hdD}X8D(sw$L90&7WSxUCFIxD{hW-nJ5mmqCm*!ZqrbGEd}bz4|_g^KrsB-Bvgy z+=?+GZ(9+>1t2ak!ZqrbGBb;`?(*#OTbz_8+Dfg2TQNrDZJrhFZ-i^qFJ)#(Y5%Yt zr-FSj-=mapE5?Yt&33g4_Q9NRjryhhvsTXsoxnbr@3l&}mDeL>cm7n^2Xlf?MUDFP zc+B*&tn&Eu_655fQ@LxYQ(KFgfwe>Td#Ad}mV4&3=WSW`-6y8EKLz43BSI5ImJO^O zb>Z99i(h^gF%AVWc8von2b?=EkD-KHF}CMzS$4#n>FpUUu6Th}bAE}0D) znq{Lvw7#)p<&CZT=Fh8yTQNptcSoY;n}GPhh|s9tfwk?fd9}Ls^z9L2Du{P?-lW2x zqOY)Gx#w;83*)n=w=eUnO)4)M5t<;_R%_09p}P0#M+TOjJgmpR-HS&{bG!er!i8BzQT&-p0{P$mZ`ZRx2NVx;&}g+~1jtUbL#r`2N{#5ijyWZYJBCESWJJa5agucLLp1o00eLZf~M z)@F>n)B59n^x!Gy&g&R$J*b3RF^1=D_-qMJwK|B?jR=kUWu0!baWxeL#%|rmt`cs= z7@oJGbXB*(5T;mwX+VIV(adAKs>X{G4(rbrB=eN7$dSf?gk|07!exvJFqtK zva9l)0dJCnSaIc(>Tk@M-cs}xRxFR~?nsOh%#Hd3n1@A85NW--%03qz2cjQ{x3R`| zC$cPAdF-@1uY#KQ2Jr!&uBhR-a=$6wyIbsuT>^x#M5%1EUeSs%BD=d2ZFMmSoMv(&H0n34kF!Tzh#0d#th)56 z9rG}@ioU{%<&oXpfTubZV`{z;p$UTh!JT2|c~>CD1t9*8IkG%Pe9>1}v7Gx=%I<6* zP zoB-~(nk&KmoK}qCc^mo&tveBG)$2xtM*XJqL+Xz@h;Ly9{hjro5L+nh`lqebN-+QMb=UK@v>Wgo`lu11QNJnQN&Cl2h_M1rm9N_#r3CXR-#v3T+GnAa(K z`)2>FuC?|%)ji(ay~1+O4e?$$Vz6~z#XMAv5|lsN?d|H)=RSjc@KVHJ>oSAvPPi4z zJvYpj{s|^K#Ry_ekO9|mt^yIl=mOTOD2N=6N^{Gbv zQl5O&tJO7+*bXuNg_>^!;{6iBt>`H-$aPVVC6EvP6Z23t>X-7GXTMNg?%HvPvG#u; z+=`wegM155H5X6Bd{8y&m-0&s=U1PcbtYmA#H@WD#O5W0ThUWwkmEq?g_b=SEvy># zOL>V)=2jOS_9w&`g7s<{5PvKo+=`wegWM3rZ!tpNz(`Sz`lbATuRU7*)8&^V#vq)1 zR!sXx55leJ$#X+wsUVQmw=9V{q8jx}nfq1$WhWuVu^^rRu|x^sR`f(UWst{#;5>A~ zHR_l0b>HZ;dOU@F@JSHVT9QCDEEce_n%T@!?g}s9r zq-vC){Ol3aY<}#Fr^3!zuayvPMNgg^X4wWH24D|-%;unL)Gy`Hf4ITsxy{(+bB7avNLWT%&#| z_qt|^t-E6ogJ)fSs;0iwishag;te{C66S-i+e+;kB`81h^i}!JfcF4EJP+c@62h$* zBQi*S`tfy~5f8K-$2IDg^3Pg5Z@U$1BG0<_U>>S3wPJZ>dbfkXURysOEub1DJl^JS z?v7k-J3JLn$Dg1lyA!Mjtvq%*0rUa!0&0Fg=AmlTFJ<<}s^>m~7$@L-wJ^0+55leJ z$#cUj>kZ-v^xzqoRjN_HlsRHnU6%Qv?SpmfgFOhhq9=}?bRv5SZL|eO;&Yf)s!_j` zIr7&(Vmrj(jxz$p>=MGQ=*e@#EL#Wt@eWR|{85eirOX+eT{{jjHpWxE0P9|ux!no3 zV!7vrcrz2kM|dL6D%Gf8%3QCWo^>W-oQ>9f6$DPOJqWj=C(jMBCW81kviXVV6V<3+ z%3OC}J?u}2aR_#U-=Q!5uY_ z7nKlhMNg4IZVTc{^ddi(QH}bg%$?|)%T7X!w?RAyV&xLTt>}qz${_y*Vg_cc6RuIe zl(|! zU&=fIrup$U`r-xb9rztc55lb&!*jzdCEaEPxLy?zv%F;f})zV@q4%T%!bKW)^APoroAb zllYpbgj+F&=Z0DKebfV=$5gs(ZFi0OrOXT|?H_l6z-K;{*(HQqF^1=cc#{LIi_a`8 zw}4cQ`lb9p=R25D{66}3FxpoIF(38mPPi4zJ%>Za0)oHEIMsGe*Qj5Q$4n33J%Hb( z_QTtABk&fTS`9ek+3LDS{Hyxg*LSTH3I0|e?-W(G#P8`HgKrz2 z4q{vh;a2qIxglorTl|O->AN^#=xQY-d7O61F>5P;a2qIxnY*^ z9j^uW-S!Clo?bQTm+~sFy;6PY&f$o`-=EJ1@v9QTt?0>f!z`2E(dRK-qkbvxG2n&j z>6;yf7<>=l7wJ8K9)w#lhUbRZYeDc0)5q~-s!_j`Pdaseb^2y!AO_!)*$BiJC4^hi zljnx%ZIS2DvPYqXRil0>KQd}=b>}-KA_jY~3&fcvgj>;*=Z3fi0pgQo+gdNeNKuXY zrM$)89<5$?AMYq`0iqAa6yIL%PPi4zJvYR+V1O8fk&ZXqa>6z0mooRRH`id!$+tyL zuy<0`ms+u$M9LsZ>|*bWszwRQ?VEL4JvayV1;KgPop39bdv2JX>b+&#I`}rOYSb^~ zjjy}Y`h#zneh+UyoL54)6+J};$yxgb-pOdQ9(0ZRrF_bXx5>Dg31UJC;Z}?x86;v< z@ovfcHWFQV|=M*R#ws!_j`IfKvM>@dWzn-+E4wCF*&6+L-wm~L9| z%{J_6IpG@hOPMRt?VFu}7+k4$1o2u4;Z}^{xnUv>Ld%|u7FLb=rOXv|F2sH%wKd1ZAE$Qh)GVavli0KiGqCD|(6ylJ6%Tg%$KN>p|D3U&=f=rE$fZ zFI$4RxP)*k#_-%QweCpl1h3jibdCC@%oAXm9|I8MKoER4Tz#n(%RM)2%qZSn$_dvf zL76AnG|&Bh6lbpbQY)5wZrIodE7%8f!Zk`z=7~J5SA9{BC2?B>x3+o^Zp9dpL9Ppe zw_c{&3g;U2OPQHPT6fv!n6Z^>N(i@N49^YmIUEU`l-9A8+BNEzGBc#Ke=sY;D6EVq zA>4{FJU5KY>j=y$)u>;}pD*Y6AZHYBA>lmQgK#T)^4t(_q!>{t$?lx+c+B*&>>S)t z?29{!pW?=$M*nK@yy}v}->%-X+fJ1taVdx|ao2K1-27FI5|sZw@y+V*zyBCwybj`B z5HoP|w>#lhEce_HpFo0`fIFkd;~uYS)Gy@)558V~_tyi4X4$?V&I0jB3E@`slE_eko6S``PMYYn*}@2ji)>0I^F6;a2qIxnXME zhtaZZVb!Q#%9p(VWOc1=&qfUP`5PeiDG^FpQ~fhxH`fik>_-%(DGJEO>r$%bpnVs!_j`xp%$)Yuh$I;|cD;i-n=FVOs|gm5c*^4t)A9UsKmxa<5= ztGR2`FXb^S+-3by$5XA2`_xO95N^d7o*QNv?>j$}{@Oxb57($)%KP-a-Nx1aAeL&q zucOWSTnV>g49^YI9K`&qa~`Tj{ZhX8#+z+^Jcbx+gV>>ja4UN9+z`Lx25|>&-Qy>Z z;TrWzxqo((&GVx{%x^-t6=QgAnC2knU!C(%HR_l0;GbM?>lNo9=3kxjush*aEce{7 zvBK3k4^^XnDQ|knHMZ{VhZvZ#bzc+Rms-)2=Z0DKe;~ewzs>L+Tiacu1m&-0PRVx$ z{1sXdpW^R7Y*j+I6=QgAh~LV9Sark!^%=I~xJLa_?ixG=vx=XKt`1@Y5KER2Zp9d$ z8{*9Y5bJ~Z7w!Pe~qqAzA{cfze$?zth>D-i5K^m$IWM*ULei23B#1MZ1Yfzs$GQNNTq@`vA4Lk!yo>(~c-5N<_Jo*OoHwL12}oN$f$rOX+;*Wv>Z<5|?4);E+8 zZp9d$8{#hrfWY5|%m1E?YSb@fu0-S3I0Z4rg4hJaKA4By3AbXo=Z2|2UPa5Efj&`< z`lZYj_50hNjTlp~Qr``ttAubXdh*;b5vO5HRWVXjqkbuKXIO3!e+S7qI2dEcO+<%Ghgh9?fGY;Z}?h8RX?4#^MC9thJSE)GuY8I8uK+jQ-deYt{El2)AMk&keKe zIS}ac)*Gw`U88;}^W>Dq)!ulj3qf33Lbw%Ucy8F(2P@bI^P0Ox{Zi%$FwGCnL7qc# z9_>N66=OsODJRREaEWuC~>dS&}y1^ZwR z!mSv?bHglS>t2Qv#s#**xkmj`W@eGrU7jqD0C7tR;Z}^{xnX21Gi_~mjryg`3@Pm& z9ErVfwmQ9pa4W{}+%U~SW?rw@j^i5jOSxtK+qMsKM)4fFI?jsfORZS$nI7J20D<{e z`D;mb=YBmNGrjb;iurd^AI0A=RlkF0&aKY4?ak_Uj@zbEB>4A`C*g0gj>g~lRgDsq zKU!r`_51@LKn(uXQ+}t#uS*EGq9@M{@!e-2zK6d;do=#euWHmU?L+EMolbWS1i~7W$ti|1&sn#U3k02U=J@?FkNY`$|MtG;oVRV9 zxeIFzi2d;0xX<8we%<4FX>arN+@`@N^g<2Z`2ir_C?OQZOzI8s7l$Cm<6D8h!;gDB zFYQhCc)RJAEe}Es*R*I)D2mtB8>a7Eo{dkm8a|nOJTL8;-QR4weM^3a=|p@ge7kt1 ze+i)|W>RmMW#d3J;>m7;C+r^2OZ(y@UTJ!L=ZjDy!*?$C2k{ZU8Mr;6C|*}@nC=|k z?^_vyk>VcDOS`t)i%qY*%$}1v4ab1kt%Oh%GpRRBS`cHPH$g23_jq2~+==Eceidp^ zZ-SZ@)SGBeD2mru7IX2f!_>5JkLRV`_;4-mV-wuRcc>{~)8ikZ|KX4!fm z@Xg%S{o~H%@w~K$UiWyskFFpN261o+p(xf+Z;0P22JyjZ8=m~@9g>RMTta6X%rTw3A55)YK4Pp|$&3dO2LQ%}5-Z0B% zfVlazuC23U4$9+sX+O99*qG<`?fChpazat8q23UGH-Q=#+X#8 zimT5bK};(l6vZ0q4e|R7AeMpl09AY3<9TT>_1SH)?!FIVKE5R#`UV{cMKM#+L4FNl z7{0rG`&g;v@w~Km+wInTXGq^ePlbxc5<*d|q24elRPcN5?~ENs9?wgAm+CFC4@z(1 zff7PdtfAg8eJXx4{vG%(Z})g!)!Sj{uISZ1#hnia@lFZB`(TvrBb@-IgSZ%XemQ29 zdps{~KIwCgdKxvTP{D7;{|w)I-kwktud6pq8Y8pt2Dinma*yYw%@Om);wwx}`UW3> zph87^LQ%Y~-VncSh)-3)NIVp?$~~T!Hb?#;C-g!M>apwrVoC|2C}vV`*hcdue~R*W zUfP_&_iT9(YVhfXN=yerQLLffFw3|y+<{NTPv#!aOPedvjav>w4UVfjK~O2CJ)tOG zS8teQOW;`@geMCvtelX?^U~&uI%DUHP=gvHhl6;fgisV~s5i_quGBkXOdX1m;vUaS zn>)iBFSF<5?p(u|dbos86f>ze#5obfGtis310&u&o|iUvwONZ_70(KqGA*1{?FmKk zI_=a!^8553$Ii*Q?jFxen>%&74}NF=yO`tD&1g?3ir3W}rV|;@p*WA`ggl;?HcuSs zeNfNqHt6qgmGfL4#p~(~vupuA)o`q!bK(uk;{(j&r6#p^0ZzpgZtRz7YIeMhI+$LaKV}6x3R*><9TVbvq+AfdhrOgg0?H@OT7!RVUgisV~s5ivlD1x{LC%$Jf58dN= zX^(IEr0qV~I3xBbao+yvY((>*cFO}lcCb>QGKib zX*%y;A2mIAPNlIek=?s>>m$&?9u2i|_c%fO((OKMdg6x1QA5NnC4{1wNxdOd7f@p& zl(W}|4yb!PFYO;6c(3WG^*Z&z_iW=no&wRggisVSsW*h;6o^fso%uuOX?YEKJTL82 zcbwDItKSx=u`E7S4-hYw5Q<_A^@drt3W(*Q8v0d3mOn*#JTL7#JI!i(WOZs*@`Yp71)*GCdie%so!fKCZ{~rs)?RiyDjKQ>_MKl(JTL8)zkZ=< zxn=o#uiv1?{U9cn5Q<_Z^@eG*U-t3vhGjA0-Q#&_b5}cYJ^rob+o*BLyx|R-mJo_! zCfcckBr*Qu;Vqj4A&=*!J#XnJ;yyS(wu9F8G9`qfSVO%bR4PGi1+CP_<J8J%&=Xq1lVW9%$Me!&Y|p!6z4{TKstH83gisV~ zs5eY2T=k$Ht%t`7Cy(c)ebSUWV%>cUHKv0YP(mn*HPjns*()I4-fZ*Msj*Va<9TTh z>wSB^Gi2GT{|})k)=+PV|BnNrf}b^@s_P!lOS{MT+hQMl2hp41=e80;QOu;?5W1E@ zEDm*G_jq2_n|cnvo5=9<9TUw#0*)l)8s6B5yS@|jwvA&#Z2lA)4F>&Mq+2o zD))F^+8p^!{kA}j>8LRP#Cw>z?FmKkx_ZMlb1;93@_1g_oWYY;r>2F?+75)GSVO%b z{=EdBYHi%ZAMwfD<9TUwC7ONVv8XW#1a{8q;1WVn%%t8hy^nS9WV;OPk=KyN^U~&u zy4kF=P-AthB~2jyfp_A$Jc`%V8{%7TKzxQVbvZ_gdz_%nongggFGLOQAFUuBDj^ib zOzI7@>}TBhtPh5_bise!<9TUw?>cTh{;lO4M85z2@RrR>2t_dy?bJbX4r2Z_aOS$l z^U~%{o$iAtvQKah?N&l4ikZ|KX4zMWToZcqkHwwK<9TWG#F5@dcRZ_eu)6)dgisV~ z6dmN6Al~VFUFCszgYtM@+B`X>aWxU2>TayLpO+AdVh#0%X(X}cCzFLaORrOlIUn&&YG8@YS7Cltl&>J9O4uc)yz zcILHWEs@9b(&mXgtyj;0I0!`d5<*d|q23T`Hy}R631gpF;pFkWwAoptb$2$1*FhXu zLMVzg)Ej2mMAV$a&}<&#QXu^ze-iL-uan{EjY->+IUE!K0q&@p988 z=YG)i#k4IO+Y+mQ7{1lAjVm0rO2s`+(EfIX_nY=!^M2Im3gT=K>z5FUVkY&5_#Ju> zj}2a|ap=sUc@23yFYRHE&TabNf(5A21H`Q$zMj#MP!wyZH^jONVvWtdtZY5|&b)>^ zo|pEJb7wbAxU5H?EL##pBZ#w02t~1mdc#C4zvZ+Ff867FX-~LnX44s~{}wgYM2!Vo zOsh=APkTa9yk2yW-9hY+PqYL+nR`4hZS1j4Z#*;rH9CP92;vVVgrb;9y&?KR5a-}s zOu`d(kLRWR%9k%UJ$A(q)cF4hMKP0lL;Tw-YV^bixf&zIJ)W2L1((0jbl4ihQRDOD z_ikMn#KaOpQOu;?5Wfci;_zMiHJphN?;g)fo4eYA1%E+}?eM8S*{xs0k|l(qn2C1k zAbWwhap!(5O9dg1=cRr62~Wg*@Kas9d%u>UC4{0_L%m^^eE{NsqgJU-jyspf^U~gA z*_L=8KZE$>$W^Mhl@N+z4fTfTok2W1b7*x+ymNUxFKzr~Ta2rfap!$Nj4L4&#Tx1j z@vr9~4x4>vwOfotc|0%eU5|Sx<_AanULck&Ar!?L>J8J3dVh;)Rs7`hLmtmd`^w?> z$2{j8{3SwBtfAfzzn=&K^RLQz=pN5Y`}|$U#(Kp$i1}CLJZw)Wir3W}rWw^Tc(K+I zu_nsnd1-h0?5^SmxUfNl9Cw}<*qHCbWukYy6x?u^SDArJKh*NkF*Y4V{#XX)^ z^`=hSvNi1=8==O^B?Rw-QM!+G0@w&Oj>Mh+fLY}p&r6$6x@pb(QDZ$2e+ID}W^Q{z zQM|6+Fv~UoF$VAa;~7J9LLSdcnze%(8wUI^oG4j3?|K&r6#t>VsDdL5&Q= z8+d!OO9(|VQ_(>#z`DCFM#xPVDem#Sw7E0%Ut>6G@O>N)f@7;ap(tKgZ;0Q(2C<-T zzm^R#;@#tUX>;#dBx7I8{o`QFjR7TuqL_(x>L9s)9EY8=e-QF`UfSHL(|zy^hxymQ zdFZ)3ir3W};=2<-VE$D&58dMgZJs#N``{VwDy&tPmJo_!CiRACMxC3^K6wp!JTGmY zoYJ_epvI9nhh7rz+zCaohI&J&9E14q?K>+!#7LCK^U~%CFwGCXbIiXA=b`8FC|*}@ zSf5c9?riRHf;LaGX`XYB+5jilZ%YV8F_U`3bcQy zoE->7v4(oX;-vq1tcmh?UfS#|(z+X~XyX?pgrZnOy3jOO_CdVh#0%={_+38ZU?)M;^~h8>d$M*gn{ZeK6nEoKO^Ns5h+dgN=KYbax_D zkDVUwe8!QjKko2G<%9jYHF)(!znj+7ck%a{dOx*ZV_TvJi0tl{DvynyofGOBouK`} zxVcT6?J^oQHU#nAT`yJsRzfI>HPjp8ui`zON64BNxfl~ZHZ5{0Y1_E7sll^~d~|lh2N)^taf0^7YrW94=T=9dMk9z{VN8uIAr!?->J7838N>vP^r0B> z?(w{|xp(z@W-w~}8bs^9-5MS*Ar!?-v{MI30<)<_ggl;?_UrFF5%;kph*S6N)}l}4 zgrZnOy&=9y2gK2j&ThFl?pz+vOMAq}E%83K0&(d0*)7kM5Q<_A^@jLuTo4bQwq12z zymNUxFYQZqoEYPZqvRhT=9CbMO3z9iBuC=P+3D5KVkD|-^t`mUU-prh9~|vlf%v+F zP!wyZH>}UWs^*|Po|pEHe;#M^9MPqOqF6({VVZ-OP1W6EWst}7(w=uZz9~OnuQtYg zEcN2J>fR-UqF6({VVWN+PJFUDC{{RmJTL9l_81%M?)Iqh#)K!U$CMC?Vh#0%S+*^R zhwpl+dUUMR@_1g_kIuh4-x<n?T=cUaNv&%Cdqs9)XF&poE z;}Swq%%t8BO5^-g7`u}f49#oE<9TUw5c99fdFZ)3ir3W}wwZ%DA&(QZ zIfFmDVQbXjUK?|;1EDC^P;Xe@2dmfzb3z`^OPedvge~|zsjHzzFWkcsn1`Orqj+7t zA#{E~T#hGuGTw=MoS@AWb;~Q*b8;2s+xrCXq&=Z1URQ6J#_l|fkVzOR?(w{|xijp$ z)lsOy6WPrm7P`A5p(tijZXjjS#?w&Jd5UcE|2G>&68}J=l>s}DArJKm}V_c$P2~F zAdlyz%@cWAuXLs^BNW9N>J8IAxHwLgH^&MmkLRV$&LXY5Jn8QZ;_4DYQLLff5dXFW zVlDJI=fp}akLRV$4k_&)oP(Hu70yG?*7~2*&#QbhWMXfxzC&eN)0zY4G=2Mg z*T%NQTo8j!I;-;5Jr_5)#|heR{OX;iroWCvjhP@W0ddLLj)bC^NxdQdzcYw=OP^4g z`NHhHhCH5^_N!aG-L!76*HB{?h^IlER6;0;+~av^58HNn)2XZT|3R|GFA<7jCiRAiXv8Nv z2%pS7o|pERLtkyW_k!(FV>)W=3}Q+Np(tijZXWnyh z3umt9@+e+cZm=cWCt z*Y1mTm#gTvAZ{ul6vZ0q4bw_}=}Bi*hsR1SkLRU5=jMC!ogvHKLXGo5oL539iZ#?5 zrWy;Mfp46S9Y-F|OS|Pa_r^ZRIf(gJT^;k#b9of6t2a!~ip0br6DPUH3DtY``L5`r zxJNAjaXRKJ9NX zaUgEP8~g|6p?f?pZH|~Oy zlgiOP6~wPF58D%p;`O3~Bry#$YKawk=Y%|-mo{hch}HT3AY&h_VlV7KD2g@I8z$m= z+{3l_WbX02w7C-9cER?j!4>W+5POyoiejdsgM1f66;JjLc*5@SytKLQR`=KyHQoSm z4TudocO(?WOzI8myIKo&wY-Kro|iUvhEKoe@78j!y#ZrtzY;=GtfAg85$m5gandx5 zc=vc-+T4lO>a{Ow#6CEQv#LFzC|;+XI!F?Go|x~PIU$edrOlnXxQ|sZ$8jF*Kq!he ziVl)*kmpeBYB?c~=cUbaN%1~D$69r3385&~C^|@soq3U18RYT2w0R;g)~oBemzNNVVh#0%^?k5{eK21W zJ3wkzu=_wGfqtI@w~LzA*KC;BXIzT^H-=ckrl%vT03sjd{E2s{V^Lb|l6ucW=X)!zcE3j}x>{zid|1$NQWcHBJUG zVOU2(QOu;?Fw0u-sb&ot)3C&lZVm47ytHRdnc4K!f>zWZ@eGLC@f`_8F_U`3MC|*o zkqsMP*e|akkLRU*^&xLIjeOxzBw{XV#lZ9wqHb9of6t2a!VuxUwGoUSa&(k-ybxl<*gDzQLLffFx5C}xqDms#M&;8=cT>hfCuuO;r}NT#Tx1j z6ES(%gDwAfBkefycwXB0Rx$kW-$nVXJ_WJC>m3P2u}0BBikR`n{Kwtnc~$TJ{)@Gy z8ZV;8VXt>2cpr??eWVirYg~wDb@1?slicHZY4b_{u+OOK6p$Me$W48FeWijxy@1)|?9Ar!?->J1a|Gd|Jo_+;+!ytEP7^wCZm zpaxg!&R9!kl@N+zCiRAicp2~F96Vw7cwX9EQJ)yh|If)exG3I574xt?p(tKgZ3s~u3i?*OL3uncZJwNpadi?-uG_{aaY9k7q24f! zt3DU?Yq%{&qCB3LHqVL0{I~$S&6y>HqF6({VR}}7#f~;BW|Tahmo`tb#XSEO1b*^& z?u4RPL%m_D@gR2QyJKaL$Me$WiM&{^xcl=I;JG}C*VP-Q8lT`Cx>Brg@;E`8okg+k zu8cFuQYD0LAj9KL# z&r2KsDu^H32OB;pAr!?-MF$!CU<3BS4&9vy)nliZWmG1GDrw`>b;ZJ)YphNk3us2w zq(=|c;MxkmI|#&5AZ9{&@uN^6md6R&P*JKSJ^Fb;yj(&kY5{Z7m%Jk@+P!wxGhqtzH*1b-s z;kbUN(G!}JD?*R{-=T#qkLRTgt)yDgqu(5N4h`N$Xz@0BE|21M=)54XEwLeXI}S3@D#Uk6s?nOB-5A@jkZ3(_I-V$FIh-azat80qxv)AHM-{^p&qy zPl-1ukLRTgt)v)NL!d7IBh;GDE+G_^p4H44S8Ia!&(2+1p@$u#BzZh9ZD=LM{0JT1 zR_O3{AQZ(KP}`09K~-I9@Jd}?9?we~T1hd_+w0Lgp(xgX+HTDA_ImX4cwXAjN{aQW zy&k<2iee3D=f-;VF=o{H>mAv;Y^;g$cwXAjN{V&&W8693Uh8j42t~05)OKUty&lBN zP-=cRR%&@XFKwtOLYtDkJ5c4J$l|b zRjs92%uhv+6SVoHlP)quB9@h@L@~^1TQI9@(JTGmos7e34 z2|Ld5czcK8EqX4G;&raBNsoRMh=s6HKO2ha@;E`8J44cOe+r}hN{p%ZO9(}=2G{)Y zSKWa7xEREEJTGWf=buU*&r6&8V7VT>6N*arHwAO>X4K#uya97uH5f&Y=cUb^I^D0D|a1T!R(Fw%r(4)t$mJ{-LUfMjDr1!BCcFt3=R!NWE2}Q96Pao-h zoCM-s=+U1QZ%`i3OPeRBG_D3iUH&?(xqmJp6qTOU!!fQd12G?Gxb5re^2y_QY4e0hF%1|}w(W^I1 z3dB&=ZM-lPh~;sDHnfszNspc?$0vX|s)SG!Kb3mJx(;t6ba-<;dU-rAZKx>Kk{&(P znukGi^6C;oQLLffu%jNmJf4>}w32G&dh|{xiZ#?5)^&Irp~Ktg9?we~DoVAaN54Gu zwhu$}S|x;{n5pO>Hw5u(D3i_#g>HE~FKwtO)si0lNqAQ4fLH=Lpq|U4cwN0A`aux0 z@MNV&FOL(np`uhP*Q0krQLIsPknQ#8R`|Dqm!?(w{|p_LT(5jwmr(BaK%D3?dEhI+#+ z`yKB5Yv|Em5qB<+6SSd~6z_uytIIhqr41FO*wsQ+x3zDm>N=q))=+Pl#uat2hlFykJf2telA54C)vywR z_rWOLM>+v;^*I;MYMoFZ=BJ{^^U~&%PP)i?x_g%piqiXtlMHHHjyHJ!a!HR~U8Cov z%@LFIoi_$?8Hmv(grZoZ=pdH|;d=D)cwX8Z`Q>`_PAG~s)Ej2mKTuVeIP!wyZH^g^G<5RgFy*!?mHqTe(dh|{xiZ#?5Cf)ER zoXGwgBT*jDOPeRaG(R}n_XEM1>$yCN*VP;1@6|wHHZ^iqxyK3GJjtec9<#PlvsSr0 zikZ|K*7w1>9=$wH(B_G}T#w!fMX`o@!z|+p=X&(=cwXA}RFrDvdh|{xiZ#?5 z)^&L6di3&mUfR$~s+H@}JE17nP;Xe*;jQb@%j0=zLq(~U^yuHjv!Z%Eba)#*mq+os zdc(R7Z(~y^bj#xeZD=Lck{*5N@HRq+H?QG@qFAHoAgPN?O;+ge=7c<+mo`+CYDtg& zE)d^>pbn_#@+e+cZGRFrDvdh|{xiZzN3vb`R?Jf4>}ceQdo zdM6ac8nk~=k3RQ!UfR$~iu)+hqpuT+VvVAMq#pe^C=hQK>hkhRmM<{)*jp@*Fl@_1g_T#1ryIOiaBu=gt=6vZ0q4YTY} z5IB=mFAJq{c|0#|uBb`>d^T3<2S7YhLMVzg)Ej2mvmkE72-!9i)8+BJw7D~s>(M)* zDArJK*inyO9?wggyIQ#(y%UOJ4cfn`N1uB)bWo|iUHvT2^50%FE5 z5Q<`rqJ!k_?0WR_cwX8(k(cYyJE17nP;Z##Am$%?gM8hU$Me!=XOY%jo?c13P(mn* zHPjns+5RAw$JuIntkm*&UfS%C(*B{YXc3&sJeNoDx_ZNodi3%*K^v;Nu@A0`Pqi6( zwJl;-b3#$9p&kwz3LrKCF(r0Rc|5P`B|ZA@La}gMX#FZL)heJFRg)gQdc&mRIuy!_ z+lB(MJWkMtic&4<(NpF43=qvFgrfMV)Enaa^g;X#&B=X2Nm(AxOB*UmwWLQ+wPtEg z4lN-R#Tx1jvF?I60!o=;OD2g@I8)n%#AfAT~cITl< zk6s?nOB*UmwWLQMI=qe0;%)R?9>wcL2RR2de#9r*44=$BPSA!{QZ4DxUjyPh5JO4` zMKP0l!z}wdh;8s>cMPR*c|0#|s3_Hv9)0NWR-nV1e<~*w#TrEi89KZb=} zRFrB-kDjXR`(jM(S3)R?HPjns+2$ZFhaUazq5Lk7=cUbEtz3`Z2}Q96?Lv?Khqik3 zxySR;hE`JC$Cmh1Er*V5`9q;cUndmB8tM)49dsZ%L-};CxN~_tFKuWg#rs$c#3dk( zE+G`f8tM(9aR_30D7Zq=JbxeZcwXAjN{Vsy5Jt(xAXbY};)J4DL%m^^jR&z7^yqhv zktmPnr41FOm>;3TTZIm9{;8Z$6lJ9NXCLjht8F*@}4Dxth+R#dh^{Txdy%UOJ4fTc{_2}jCytJW}6zeW^syBp! z{eH0~I-w}mP;UtJQxIdI)O={H)be;<+E7u-cZQ@0O*QDFO9(}=hI+$P;}$4RKN%Xi z@_1g_P*I9~kh;D*NRtf>3L~$#3X%Z z&f2e`gS}yBFFT9(MkzoKO^Ns5h)@ zVYiOOta6X%rOg?f^tM9_yOdBAGpRRB>(wRrM7{9I+~av^b0tc;;cMVNE(Ot}gisVS zsW-&=3dB)(vM+?vxICVhHdoZ7f1ZKp58|T|LQ$-t-Y`9@%`ifSV5GRm^U~(dkaXN9 zW0brKJ^DLJ2t_fIdc!maXJBq{9=gZ#(&nyKu1Bw29>q)~QU^&bZ0cZ}9)0d{f;M;R zbRUm`cpv9beJbVhDArJKi2siR;!>YxQ~(8I~rpo%Hw%y^PHIG$7~Rj zK|3@f_HPjoXJ?aqb%zulOK_1Ubn7k@7kLRTg6{T9a9=#KaVh#0%I5VI|FDPNY6pGODcwXAjN~$G2 z`emRwxfO`JO9(}=hI+#+>jq+BXn^v^J)V~~RFrB-kDgk;T@c;3gisVS6&+;g@K&J1 zo7a%X^U{WjQmtH%-U&sqhI&K%%_#1pH{Jy_S@Rn5cwX92QK}_9`sZ;U8-bW#LMVzg z)EjoxqnF3?(uRssE$PvR4sQiIy!oecLQ$-t-Z0A+!hKu_J^H0W`CT5*OPf1UQWK<> z>7k}a?}VaQgZ3}#(dQn|OB*UmaUawsM~#-{3qATep(xf+ZBc|0#| zC?Cc9pdS595c5h1MX`o@L;QOQh>M}%`d++2c|0#|XeGtC>V&7eG>DcGLQ$-t-VnVS zh^L@xy=9DDc|0#|s3^t!psMbP(5~I5gisV~s5eB<2?9F2tlIg@twBK3J6}beP!wyZH%!{g&q3jM zn^+U&@w~L5l@#kPpYFpTb|@hf#Tx1jvs~Hw5hyi}iIrL&&r2K1NBPcB5Vw>Niee4* zhIJiY>S5S1>v6vZ0q4Lj=5%j0=fFR2Osg!j=EKa)f2*9qQ- z^yt+a7I!{66o}>VytMhGlP)q##FXpN zJE17nP;Z!JPou`4FcP;3MQC|EFKv$eq*MJSh&@4cDj^ib8tM&k76s9OIk$fAz3mAgeurrOcrK6Pb@hf>Mul#w%b$!-<{l?#b0sR*qgO7EVkY&5NsshaMB*3q=yQ(~w7FBK``{eJ{A=Jm^jsdr z>qQ5-0Ff&|kN*C+b9tPg%@aqVM}H&Ms;f%~MX`o@Lue0R6@3nR^jt~Z<9TWGcP!uz%H_WmZ zLCnSp4R9Q(R^O1Z}7&)ynngolq1%m3qUDdi3&mUfR$~swF*o z>Yr0BovP`c%cFQ*yB|ZAk;jK^y)N^?hud6p~qXC)|@;E^o zT1mA+kDkie{PA2K#p~(~lNPq?(aYlmZTtmNE$Puy1^fWq!(UA*P~Z1k76bgg&zGAJGarJ&pl4ihE`JC z$2@$h^Poq6N_;Bi@+j6&Z-~Fu2eBuVPalapm&Xa(&`OH;u{hq~J5bKPzJyQ|Yp6G@ z>+n`NtK8#xX=A5}am6`E9qckfQOu;?FwH^gU^m7{l*jYZhE`I{kI><*LWeh>A5JKW zHPjo{=U`orULMa&8(K**&qIf|3LW0Oh7*cn4fTd~9p1XSygZ(lHnfsry$T)Px`MqE ziee4*hFP{gp6>NfIPM)QoIIYFHnfsr-CYL66CgG%Ar!?L>J2;U(aYm`X+tY1-x)gU z(L13i)=+QQQIB38&r2KMFjY%`N8etL-U&sqhI+%g4sWaU=;iUes#mT@?*#8ddi3fI zlNPq?(aYm`Y4b^!>(M)*D7}w#l4-9;uddPa(&mUs`p!M@&Tqv#|2njnolq2Os5eCa z0b&iPT5lbS(DHa*+8p^wr<$7Hn6cHfO9(}=hI+#^&zIkFT9rTU@w~J-g9|zeOlwI`tnF8aV!Aw@mp1p0q~pFJY8(dQ;1WVntfAg8ttD&i z)~{u~P=1%k^U~%{RIW$wgrZo3cA-b#x2+z1?(w{|xl^b6$VVcSvwIeL^mRf}tWk83 zTtyed3E+gdb9p>3ZJs#N`^Z4t0OFbwLQ$-t-Z0C4!e09v4(oXEZZH#^U$MzIYy#9o|iVyiD`cD&iBF@ZduGj&*f3PuHLY|57zbQ z<#B>G&%0@!uZbFQ7R_rop(xf+Z}JEU?wdM6ac8tM%@>e0*N zd1*scx7KDKtn1M`p(xf+4_Ds@>w5I^cwW^@dh}Ecg*tF$d|k0HRi|17l%Z65<*eTq~0*gdV!b=RqL%zOM3M3cwX92QK}_< zXX=bD2F=M)C4{0_qv#;12)!`0Gyfcl(DHa*+R#d>B|ZAk;jKW2x8k`xir0${(iA;& zLLMh*Lq(}pu1D{LqFAHoAlvKF%j0=zLq(}pu1D{LqF6({VVNF%>McDlZD=Lck{*5N z@K&J1o8P%|c@%4?H%xlMlb}ccS}3N=;{}Lx(rt4V+LEYp6F& z8o570qx!qpapdv5w4tID`yh3yp{iS*S3)R?HPjns*}6gex~@l`dP~o%dPz-?HK>EV zMhU_DkRH8y!*u71;?9o<1!8$TFKs^Qq>IdVzAA{vN(e>ieWa5Nm6U&rH~1!Im3urd zZH}0v?@aaVRX_|ZAr!?->J94}(p4!!%j0=zbL1B~)li+TE*z@UPAG~s)El;$gZX{P z<9TUw1{ZqUu1D{LqFAHoAY&h_>(R^Od1-UKD%YcTLQ$-t-mpxMKJ}KKmo`__q<`KM z?*sF%+8OV}b9of6t2e~oG=TUCBjklpOqa(A+T1^qj(c|y4}n-QRN0+S6lyx+NMYEgrd^@se>%hqtAOw&r6#-b-E8~dT$Cn`fmya`#Pa0 z)=+Pl=HR9iW;gsVo|QbFmp0EO>3#5AawyiSXG#b~v4(m>{A~t^4X}b@AI#sNJf4>} zPfmp%{bED6tNfvaP*i$W>L5Gn(I=1RrOgvyF+bYs(HDfGSfl75?JSz#hdiE_HqX1o zJjWcYE7&`sDArJKSYJ!(di3&mUfMj7r}e46Y5(9!rUv4` z5<*d|q24g{QIF!pm&J}FkLRTgRo&PJIT9ZS@%et;a?N`u6vZ0q4b#{q@mxuFCqng- z9zAt} zRFrDvdh|{xiZzN3l8T(M)*DAu6; zi+c3A$Me#LR#MzYi5`8OP!wwv9V7|YqnF3?(uVR;ybnHI*Q0krQLLffu%jNmJf4>} zw32LGxgNa}ieinTgPe{}<$Cn;cwX92KC=1Ydh|{xiZ#?5rujh)Ui{>9P#(`q8(K** z&rJ)v1EDC^P;Z!O906tEtz%`7$Me#LR+6n(u1D{LqF6({VO@u}u17DA=cNthqgZ#_ z>(M)*DArJKnAY9DL8*D=Sli|CytJXBl2dQlBdh|{xiZ#?5)^&KRr-s(AJf2telA0jZfvJPNLumav!TVs8?jxN5IHRb8 z4L$5!vshiD=cUajU9Ly(grf95(n*F&%C1MRuF><-=7=fuon4RK2}QAndc*Xr{*JNR zDHNgQ@w~J-@(Z2nQ6LtCg1r-pVh#0%ZRTLEY%P!HrOg>!=xxWW?La7sHPjoX8m>n# zkLRV$m8e{g-U&sqhI+#+Yp+KykLRV$6}8YmcRhM16vY}v2TA?&?VxHcJ$iXOFKzA& zg^s)H(L13i)=+QQQIB38&r6%TTDcy*6N+LD+P|nrpL;wnZSK^?eYDe~uM>)54fTd; zk8(YFc|0#|o;Zs4;d=B=D2g@I8)g~bhwIVH<9TWGHPjoX`Eeumz}G^LULMa&nc&v|}RCU|#gLOT6CltjR>fzF} z`W$-ngNGzNdU-sr>J@tQPeKR#)7O$>q4H9t5IVdy>CvkJ3v3=zlg)2h=^Dmo^l3YlR+tXDDay7wXx{(UA*Q0krQLI7x7xn0K zkLRTgg(R^Od1*so*WQQg(L13i)=+Pl-p3wLaNRi6<>m3b zw4tyYC|*}@n4T4Mcw3;un-lUlK^r=}v0m|6Z3E)Q5<*d|q24e( zt4YvA{xDWJc|0#|DD1|%n=3+_9=#KaVh#0%={~Sh*Y)V-@w~L5u$%7;iMR{I7tnb2 zTpq>i>J1a|GgPhr8ydOtI6)hFxwZ6rGNG#5awfE@J(oxEx_ZM@g9`T2qnF1C)hqPq z7l#h^Qg0@8U?+ID(xX>zn8wu;xbvGsfmj~TOPf!+&_%u)#PnfF!QKf)=^3Vz4DWnd zs9J9wO3LaQJuhvJm_pzAd%W|{Lc!h%MX`o@!}P4K!blt*iqP_SUfP@=g--P?Af}cO ziee4*hN;Fh%%~m*CuM7SJTGm|;6iVE0to(iE|21M^@gd&bbO-z_+;*Jf;Ly8q#Mqs zI~T;{5<*eTq~0*S^BH)u2Zz$QJf4>}SJXoP-1X?4P!wyZH%#-~_2}jCytKJ9^exq+ zcS2FDq24e(E7zl!$Me$Wu2!x`?}VaQgZ3}#(dQn|OPf1&aUbpU=<9@{SVO&Gx)0Z* zm&fzc=82(M)*DArJK zm};_IKiZ#?5rW*f7=XK8;X~&Vr^U}_;2WoBh!G%|M73N({5S;1kWXNa7O$uW|ik^8`Y!vuCxA*zpfb=HMYb% zUkbB|ggj2r9`oUKwXf#sy$Ie^=STS)f;LH|9C|ZH-dOG2zfj&?KgVe zRI9vxQ4mX@Pn(N5!WvE#Q9YU$WVhCqzxJLWu%k8bhlD(ym-ZIV-B!D)>n%ZCi%)bK zK3RLBi0aXtWn*gtf2sxXAc(VrkjL}V9)0M&wbKVo2;vRAi=XjMSi^}Tsz>wlZ#-O^ zG~(qTHp9Ev9PfmLJf4^K3eP`M+o|)EAodtOvG)Ybk@iFp)uZ|9ovO7LuALdg&LAEM zLLSdcd*vspwI6SPDTu3as$6XNgLw@niYVUSl-f@V-Uh*y`U0FPdj=to=cUc--^_U> zh`E@tWkeCxqj~Vem+U@{oId~Yg`8_tOL!TZ=1 z#B=ei6 ztm{YAM`A$~Q9YU$TJW*Wk1Ie73ql^xOMBWj^K5?n8~f88F{7L)qIxth`u=}yo<9rX zmLTNuytFrb>I<9an13ytha9_36j42z_xsEDwq9ZWwQwGikjL}VKB(KbwqE^!6UKY7 zCOT0>^=Ll+rXOwH?S>P^DzPTY<9TVXu*eUw?s9Fv0sY5h%qo5=CyJ;Z&D(6SAYb#- zO1&kBiRkV~$m4lww;ugt>h<|Mv?q!vj;rj6w5yT0AH?gJxg_NAytG?> z^Hc1DBDTRiY)=$X>C;ZQ<{!{;Cvg^P{5uHV2R)uw_0FF)Du|77=fA_O(tU{FeWa-L z46omQ)yZisc^<^JLGbC)<9TWGN&n@h6@tM0YvDX(4JV4IGrx4o1i%j1<;zqKHcS$4l4F1i^RyB!~xs;BG*V=cUb^VZrS$1u+&QeNp^-25UG` zMDhNnU`EXb!TE8`Yx5uHJWO|}i7)2762uyqv1LRNmG<-EK7PReW#|;2io3J! zLj-GZr!MZ}6|7bF$DKP-M5WV5dLMjNB*q58bBW%E2-e_}Pfo?S>V8qbhBxXXu^@`5bQ&z?2mW=XVNeh}Cu)9(U=5xC zi}`UYcC;xmqns$B(iydw=dXZR8~-N5ch1wR=D7&g;7PWa=cBPR|0h-kCyJJTg6DRvS0Y%0C-P#w+7xG!Zm}jhQADNwBdxo9gR6n~Ce}puA6j=sum<~&wC<8n zcgH(-qKHbpPuf379D}pfsvEw*VL~&eQ*>+cJn1${x z&B5gHytIG&%*b}c!u6fAAd0A>hf8b86ZllxoxQsgp?ay)yC478^0|}Gs!YB2;s*De zdER=>$2MG3JL!;1^WL!N?(PHe5{MUrkjDwy3(mW?c6Oho`ru3JKF2yIh51-6) zc@(b~ecMQk%cFR`=-VCzaRlDQ$IB!_ z9w%sjIsVbwVxP3228m-ZLT<)L@mwCo>qX!82#6sd#sndc6SSvq-&)&wsb^4w#I+|) z?7jA|^YR)_D2g?>`=suU@8iIeC-!a#LLSdco7eYW<2lqI@#;wvCzTP3VvVA2~9$D2g?TzKx^g2N1``D3QnW(!ONJcWhkUfB7oaA7dmsp(xfU`ZnIjc_2;< zLLSdc``j}=jQK(0^e(-t17Z$3p(xfU`nH&ZRn1y?JTL9(4}TW(oO2NKugZDoxjZU= zR`u?VH68_VO%UqnoS?nN6JObS)n(Zes$a$m=Y*nIqv+cnLX8Z>v>@d1ytEe@_Fb&I z99Q?8d{*_;SgD;*6l)ZH+XEo58&sbTLLSdcd*l=I^PM5fxPRd(^wQ z^S@zMc`lFQ^`dW^0OE2Gw*?`O6SVoHhxS=&GX8=Z#KdJzsNR5C<+(hH*NeW5cfKy( z`Gg?kae_8S%)mAJq6P`qXzjm0>>+=LaE==cUb+ z=%gj@M~(3yj>40jiFe|;Jc`$gzKu0TfcPK?d7Pll6?LIcT2O<;zc50s#Ypj79>wcL z-^N+{35Yv`kjDwy+!=OT>KW7^@jZUec_WN?&*f3P&iyKNcN`_>;&-Vz58dMgZ4&#e z@f>Q9Sm?xj=j=czikZ}frQLZTi1ng|Jf4>}cj|N>+@s#W%5y{9xf6IilH+{Np^Zk!qTf46R`8ln=EzA7dVMxg11nuSCyT11MK8y6pvhDGAkkj!O zpoinHa@!M%;`O4t+Z4od6Q8UcAA~%fm-a5l-59^u$G_X|f^Ub}4&TqD<55&A6!flw4Psc%c)Uor^9 zN!U`u;n!91lh<%UQLIsPckKyzJTL8yp86!_Ilo(E6MSFBfw3|; zp(xf+--hpQ1JN7Ag+a*Ud1+6$>dRQK)&|iy@yY6wvBEi_DArKlmcHMI-xM-52zfj& z?fOq)Q?FmKk zdePm*U&U94;&0sD<9TUk+4r#zaxKC9t8Rr^)t*q4YNy?qZ}2A&x8pDG-Q#&x?~eZG zqaWm*XZ$`6%&PVT?}JgiUUYZtGaQM_JscbtPu zg19yac|0#|j+mbpG@=G~oCPn8tFDPz<+(hH*Ng6s&uV*&-QGdS;{qyAsd1-S7-`sT+YH;lS3ZJMaKAGq8C|)nRJDvbKfmk~Td7PllmFVrA zZbuD1-J|hj`JGFi%cFR`=i zMRynbU<>D=dz_%none=i*mLp?j>bsmh;L6Qir2YcrS6V%@IHKl8NO>GC*<+Gw0Zr< z1+Az-;zZ2YGD1%tO!RQM|6cEzR2hf><`jt~^fA<~cFV4?9`rHJnfsYp8E)b9&7Qc|0#|o@CQJ zXN{k6s$4Br1}7B78tU7!tO8;Nh>7@i825Ny+B~LkLRV$4k_&)oF5Z$;yWRB z9Od#TW>Vi)|IV|@iLtB6;{@$2yEgVg&U1XPT4hY^oK7f8pSI}k9syB_-II6-^%54YC3t~3}mP6V+7zJs1Wp39?nz3A@R6Y@Ag zd%z8M*Z$J=Qq(vFHKyVdHRF?cE|22%qPyc8d(cS$X#5fR#1|g3VwEGU2P&@ur{-*37Ks<&K(i3CLb9of67v0^dAhrjw zP!RGsLHnuYCf5e8#GaGHAMyRv58mD-ui=EE(*3EsyBx$WyYy?gDhTdm?E5?~ZC<~8 z=A)=_8Hf#b?blL9D2g@Ix1~=tbeDcD4@V7oJTL7XzL*;K!FPT!v><-MtnyqQ#p~+Z zvg`m5CxKW$o|QaK(0+8x>+wDYfj9`?d;X_*gH9+aJu7v0gF*BMv2%TtB#-B%J#xmZ z7+1%Ec=PQ$tG}<0#DY*1Yp8F_vI{^w2V%(}#oKO^N zsBg=%6F_VXV$UGt@w~LVFZOZFbFK_K1~2gzD|N#F^*^hlBVpp4AA}N6e_1+fGia&jA>Tw_#R! zE|21M^=;`59s=TyAmnj^Hb?&ID-A}C*ww1o2lEwcLcgNLdG6>#_dz_%nmFVsMH=@R$K|F{RZU@Y&_JpE% zz3A@#2I8AHhgO#lLLSdcn=9(zSNWT=SA#eJBjhEF6wl>Ryso}2ol9N?!Lj8YCunp3 zICLfUoZLUQ*|}fKqZsk+2}SX``nD|Ne%^w)@m>(}cwXAPe$~uJQG@&WX*>68c)x^D z6lRaS`t0 zc&wn^;te{XsPwGV-Ekj06~vD9QIb5Kmp0E=Xf6#B#Qdvh z?8@VLY4eW#UfMjjr}b(eh`n&acnI^*b9of6t8YuI=&wO+8-zSg&}L_m*4@|#8?g`O zHJnfsYZTobcZ08R8sizuJ)V~~JEXLKoDSkXocQ*{S+PB#C|+0JmSr3z*asUY1tE{; zr9ESp>unz-aWKxjp39?DJ9T$_gO7kXI|%(BJ||Rf5sHP!M~9ST6{9oS?nzdpFkpIp}lL7(ilRkH!{gbb2n2;`O4t zI~l~bAX~$-u%t_;3Na$PUu>m4~U05WoQfLP;S*hhPv*Hiir0(o zZY+q+K%5bTJWkM_+5N%Vj~D(OH68!~rSZx_c*35`qjEUE>ggUQXn)&j zBK~gsR@8V3#IewQrK)FpLQ%Y~zAel40P!Nm)czP-?(w{|PdIXNZOmR{QDZj{Gd~>O z@FY|{+Y^f7b?#TGySo^~NGRUozd0d~=cUc-YtFw9H7*2kA@o1--wuSLSfl9fb_FpH zs@70i%?WutFYPO@of`MC7l{8s`Sh^3b0-wV8tU6n7sOFeKAjU!S02wxyVJL?#rxnJ zJPLZOdV@|ViZ#@?;Wq(690{URj1qY~FYO+0zZK)^9uU-uKP*O~6N+LD^=(;pAc#vq zObS9C&r5r)wcd^SF%ZP*m8|uOn1fCziZ#@?)n{!!bKT>4X&-XVM={UOLXBIX^ZWZ) z8I;STm`QzGmK_J;UJ$1SA&(QZ7rgUntXHRi*lJ*p))!-ib3#$9p}q~hGl&g9JP?FD zo|pEQt9=>k?iC=`*?jZX9#%v|?)UfLUW{VLxXvg}q6gYnY` z^RPXkC|)nRyL?80*!QDE$m4lw?^69L_CXQ1V;*`gk5cWlJKu)i!NRJb$ zH+O}T(5var-^M)jTpq>i>f5sHa^&9#&uU5#@;E`8Px_ugpQFb4AlAbhoQzrJxjc&3 zi|+0pAeI90L=f^gL7O9H_4%7k&ayEeF2YFciCN{jJc`%Vx8b)9K~TeegCOK_f;Q*J zyf64yjZ|yi4s);{ems{)@p{qS-3a1Oh~|%boS@Aad|syuP=jx zTb3OR;$I-f1R;;-rOlNnyXfzzaS#ZcNvb%TZmj?FmKkI`^y8 z-El^pin+o6y2taUJ=cUbads?rq2eInF9*uvE70wAo zv4;A#Eb9+qM-blyA&=*!&Hf{;yXsih$2|009>weG+wiZ0sL>0ju{UFFm&Xa(?2yv_ zaXN^rapGHJUfOY-P!wwv-CaJTK>R)SD0w_D?eR_jY`YIO{yTO~ClsaoNZs8~e5z|u z%s>e<*%jTcbrS*)deH)h@xPPUsr+f4If4Q-C$Y#gnbkW_dcxso{!$JHi zh{974P^N62bNJ1*3vPNJHC6*Lqi?0LY3R7Th7*cn?V`I|1jJ_`dIwQ>Ja2b=&&(~g zMMrJaC(D)r@vEPEHjbY8MP9=RMX^TF-Mxf6?+@a(APSG??cV&y@psgg8UH8Lm=2QsLGW3v_0ibcee3dX6lbFb?_n=|vbMR3C|)nRyK6vned~+L zkwFxmf?$msKYg$^=%=et<2n$h;>m8cTP3gIgrZnOeOs1|0&ymYZGtE~p0|7R;@3>9 z4L^$i5ArGyOAOk-@(4ys+gwEyud8pv?`7Z(o^a6ql>>q(JO#n~xct7!wPP0H@4apb zVuiy-HvE3$z4IDQD2g?>U#0HuEPSeYM~rNEI*7vKdAsMtGNbN9jdMX9aoEU~f0q!X z8O0jv+tPiEJYrFrB6dupp zy?Or8uf_Yg8pL5k$5ng98+1ZZtf9Uw%N_(V7{oe36duppz4_oSZ^gKJ48-J_UsR8X zk?4e?SVMhVmMw}mI0?i?K@=X(+r9anmFLF%ATjo|uKda0xf6sx8vGgde! z6vZ0q+p=s9p6>S`Mg&oKJa6~rwXgp?)?KbXS5EEQx_+$GPAG~s)VJZx0OBSPM+Q-N zJa6~r8E1W&?+p011ri(Y-8%R1kqvEg6;Zribay|1I2FWf%-pt~g5W%VqQ`$@ADj>3 zWDxTXAKB8LP?Tz?-I*hC42TVa;C&>I=S}sRHaiBrS}Ta#aOVqSR<+GlMDcpj-SO#O z1!9dL3Qs}sKKP`szUh6`;2Zn~Z}1Y#s{e;LFo?oa5Ujxwv-GHq zCTH2RAO>J0K8#t_HdhhF>(qr!yf?y5K;Bo8nZxlzP#u{&ZQ9S^ktZl9$ir3Y*W!ajTQT=fbTL)2i3W7Db67~P- zD%4mTL>D~SId~^+a}`m%UUYX0foK5nMG%FjAXtMd>d>S3{~$Tf7sm)W2_vO#t|E%p z)wiMB#+^R|;`$&8PeHH-cZOpZxg9k)2fxKg=R9nitBB%t^=((ve3XkVa=eaaL&I9o=_CWmPHJspSl2NRoz77A! zy&X|_Ja0Oerg?rTh?B50FNt~BHdhhF>+0Lm>N5z$J+YP)o`T@};E6n~S6tyToG`A5 z70wAou}0C|v72}sy}@Qd6duo;`h>LZb^&oLPD)Q7l-719*ncpJHPpAI(LM~sqOrCY z9?zTlowR>^hx<4MC%%tk$8myv6r)%}eOs!5+0^)65QWF{c5iN&aYNgEu<@zbYn@P( z?jv<~`c$n!@KYs^=k>mAy@y|~&T1aiIIsVZ3g47^z*8oz)x5`@H`Q()eJDCQ@527} z(CgL3cO2AsZ4m0{oS=Q|*`sSmY%&}4i6BM}{(a+}4NvAZoG7Ba3p)kJ@?i&?K})M4g|3+KG7QZWUS#t5#?Rj zdmuW4STP87be@;?i1Qw*t^DC-sPQd`{&*LC@Pt{zi6Y9ouoFSt1!Aut)c1K_+P!|7 zSlj)F>rmr(5F28IOvl(_4JV2y@4|k@)4d7ACqbyA^Srdbnlrif>_MYZV;R(Ve9q{G zuXa5$ui-=yQ4s3rJTGltUuotosL>0=!*fQrd{{yhQQn1h25~HiuY*uW z=Xq%_yXMrmj|I5%gZmGuei3)>L=oj(*a@g{3y5h!sH5||w4Yk|wRj&VgE*z($?Ade z2AwFPybJpt#N{Bi4niHB=cRqlu$eKg=7Q+abFtQiV=J}JI?qe{ z(?8CM`4MxlRddjZBFek4QFywK^z704YRo}(be@;?1qXi+^Zc(M`fpxo-8@zXCyFTV z!us+Jg4i(#b#$JW_Tp#Yckc4_Y6yr62LHZwMy!cW6jABapZ--Jtc8SliY2d0yHN?e|6O3@f3=x4Yu+`(}@B;5>Jt zi1IG%ZrsN*eUEHC`<+Cnqw~D97yIsuTKY!Pdq6A;;@jDy@y&QeuC`I$h5ZEL2YjlN z-$?{N6?bGORIg?9p{-CE1MwA}RV!wd?n4CcBSm=^b`tJ<3W!w)Btm_k=cUajz3(Qo zQG=@}R?t?gqf1rm{q(FCyFTV z!nVPu+8V@qL8$NZytFy;54q#_sBt)mTQH;e!x~N$QQn3951;BuMBf^O`aaJ~n=^Rp z&cjfHE5oYzM1AqeSi^}T%DXV$`I;bh3qpOL=cUb+XtfV7Lk&LNEAeE9;t8{c6GfDF zVMl^^3&cf1sPFT^*sWp|&coQ^r&8bNd1-TJ zc>bW#sL=_}>SfH0`55u-i6Y9outpHag7`EDb#$JWHm|QRli&AR0r4#6_$MVq5#?Rj zk|0h6!Fk9}#od{GpXa5`ojTnI*Y;lx7*d%VckVL(`BosBgHT83d1>=Rp4KbQLCn8K&O?q8CyFTV!afUvXA=_aCfLz=UfS#| z(z-hb#FscJO^UVMi6Y9ou-FY6F}Cs=>gYT#ZFWd$XW;4edz|=Y#g5}d5#?Q21D@{3 zAdU_~9i8W;{l6t|ihZy*hWs+T&wzKsXYS|qXyoB0kk7AhLfZLLMh*&z%je#v?C54HA#y z$)1TP?72LO*NeWbGl&mB@SV8F3EIc?eylcONB&Og(jb~KLN3EdX-_DM*NeW5Be5%p z^MjDb^U_{wky>r~1^j=IgF(D>%Gib#k2p22;e?`Cqv+d)fS3ZJOAzvSUfR6=@%J~Q z28n5>jBP0+{*SVAf%|+c^Z(DWnsvw&2`zty+RdgKI{0Uv<~v)`f7(rwHj3RXhsrol zkr;;*BB`|@Dn^?QT0;(H=II&BN+cwNQaNNCW{i25LjKq1zVGXMzweprH^aPMUa#A8 zUGMvIfA90@`~A6>H0rudsWOeZo+`I6UWK1}<`?BTW*9O3#k1xeRi2!Ldr70N+a?&X zwGpQk!Yzzf;V)l(TPcsVjTl?^=6NTT5+vbX(x~e;)snl6IIIwEVY~{zYE%17y}n+( z?YC=>j+eSi!o8$X*KIF1jmbt#D0SB@j91|;fBXB=KDILAo%g?Pbl=jVNVu0Y>bmW0 zBc>Z+|D{^u7RIaaQ@1`)+PQj$`_F#&=(|eKK*GJGQP*uZ7s8%CX}E>)D*Wu73rc^b z9`4w`-)nSc>ETGYmo)0SO>OWCM*OT0ZehF%KlaNVbwRrvC6EleZBV6dMN8|*!E^nVWh{tk?bUiy1o-5q4a`bJz<2)B?>c>5{7 z9(3aBL%%itfo3DP-QgxU;`N`I*7#F?t_quLV?tb2g zPZq*0BotOoZ~WG~O=BG+{?khEM71i!MKArmuG{|Jh%Xy)S|Qv*LSfaIMN2pP>0q#) z5!U`jcd=H*xag(7*LB-Bjrf%jdlkYhBotQ7-|X>!GL5erVPoK^jfF{rgnLP&uG=QA zb^N@k=B@u|VY~{f1<(1$Ow)L^5wEip{oYcxEa6`IdtJAwr?!!E^xi_ah4Ct^p6IE4 zPBx7)4$iZ2Flmr*FKN_u+Z0RHE>;#Z3*i>VtFU_1OQz{g>OULtHmf23YBhy%(Mx}? z>o(QI3ye6p5N;u%uttV^PS6?TzD8Ve$oJ>I(pnYcqL==z@hY$G4v~ftuPB6DNGPno zKd|(hrXk|;L%zR5M7WnU>bgy-`nD0CDz`9Rg*8&==TPtSf34@4Ri2!Ldr70N+um!r zd%O|56~ZlyS7FUKa(TSXh;LXA`ms`iB-~3Hb={_V^>HJfx*}89BBPZehF%Yet^?tG_eiD>lP8q4aPh+)EmD-S%Hb zSXqp`yAW<+yb5b&k^5b(Sgda!c~|MFNw}9Z>bh-zBaSfQV})=F<5gHIq&$9<5og54 z!8AsZa4%{2D$KrXU>Y_Kj@USu2)8g^g|8j+^`H|r4yLh|gnRjOI+_?>2MfC#xMlrL}C*oqqN=$JTqtM-uJpw!z?UZ@qZ#uZ_5=5YN>d``UfKF^vO_IDCtJM*iWn+mi+f_mZ}++w26(h(nEdOChR-@ov&RxcdcT zs}44M`(SXc5wCgZy(7==I5DM{gnLP&uI>)DC*RhHCkjz5jCYgnN4sA*_Uen@V;UD3 zvC0Rw9r^99+a?VX?j;Si$Gp1xo)N2ps20Y%Nq5&y7mfYv=7*Wafkxb9DVlC6YvZb3 z`g>j7eeahS&%NJ>X@#hkN~k>SO_8yEPdmvpHa6l^%h^v_4!3btFa6!uZPwra>f*Vt zFye?pR7)kKaoNs49=q{h&M=La-FETZ6Rd{(#%f9%SM}20ecd(~ywg&(`s&9|xxEn8 zQVD6?vG&;5PriJPX{=+!i*CJmhlwveDrt~#FKKAJ%B#DBjQHIx7w@oMA*zM(>Y1(^ zTYd0N(-2`Ab0fmNq~YtfoT_`R6g^ed!gx37UbFZYZf8TFRLnZiW zE5SEdt7_w_Uiy1o-Cb|QVMf?En22hrgfvuR{_@A}w3AF@ zi4iZgoIT2NxQ(lN>F;%Q_Y=#jBaJwy5Y+0@1*0-N%b?S~nR7)kKp^@S8FP~!?Up3-qmR~QiHqypbz4UjDS9x_;#zBp0iKv!J zNJD?OoHdQZEdE=6dGQXf2nhF*hOgV~>ll`*+ia{|tq|41c=NcMpJTQW6Kn?XzvanE zXgrsfG<@A=zdc~NJIng2hYL|Hj5p68a(Rpzv61zlUnnI=LbDfnNyFD|_HA5C)yYPD zxDeICc=b$|j^%pwCL^Azz zvYFC7rKcvL^@qHq;p?_M8d!@R`9&eBh4JR~P98tXh%@r1GUAZXI!a#B@O4|BS!!0f z)XKiKFkY4aH_Q3pA=U<8Zp5QylSwJz5n5&L4uZ; zkcQQ%5vwUlgG3EanE$=MS=gPj;L)N%f|i(&hP90mtMPVEZ7?8F!}3yIY4)miLxPr= zfQH?-(?7=L;rtv2udg?%ppgj0TP+cRyqY2f5;dI5ovd8RxE30h*JXv|g1O?lPC zqUO4Cw@PzrhOkdKs=9Zu(CZu7{Flx_|G)UC&g!!ACxumoG=~Ayq z&=M2Uu(BAn98P^Ai5i|T|A#j(>3i3fpd}`xp}Cb>mGX*24NsWA>yjlHB}mW`6VlKe zQLRcEBx+b*<6Scj_5>|40gW`)lBnVQ9CbV|sY-<6trkxS3FOs0e-0-qoy()nOG;iP zLiyvCn2?6`xue#TE=N?_>y^*1NaS+PmY9%+jUA&lB8=)eNYrp{A9bEcLiN=xF(C~b z14nISOBy6+B&1P#>ZC!UhV%GQ*HI+YpSvX{q@j7JYP`yvL=DT!S7Dknkf0?d zMAv__MrukXrm@dcm}Bz!E(uzyhEl>*4I}8Kk-F-UsC8*#8fCnWQM>xv#Ak$-T1zZd zeQ7F%^iK##LUV_>!K}&7t6U&I>Jws*MRMl2HF^z-XnybH3rFebb zt`ydFg34oMCD;<)qpmQoFaj_~+El3we1@#j^cgvGq$Ow}k#oUE=gLHRmA#lF)n9p~ z`s#C0m2*G$O?7u=dDRg8tY(FI1uy1Eo2oi1o|yJwJcZ1WmY}81ca;*Km##2X@M4a% z8g*SWG3|JGX;Ql-XsIg}OG&@7SYfK*#T;oh>dJIt+FS6NPwkeVrLH+Amfeq))vLOK zoS61xYCWzhvqluJ_XbL#&p4=E{g>^pTEbWNE6gkGATUQ-4V8iSoGQ)Qe>|U_fke)Q zmGxKjVve+_Vy~}q?#JEd)dm~FYD}FoRF$@8Q0;Rs=19Nh%yWjpq1Ida-lT^o%-?bR zV2n{^&6$YS5)oz2(C>?qsNo6ozq9xtbUI+EL&=R!7 zglO%@_#BQz4cnf~qyzi<))KA7Q$j)-+K=(MD2W=LFn{-b4nRF7K}$?XL;Ep4rzTOu z6XyTy#u;7R7bQVUOh`lfF}^k+QNt7FpSQ=1zQ{2z6L=DSpMptJUBxs2VXrwhKi5kw&QD-$pBN2+XT0A8rq*0zct({5K za4wHJmXJ{XxFsf}q5T-&10YeuUax$_A(6{DTVg^Q+K=(Q3=%b*+eaOvNT|NLB_^a% zP8w`JZQr#3QNy{_*4Y3FwL7=Ogf#RFN|`iB)Udn`!u}NrT4F-9%EI@^NYrrdck2w0 zg!;j1@syB|M(L^3bC9UvJbu*q90~R3ZixwLlo2Oskf>pKY4nNrMXMzyiblW7*~aDc zg!xxaIIK@?zvfJ-YAq2_@~YqEBvHc?=6`VQnaK6Bc1{|!#Dp}|=lWhai5iyIr%8DU<2*q11o)Qws ztF&iHqK0#M_)4bF-9#vV+!7Pg(D}Td36rQ{uUEdBAd$;CTVg^QI-mEmZ4xz{+ecmR zkWhVfOH4?koK1|X%t_R6ZneI?Y6-PFx5R`r^bAUwG)UC2ygr3_I|*81LbS?4IV=ql zHJtn1x(Xwqez00RB_yO#dg`P>qK5PMQTO^ts6Tg0Oh`lXP}O)n1&JD#mqs67!;zpR zCPdeNvqox4CZ@5^Q73 z-)E@LQESP>G&GY{pCPL>eMV00mY{`1&IMmhR3^%+?8O|Z z{>m%WSD%Zj=GVFJ^U150@LA1@^Qw9=N7_`?S@FcQ5929hjI!mV+LNjExT?$=QM}$8D1~*7@_g!5OU&qd*Q&5=Us87sCZ^qw+U6@WYeZ$>qq9o0 z_8-qDRU~pQtgOGH7jvYhNzcJvU*%l;+UJw1mhc_6mDMZX7iEt0YtAxfkoq%I^Zg_b z_v_m7_p(Y&L}_;`AT-vNmGE*zrTf)(iHSsM2gwo>(kLtXq(P#F<&|1j(I7!fOo%Q! z6D6-0mxufPlA=MP^ajNe5z;6-EJ=ez4fp##B_8YD^|l`JtKjk0r>G)UBNzdKkoNR(bQSzMZ8!Q?mXo(4Eq%|jr8t(UZTa830Uh8X%#Zy8;8s*8Ss2?Ix!~H&WiHU^r$NKhU zi3w?xz3`+#qK3U*Ehri!aye&9Oh}{b(2wXjNYrqDZcsExsJ_|=kSsAFjdIeEG)UBN zf0|J=NT}V}h?6WaA&qjzk~B!vu)I>=UNlJ15)-1!Sy9p;QN#UtRM8-ze$d9HV)2xa zkVfgLlLm8s2d5*H? zOsOhsz+#Drl2^^XsIB`FQR#lQU1GAl>WQ*ST>&ADvZ7C^B2mNgO6$R*L4uZ;5M6dA zk_L$y?)OWI28psVEf!A+32Br)nWRCYhWmY=5)+BCc21U8YIekIay*t8rD-c`=Z`cSGwOFEE*)r`ZZZ%LKHJH@+!?4NYrq@PhDavd6kH=s!o=e zkVe@HUyi7>*Q+Os28mqG*%A}dC_D6{8V5<#aDQ%4G)Snv+A1ztVnQ0_Y$9opsNw!J zqiB#&yR+SoWQhrBlrxs3L86A`m39z{1_@eXLUcL#Ng5<-xId378YI*Y+8#-Sz&f;7wM9(j;NaS4bUX&V)i(br;>hF6pw(FSkO66SJ{PW4H zmhjd6%IcN94c6C6&yhA&wKvFT6P`joUrW$Z+qqK0o}n^rO{AAvaMdGG`}2G@QPci> z@~ZaKN|pDhE6%Ix#T=<=QVG@(IiF2<&1a6Z1TA%}^|OhU)vG#k=Cg@fkE=>PoABO1 zDXeYc`Q%kg_^f8dc~!lbBQ;IRE0uxwoGQ)Qe>|U5k;u8Qvi^!*%4yG$HdU&xKFX+^ z>-zKgq^c!+WwGMCs$R^Ie$83t4C$tIYN`2_ul7j$_aMvP%bGJ0<(~Em2#vL6CA=I_ z>Hh7^5)+AXZ#r3GLK-%c(L19_gG3FR*R1qjYSAD;OH4?^W@LKzHRl!M>cjo}wMBzO zxjmjOAt4Q$S?V3$q(P#FZBHh@4O}!x&=M2Uuo<%6MNS$dYPf&jxoD6mx5twuCZu6A zeZ5ni)&?YMxPNcEXpks(+LI+Fq)~S6k_L$y?%zKz8YIdc^JIw$X>ga5L=DR;-ES`% zBxs2VXrwhKi5l*|2heIHLh;tV)>A?Pc{N4-5Q!S@ziZIuRU(u>-jl_IG;Bq$Zzn8A zRNCv6_o5_nIcG~uNW*p}^bLp+JqL*z&h4Z2^CVPX-4YYhC?^d`gG3GY-^(a@MMCY) zN1T|DhMqww({qrhVe_(H!cMb_1_@eXLK-Ry<*+nJ)Nud(lA=LE{a`;X^(i4CjnY#m z4H7lne^sSukSOm>Buh+4ql`F7gG3F>OJkR>yhzXz6Ga32qKwPK{d>s2Nyo!duUtC3KBbxTZ0qntD(4H7lnfBmAA z2MM)1UoXdmH1rHgnVy404VzbfnqkA zQ@pDt^=zqQtyZQ!CN959tpvT4!m7tq)j3suhu7y?&o5PVwqz;kXEiHK6}*@uHBH)Q zsI%hy4zJIapI@r#eAnOM^%-(i(f(Dr$}81ZZ-Xl5zRe@oTY{-- z2&*x^<2jsA?Q<{YNK4e-Ab-okQ%LQWpry8Rm72=jdxpxic||YgNcC4<)&4wx%fd^O z+ATp#?WxrU(>I+;pIDh?QUx#ONcC5$>WG}bW#KiS+ATp#9c%qt7Avb)b>z(7vZ(dA zs^o83cyFK-*0uWcX@f1{vzisR!Ro~vscBMPsSLd5RB6`!e3cCISR*DLp8j>vyjo-bJFxzGLH>gQ%tpMCDRpO)|#!e$%j zzkrY>AjUHB)$;Dg>c`I6A@E9iS8krP$KH0&i;W^d3sYGBJ~b1+D|3>m_69x)dM$eT zcb5Lm#*RO1J<}jTOF&G`#BF76^)}mYAW_1}>#U7_n>7CVxmTJ730eYTY9>}K?-bo? z`z9nxIC<@I%3Vq0@tZa?4HC2j#MDe^_NsE!ZVrhOPF_p*xg%*@xY4Ukg9I%BF*Oq} zE_3#KZ2e54gtOPxze*b0ZMU^)kQl%c5K}X;f7y5anf3udlyLHz|KndKjr*V4#xzJY zmQ0hFnu)89%ik}3+}_zIQNqdVoEbMHjYHq@M$;fcOF&G`#IKLa@9Cdo@9dK(;o@~& z(s=f7CYuHc``UMJ35cmZk#J(F-s-9>qNsmNHp*?w8|0}OZlyLGI zdBhP??h`;pDZ-4nIj6eJ$w;S^}cfE31i?M}vXtE{PIOUN8CD zKj?L9$DK$P~Ow&!h-L{3)lSb}ENzf7yrQdzUj`^FM=N^0f6cQzzymq|j zqNI^W0}`|ZL>WJ9#7R%CF^WV9C$CkG$Ql|G(-_qgv;;&N;Z)ihmD9gjg|IXaraF!A z^2ERisRu+FscWjBv67=y}k`jc;zw#Eden#6KdZo4UIe`ye7)a+s(q8HZu(p zv;@S|OrV{QlJFKKFK_?X{Fw!cKedj@%VKlbMBwl)nCv;@S| zOsrS>-QU?9h=liW@+ z`lvQa!bhC!l}FU){${diknoXHmVlVr6KSW`#@bO5KGw?1$N4^0J<(e7SPP;&hvn5g z)m`Nk37-KdUd&f=UiAbm0a41sN-z;Ba}t=zO!awJUrTy|mVhYr%4(wJk$o*od!uCz zm*OfjGKGEq*w^-+Xe`SUrF~%bI!eN4mWtQs!F{Vu8X{>4h|)z?>fG$27sKuqmN zoTQ-*uLniY5)kGs;@S=0J?WWS_ne)_-09t!2i!Py{W~rko3_!; z-MO3mE`D`jS{Uy9CvF(>me7lH|KmS`daq++R#H(g~F(5X4-&5V>$-9n;_}An9 zA|izcgVm<_-`iB(zReBYOP~F1^4e7q3{5o=z!%Cx~?trVU(Zr^+TmrJMW?=8VxTsC*LM;;SyA@Sw2r*}Kw z_iRAWLgMnB_wEik<5ekzZK_DLUVGWEb8Qq5cBb50?%L@?_WN2JBrnD^T!X}=yYFhh zWVc?R!MN!4#r^)texoYqdaFSTi3fMz*>*W|*|fw3mwl%D}0Ts)$i^ya%#_{_~` z4k`n^GU%=qY0X^&N9d(}IS?)KbnY4V!=`jfkltT{1wa#~2d|K_8+ z`~QAPph2Sbnq}H?y{b?9-y40p`~1OouH?!2v?LB*e`fc=58n}_ibU&mX!qQ6w+F;! zzxa6f?){%jmfd&yq@4(?lJcjmm2Bto+P{>bXfFfS{I<+#A#wWI`&nMy7o>`oX;<#s zee3!MlNVzeu0i7auiLlV__l`w4aU`a?K`vtt3`y@48}A(RSjX!v{$K>!wEfydkrrS zT1ezPd?t8u67*tSXj5h5RG%lR?Vh7-1ua1f3AHXS&EW*Sa%+xiiSAQ-tv+SJL4BKG zD`+)nA@Sb(59q#7+T(Dd^_tQ5T`j>@q&F01e00^7v?!Jb3F%$+&eekciUhsxSbKld z+cY3(A)#D&|ILvGiPlTEqc;mQ^8NN~S)N#ZB}AsP*X*s;gGU;zMJdUIdb{{JNYLwt z)(6MAt2Y3>)Mndw<$WUSbX(@Mkl4w_DDPc|6ZGQP)e>!bk;3PhS0ILugNTdI^zpZT zX-Ij{LgF{`&efbT=zU1g>%-G89HMc`_Ltb~^>0%BIqZv5a za?KSzebjoR-Om=jJgAAZkho!$E4z=pe!@x!dW~&$Wp~UbF9`@*CQrW7p7zDbi`s3O z(?UWq9sS2O0}T@N+H|*{bgx-!VNf2lkkB)ocT+U$BSA0a+l@Cw?VJ{s&0T-UJq}}P zpPUvFr>}EGw_wAlzal}ev(CJ{+xW2D2e%rd2mPo!YEGW--2C9B-M-J{@YTCq(ye-R zlvlKn*n96whiH(X*Vp&>UU%vn9|_81pn0o4EeaQ|d=*4ns30g?l?-X}uotbOQ zaDrZ}Z!N)^G2`(|x`#>)A6`pnA))@!TUV<=f?n&MaelYnC!+ZkEhJQeaXTkLFV?p< zRkV;$jX6K;eMr!Y?WWaGOa0nv>!jZDiX(s2k21>j2Toc$=tXHE!8+Y)kf4{!W`hT# zl`t(NIKs6Wd=Ay6W8bsI#{&7XGCDiUbch9uG_WqKi9EnwJlfAWFPijNKYJZc3d>Q)K!iUhsdlBEVMBrf>cll|^jn^z?0 zHN5V!{(NWg!Xa&CSgJ_qeMN6K!&5~s*3gz<&!9H%wS@JpC1@d`n&^93!wGr~@2_Yf zp_;#n-K|}IPoD(6*jKix%5B?sAaoluuWMd@__*B{j&@jDOC{8=#5)rt=(XkTOS?nE za|2pPsOOs-?i7(|y`Je_Ipn0FT3TYf-xXOluPUKl+xJdhcGq9~bBdN|EtOFF@ZFZ- z1ifB%;b2;Pnn4Q*wa1;xj`uPeh>KqAFLQJ+6#0t`oS#*)3%+w zYstmcrfpZk>+H7bv~xE(G05H4QVE@N#$(j7gnO|EZ*#Y`)Oa_!bJc0@4bKNj(2J*; zt;Sm}d_w1^=?TAl{}Vb_P2o1REDu^poG@WYx9VF@DtYzE{dV2zfUkT$<*vN`@f*h_ z3v*h;U$6aKA+8*KcGAs9Uh{302Q4J1-985idi{BWC04J#P&D`)w2)|@*(U;ln&@Eq6tagmka%w+l8u8X=Sf0o0Sjy>GHv9Hs7a#~27@$-e{?WdU4F-1}{)(-3*zx`8$@zqPes*#9 z@e(ida4@*{b*pc+^){bhF0V)|dHV70oBeZK@^>3-waesPmLurJ=WFW~EhN@F`0?(k zlGDQpda;~ZLY5nE_-e{U5o?^C!)(nhK?@0`aGMupx+RqF?)u4rhdI`_B;RL0O~hhD5btp+V5cCp&yeeiICUTg&|!P=l6&Rfy*D{~UZTOaH#xYb}>^kVyO z3HFw3E6kCWpoIjrhZFR=@_YAn+yCl}pncFn;;8L^*PZj>ivoh{KCatHx2d9q#KUXd z*&TTO{6K>Qy@scXd-@x6S9fn;Z$XNe`(#G>iMNd0 z(tT|1t-+I%pciwY)p+$fCw8~}_1qK}&r*47p(SV`G5pR133?5`O~q7gGGH{5<*kXIz=#l8MkgBB9s+T!coD^H7d?nuy!XBMr-y0;wAkEu%* z9MI3B+dG%+MgMcFS=~c(c1cgDJCNQFesR;!4C!|n?{Bv~u%Cqu*Pw;OX+Jp7_Vn|b zp?wY#^kQ9T30g?(x${9oMm0Vyb3wO4eTLI&&_d#b*BsyNc8;$CB3G<5i^VIu4)vsP!4XOLeM5+2jSsO49 zTY?r6%7u6xMS@-|n^uD*rS{>qk1@3bEhL_>Ht#d?;RL0D*F-=^jdNI@ENOmAD@4+HMgmvg@oFsuSJIw^irx^uO(>Fb9f4= z-4e8r_>PrFyjCMYFV^W+gBB7hfA3L;6ZB$l*Ag57*mtpHTY?r6>@kKD^xARDncdPW zFHP@kv;-|A^yY%U$)eH6-+U>v zvw)yQYw);ZJ9Ehfeu$K+r-$y@c&kuY{nNdL`Ta3JA?V zY_66pWnPlP!{0umg+!SL1sWvi#W&yD5@dSIJSfG>9BBz!NR;(ekSY@NVrp9rT1b@j zRiHtFUd;7YgY`!(*mnL?ysU36K?{j8Y6qzzL9Z3OKZrLANoZuS)0#koanXydpnVQn zNNDV`Q=mYD1ijc+T8$faJfr*9D}J8hI_TOjb=N(6MGCX$YYCOJk4u~luw+|;781iX zNYLxDCr<3vfAYNG$!Q_MXKGV*!-bc2KV7si#WnGw?{`x+cr=BNeeC~aH+%3vkSY@Ny5h*M=$2kU&_ZI}51rHP{LA00grFBoc9|#7Zz7~8EN>{J@cEad z+lIlD(?UYGChZ-HfS{$^vwQ&>By^YC?$!nxOclM}b=+mP=G-hGXdzKx(RAG zWs?_UYIBzs66FqTph1FOx@T)QWdowzP)-)zT(-9>QkeCvO%*L9%1!A&g9N?UZdwgm zNR%7jfd&bB=|;1?n-LKE*iCD@7o05R-g62wwQZ^xSGgUZ2x_+kEhNf&8bPW^(5u|j z4+uU7(_U_72Lzv1d1Y@UB`?zLbI?LUWn*ta1sWvir5a=JE(L_zhrR8REZ_RxRo&*t zJ(l_?)qHy+CLm}b!8~lAgGB3<-kS(C)Qaqliew=%ygc}X<*k%NGe_D~(L$oUHxs0a z1ijdrTMg!Jd8Z}C%Y17IT1cozwRb^+RFR<9v#0(~x8T-41tU&*`z*!9FFKU>$^s2q zNR+q40)i%rCezBs>U0O)+nOcGt5_;Rs-bx8lMS@<#^NL^6 zAbr4Qzv*V2I~tTAEhP51>0W);AV?JndL8xpd%Gtu_->$4ZX_hjrH?J@cZYO4!Ojf= zf)*0(cSg9AN`hYH-ddo+ROyz5?FcTH!nOpN5)!%x;(J-c33`=#Cqb%|UOQb#7Tr(t z^(UXH)hIU|60y~j57~U@z!cV9oOn-$77{lfeSf#$Tc-!9B0;Zm_a`8j_HzF&c@2LK zT1b>zdVvNBdJQjg-GQ?m>=akI$&tb=**15}ZIR@qTQ6QqhSzplNR&HF!E?OU?kD-a zh*D)|1vyoAuP^?R4$HjUdPxLJvwaR)NR(SPL8?g5OZR}{RMA30xnL)8fd&bBF-O|x zP|NY%A+;zwA58J`YedTvb{>(u$_=^{9$x0OkSMozqUS)bMlaU4HdU+*y1nE5AZt%c z&_bfz912oJf?jOFtp+V5%Duiog9N>X_YADzx*O&D7px0ys%RmhoVJtrAXOyjHN2M4 zLPF(lw?6|767*sXZJ&en^@I7AZ;F>OwFE6BGx*|(m8RFP=C7V4`i0iib^+@kjl?CVJ{AXOyv z?ty(hDbQf5TCc_W&P+h;lHWy4mhzrg@mg(~eY-6n^d^E^Na$SI;=6tR#kJeHN#bjUZ2{cI1tGquL5VWwyFs9+DBEeiAPSA^eWlPXPg7b&r1id(y zXbF~--rBLR8I}C0CEF4#a}s*nF)j}htyg;ABq)#ahD)-vM0z`OB}92UGkJaH-c_gl z?{UurL~E(>O0U*X&h$yp>(XOao%Vq}Ru5Jzw2)A~+53Y*sz}i5FMnEP+C8s{c0Xt# zkxMpuauW1f{}roDd*s-4gXf@ygxb7)5h!>L67+iG#KE*{-xcj_(?X)W?G~hp1ifaC zJ=^WN$A$q>-abo~^0s73`|x(I_q@Ef)H{ma*Rnmf?SmE)<$dlTuSm3BF!VGZyY>1EhNetjw>PP_1f1h?QWUyw*k>w(tD7}OV4EArdkO>uf>~ITpqFL? zaqhCVw>3PyMHy(YP2^E6_a80IK9Lp@8d2>_l|gMML9cdZKn;xszV71;P=B{C#0DC) zkYGz|TNH`b>-mg>EitUsO2cPMYEeD|^T)L0iHN=#oEZH_yw2&xYVhqZI1ie_Atww7}Uqejs>br`yPO}#!L9gMp zgm)OqcXCUP&d@hGg4`vMYh_-UO2fWi6A-*1K$_*$J~=HUl+*TQnm~gDy;$E`jkY$- zvNoUZNie3CXf2gcOy0VN6ZBH8jMoO`YpSW7%Xe8*xNT`Hb6QB~+qm}Ch#;>>(2G4^ z`y4D=)hqk*Y>Jm<(-O3hP|bfn^{RTYG+PbcTi|(id(VM+MGFa@n6?@u==Jbb>D!+{ zJEw(2TYH!)67*_&3=*`E7+$YP(2L_$`{eAyHI~?yjZ&Gj_Ot{oBvh~L%SJ1yiS%Oa zX*FmeQNGe0Xpo>++uJdB)dszeYX0!TYCDNj?OVlhpU70TUWeLjAnHXqXW*=ceSVu) zw2)vq4JTSJr7BwE9?*uEc8->%^AP_!l3S}LKpE_PmU!szn1 z4VNX{i+5F9jn=|=r+4pu=?Os_T$XSz-brsYS_|Wy-kmiyIz?WVa4)vBR-?5r-sx7` z^PcsJ3HM@sYl+rU<2~Jeo5Q}n6XX>Mda;JK8Y)}=6_sV*$MN53S)OnU3BCn2oS@h9 z`y~Mq>RtUeG+K=|uIg2K>Zzsf+OPH;VZWX=_ui8x9dgYQJEMDY>~9`fbH0byzhi9d zhE>Mxz2qh7@1_BQmWU8->vsFqo^RT(FK#mFvy(`8SYBgWjoVu=i;D&cS|TEAoMyjf zb=h%qcG&;ddrTtXVR=oSoPLwHXpo>KBC^JRn8xkL%$a-a&D%{P;bDJ{XRm#RB%`e`9goov& z(md$fztV4D zefsXh&LiPrd7Zw_lI~Y;c%W#Ipd})*#zVJF99?YB^7Fe-IG==v<#pDXPjqiua9`0N zK}$qrjW1eR%(pW6!+i_RC*fgvZL{GM-OWq?STsn`5)oPB5vx-RtZu#R{w-#c@UXn5 zp1Qbu`lGHvf|iKL8kZhDXYSe7Mt-ozduEgHaQ0ekH&R@Kgm!`55)qkx`m=L(_@-&R z_&*P{U(c$9hvhYT(BpUx60IfEB(lcm?U(+3ZF#l+)Dvct@UXmYesB@Wg9I%Rku@&c z>y9Z)tjssu{IuC5JS?xh_g>U(*Vii&v_wSK_=NrP;(uD*opRoP%qHPsdChoyA=(EC zS|TEA+-|=V`_eVG8-3pyXUrzyVR;?)#f50+Bxs3Sh^%3w+K7#VJJ>il zn}mn`Iace(a}tWzEfJA5Y*ZVuad3)_gXuY(a9Uo{vku_{o8`1Bw+Bmp5 z2@lIlt!wLF{JD;UJwZ!EWQ{xRSDK%-XIXmp30sixu)OxM{_5xJKV39P&=L_@V_z$a z>#a=Ix_`kIBs?rH^>*95=$WEHf|iKL8aAp;v2k$3#=%J>JS;Eu+N+=K8YF0mh^%3w z+731jj@URjiG+u<*JAskgKLn`NamJ^$h3`Wb8Q?Pv2kz`2@lIlqv#s_bC75)S&u~4 zuu*NEje{dL4o)KBVR>mbP|Je^EfJA5Y*d?PZRaFtiHNK*Ze#iV)($s% z>hwt@JS;EGmTP}Sf|iKL8rJ?s)vA76)`PYNnCk06h2>Rd{ps(60SQ{lyuBf^hUTGa zRc|WmL0ikDxSW<(S-lhu60}4_*3djut!mA(9<+5-ipyzvl~q{LAVEt+WDU(j)vBJX z>%kP4)BYSbb`=d0iq|a>ku@|ARjYbiSr0nlw7irHHVzgI60}4_*3djut?I{HNYD}yS;N}js9M#p%X-lIj1-sC@=`Bx{rXQA4HC3OMAoqVn0eY|d8(`j zJuau^ReHOkL4uZu$Qqi5YL{jEvL3WPJjLa-ywq#kI9N1D&=L_@L-SDWvP>!KL66Jn z?3G5JqCujJWXTc{nbtg1yDWQ^^`MQMC9WK=yvitA{!XH`EKg(&%|o@zvf%A`J?PKj zw7fJMczwyk!GHuU5s@`C57jQq>&kl2<8oSFT7}s-Se}CfEfJA5G!NA-%XVcw=y5qM zuQEF;8YF0mh^(P`sCHR)F6%*WA5P1w%rc7x30fi|YuJ9wh;~_Q98Bv$8&gwUPRmQP zW$$CGCV`+OBC>|<$Bbx~WwfjZJuau^Rc8I=IY`hF5m`g?Q0=nVIGEOh-tRgsud;e6 z8YF0mh^(P`sCHRw9Q1Wmipyzvl~q{LAVEt+WDU(jwaa4Tpsxp0Tu%FQ_!vAGkWjpC ziHNMBd8l?-Y#dC_;e^xjQZD#hVlW^S zh^(P`sCHRw98Bv$kIQL!saD#)Xekd8v_wSK&^%PTEH)0N^`OV)w7k^1Y+tl!kf0?Z zvWD%)j67w}^82zL^thasmwE}?zbYCeXo-ldVf!&tw9B%Jtp`bXSYGPwY+tl!kf0?Z zvWCtjw98`SU|J7)Tu#eNz4kL7bqx}l(8wb;R(BpDiUYga^dPRbkh{zf`m(ae9je}`D=y5qMFU`(w?b`uakWfqs_+EfJA5G!Ip)()l0>56kP=_Z*>p(NcFw&=L_@ zL-SCzDxD9K@UXo0+4~6Xixv$Mv_wSK&^%PFO6P+lJnYZmYq-IHgyMBeL}U%kL)EHu zK1jmD@=`ANTw*XFK}$qr4b4NF{M+GVkQ(ep`oSY97_{Y>q{mFFNqOGIQ1%|o@zqVqu#9+uZJn;eGqAPHI`B5P$Ah&mS~N(smQ0h#8k&b{ zmqq7;Bs?sy^KLo_QJxIdC^4j>Y8R)M_ z&=L_@!}eoFw98`mWM-4_u)OwrW`Fd%Bxs3<@*Fm|vT-n-50db(ypEc)zwXJDx~rM1 z6SPD`*3djuyDT~%B;jFsoq6W|?Ks#Iv_wSK&^%PTEIJ<~;bDIcU&EzwuqPC+TOuNB zXdbFv7M%~0@UXo0wes*aTp9;^f|iKL8k&b{mqq7;Bs?rHm1dn^k)S0avWDiN+GWxC zAPEo4OSRJ1aQ0hUAZUq*tf6_Rc3E^jNW#PNy35+Rui9<6uu{By&qdWLoDE+GWY-gOzYv zUdP&aUY~FKBC>|&p=wn+A0**nd1)19dznRp z1T7JfH8c-ZtJ3)(2@lJw)XJhkf|iKL8k&cyRq1??goov&RhYH&qCtX|h{zhcrnmX?vMPg9I%Rku`KrO}i|%FPhea9+%Vd zDzoLHL4uZu$Qrt*rd<}hCzIBLwgyOXIW4a;>n|E4Xo-ldp?RowS#&-~!o%_^tCyld zf|iKL8k&b{mqq7;Bs?syv+{bdXpo>KBC>|&q1t89`5*}o`*YatXVD;`c-;~aSwr(s z?Xu{6kc5ZjrChLm(V{_umWaq2nultaMdyPgJS?w`Y(406qV{}{mWaq2HmddKgCsmG zFV#xB+ftr`1T7JfH8c;^E{o0wNqAUZYF+g{90^(?B5UZLns!<2o=jQ~dR$J+OTC2M zZ7I(|f|iKL8hUR@yDWB3W(yJ?mX~_FdOwi_EfJA5Y*g#d2T6EXUh1{$eNhs$L`2rm zxrFv*bUsMJ!`UnCMwYxHp^?n*i$+AIbuOWOnS4H238&?yQM5h>iPn;75?Mp%655y1 z`5*}o%S*EXyW3Kpg9I%Rku`KKpkt0b7!tI^#JIgb$Qb~M8XmX%4E*f@612pGH14o``m5#F8*DF}L=BJI zeTGZBjStITylDwqVnP}ZS%39?o5Q`y=5Qoxc--zYT-tw`za?mi32AU3F`^Y(S&o_-#KKveg&x>(+c--zY@Yf1R zw3djF##Po|J#O>%t!<4%qK3!qK12PbgqENsCZy5c%&c)$dfet$m!n>hpd}`xp}TNu zxq3&DL=BJIeFpxL00~-RLKhAYs{Nzf7#(s<>iJCDw> zXZh}TU%my28XmX%3|H7_=UV8XmWC@Jc(!d2!JoK}$?X;|yzmJK6gAb+$)FqK5Nx z9J9$wiUtYA>z0_1#!_p4$J-q1WwzHxqK0#M)bEjzQ2w|jCZwUe)SCI}9d{Bnoa+^S zT?K^7*)1_44UU{7YB;x#`nyXcRA1c^6Vg!ovsRVv6p^Um+|D<6(0|*BgxZ~3VnP~Q z+aBE2Hm1MD_QFZjaPF__Z#$7t|KXOHkjCcL{_e6l+!i*6BT>V--~HNZ{wqo()DOBP zCZzG0_3c^>KWB4M5;dI15C3JTmQa80mY9$RPfSSEu)Hp_b7y}J612pGXdBgbuyJt2 z#zDK+$GAM4$MgD&QzSILR!c-k;}lyr-)4C=cHb6uKd}-uoaZH;>n)*qf?Hxj8hWQl zJ0NS>`IL{Nk6|{urZElGPXZ?a$iblrPzy42c>ZxBKmL`ca}KXo(4FoNI04l%wYCaKG&>k*MKu+h>@A zagYQpF(Hj_n8s#D&6#`8ZF|`L_8M0W=jW*7ISIw4EQMpq@ zqK3!E_*=FuK}$?X!$!3c8wW>i9Gp#}hR4VF8>cNnOH4>Z?N75y?dg-K;qfv45^77( z5);zk>W)MWkB{+}P+NkQn2-k7gCuHre2l+@+7h(HgfzIiBT>WSWBl#ZmY^jjq`~zd zi5easYk!lK1T8Tk4c^QoQN!b7{Keyzpd}`x!4pLiHEeUZ=9iR7&=M2U;OdS<4UdoU z_lsMCmY9$RS9c_8czle%U)&P3#Dp}|{(L=1qK3!E_>0FaK}$?XgR46dH9S7n{*p2Y zT4F*Pvu&+*itU+fe#>@~NYwE77=PuuC1{BWY1pVXYUAJzHV#fAQN#H;Rx7_|-x7+~ zEioYtn=|xxKSy`gra!aV3-4YYh;OdS<4d?c; z)Apy?otX=lAyi-85);yRk&S`Bv$62KcBhC$4d-@VfAgM%+MQcsLK?O&I%@l(BepL( zi9`+O{;K|_9trgyZixwL9A@jm|F!w(Yi&J9qK0$7>%R=v66y!t5);zkdXPj7=kddT zajqrQpSvX{q`}o4i5kx1;EgxrUpQ+CjZ1Ec32AV3N1}%Fcp>DVoaejVnp;BiPq)N`G`PAWQN!b7nk{>;)DpDBgfzIiBT>WSW53<@z`l2F30h)8 z8e9*OsNwOkCl(xF_uEe@Wln;Yn2^RMzTYP&vCLCZwS|0QcD#qHni}u-{Ics`0Ld`}UFk-V&w0u7HrnZ8io@ z#Cp(LR3a*!+qwN7Xwe{{cITFukj6o_9z5OFgL+qnL=ETu%0|1QK|=k9TVg^Q*V)~Y zMK&MZsH_K_sC3`&77Y@mA54~*kjBStukSZD$6C+cT_RD#{rFKdNR<9OSzeyB@TWGZB>@ANx+8MHLMaw8Vro_{JfL8qV`XZv`!(d7E2e zLK@H7*~CNk-{E&1b{>fu?&rJZIY^ZGXR^eEH2!4mZ>jYq8(sMFElAXGp0|4+(-N9T zyCo*1vFv)#iAs-;t&>+7u5);yR+UnH7R<~}oJKH2`xL-#V4H9KtlPobI4V}b& z-o~ht?d~~=8t&JFMT10HpCwC7NaIVUvB>T&9b)H$Bx*Q6hmCecgM{LBOH4>ZcaYDv zJ>-q;e2_#9_v`bbK|<>@`-SfQIkFxJY3MHXp|%&Ncic(TaKFz`G)SnNZ5&LNm`KlI zb=Sth^lk=;8t(T?{5e3VzRo!L=wyirY1pVXYU5yf$Am-;=XP$t?_4xUsNK0GCZu7b z+Nh0#`CED*DxKGZ_8ZwngM`*+Zi$Ih9`>$*je{dL4yN^>6P3>WuKo6Q(Xer_C)5wR zB_^a{quM+h2S;oioJ69A`~AeCK|=kx{T6bv#Dp}KT@N}@={yeF?;;ls5*nA>5);y} zQEdks2S;oioJ69A`~BUbK|&+4{bF*m#Dp|#RGVVs;E0WblStHXo|o8feHRT9nkTp= zCZxeP^+?oko?qE-h!+hKn(w$JCZw_KdeDhV_vZ#hgM{X7-acYN8aAqp*f=<1kU*|FqwVPL`OEhK++GHV%&1ICwsZ8t&)qMT10{w2TB($z^OH4>ZD=!-dcd&6Vt)rZ%biW=f zc}1eE&ypo3q+z4lh>e4DZ5;IVU?M7QZ7{EEiv|f=VnP}=s*TtBa#T4F*Pwl6xx_C-f+UvxH!8Xg}jzgb;0NYD}!($M+5cF^sf%xn@hJU({( zu8Xv5STsn`5);zk>W)MWkB?pR$3@!xEE*(ei3w@&e2_#9kB_Z+@Z)$6612pGG;CjV z-ffmwc28zDi5j+c{`BM8{VdNxf|i(&25*0os9_sFKD$`EpGAWNEioYt-u@&}!{cMS zEnbZFL4uZ;kcRDxj@mt$QM)H|9*G(rAA9d^PoSNXpd}`x!Sg{9H9S7{mJ6Tg`debJ&pf|i(&hE|Y%Uz9`*=jZTMUrQ)nx5R`rbYI){MW@)l zXnGDODxJ&2c0bE=kWl`(B_^a{yPW+uuu0T#u2()MY6+FITVg^Qc2A~%SD!=;=l0>V z!In^cbxTZ0!|ut9+C7=H9wbr2xt;s0wk6c=+!7Pg;O$QmHJtk^U&FP8`VY6ngfw(M zulcCn`5{rmx!?U}zy2Vhe$Xv3Aq~EXM52cC_~EOimQa80mY9$RS9c_8IFEz-gzG_# zOKyn?Y4CiIL=BIRea^;nUyHT`EioYtwLhIt*n1O`NYrqim-wo$B{WZPOH4?E_eDw6 zaGqc7*RKajXuji?n2-kVi;}3}JWu>~zh6Q^^ES7{gfw(t+iqcx*n1P3lc?c5-}T*{ zmeBmuEioYto)40!;qkFuY_9FSQcKVh6Vl*%kVFmJ`0@Kk`&C~{&=M2Uuv;(vJG>-n zczkU2xsUd%zLuaRCZu8aWJc_s%no)>W;Tf$wmbCy{V2vk612pGG zqG*uN`+RPR32E3{5L4{EiBWrRBE3K8M5X(C`bC38xi_CIF(D1E?nu;de&4{}jwl)= zbpPKiF(D1E?nuwIy^m2Xo)Qw$;OdS<4fpS{ z6b%yPy^>^!32E@Ok3QNwlyncsIV&q0Egn2?6OM?cTrqaU&N=+pay_D+6^tJ3{@+eL$f`oVplS!D%; zG`JolQN#WF=S72r`tzgaWQ~}R2G@fmYFJ+B?e(HTf|i&N&GjIO8t%UbP&7zreD&vu z32AUWNTP=O?-~>h5}GG?dBlV?c>9w?4fo$?C>kWn_Y#sNCZxgBJ`y#Y=ZO#X?Sq8o zZElGPX>dJAqK5nLWt8V2q4}q`^O%qZ*MlT#xPQ;9XpkuHc_m9sNQ3J^5;dIPS3AG& zcS-2|F}K8oG`JolQN#UvcjY-ql=tA0B_^c7FHMoC;r{)>qCuj(&zCGQAq|}<`h8In zHQc`kSu{u}UVD!|Sz^4l%AfbIRx5R`rc>9w?4d?Sg z+fOVSBy?WqmY9$RS9c_8IPZ(vZJ44#Li?0%i3w@&_9uxN?)P_#28puYnk+FP4ZHQy z-xnoO!+D?Dc0Y>-3GExZB_^a{w_f_+iYHOSdB5H6wiFE#+W&S-Oh|*LeI#mleC&hy zbf9REpd}`x!P}oCYPdiDC>kWnc|@|rgfw_xltc~p=Qu@!L^)SUmY9$RS9c_8IG;z^ zZJ44#Lgzzni3w@&_9uxN&gW`&x20&1&^eb|VnP}^yYu^^Bx<-nA1oRq%6VO~#Dp|> z`;$Zs_vf5NgM{MsH$!4V8g}cYzb{InhWqo{qCrCWYdS&-yiUtXl zvs+>!JqK=olBnVS{M?@dgzBrmR}>S{;O$QmHJr}}?e=%kAffX*x5R`rc>9w?4d?#K z-x6#I^&f7DiBulA{Yj#R`+FH)9w5{Y`ul1zAr0RCBvHft{gR?VLjAeFcNY`V;OdS< z4fpqCiUtXdOaA^~Oh|*bKS|VZJ|FbdwuH{>+!7Pg;O$QmHQe7@D$hYe^8_!Cn2-if z`$*JqfB&jzkkEOZ*Q=P2#+`P@OJ4@oZ{Cxr;XF_DR?rffx49)Iq`}*tBx<<74_BUp zgyx^#&SOFvy!}a{hVwa&_ew3Ha~!wCgfzIiBT>Wsc~p5066Jg-Sz9w? z4fp4@MT3O$$LA$6Ar0OaB~iouxpUDVQCD;q`pL0*k&wo<8@_w?Gq>((-@ckP`ow0J zcL(11^7;B!>85YJqMQEa9RB)i=XY@8{wU`b};g+C<#0jrCzT54b&qc(wU+vDh<+)^8_l)zq^*)h*Kj>Rq ze7$?+X?Fw!ExWz?Ke`)kzb<+G1~Dy@Dp*KtGpqzhn8nSt_aDUwet#M=rIW&gnMqUKW(#hwl4fH|5~9lI2}z{;)4| zK41GB?^)yG?&~|{^7#55-|J3&<0C2U3qSJT-C))#fd(xkSemVd+V;L*ek$k5+pp}d z`b_?P#!YwoN%xwy76y6MSU{Zl4?pgUV^lc zP<``!YoCJzy;yr%LN(lL$<@1D(ye-RsTo$=y~eb}02UIgmBR^o?Q_e;L+TYRB-n12 z*YMUU`eWnkrJBLk+!C~qkj5K#e`!#!NYLy5PB^#kFio)$~fuyyP>BuJ6`)=-$*X zu?0W=!P~k6UUz5EU$K{AztX0bPfiO7>J5JmdTr2M-MxLi1wpE4A;ITsHLm>LeckrI zIwQq()b_vY&iU{~DSXmak96yQZg!wS3yFuWiL)|%(4^MGzdfkHVMQ=VTg)i+M?w)(@ut0+Zy^i_wBi(M(-yRUOkeK+; z!`+*|GGiqKy|%vWk?!Mvzi&XW1f^lW#hJYHOh?{#T0k(aYtDbP`_xnamb{qSwwBOB z;@jVSth;IRJp&CA^xE{l7k2;gSw;Ie7 z<`vf^EkO&3D_39K?NCZ{I6<%bHhE%5z54WT$GbO`mc!NEN7ftfJ`uJLT1YUpZK_Dn z>zXZ=bcdI=(h{_g82%ip?O&Vm%~VoqQU7>+UO}*TZ8c~iq1OEK1!o6kPJ&*nZ>OoCqQiCPVo;IEH=(%Qt#ly;U)OVC2%6VE-_tyy~Q;RL;odiPV^UT_Q=c8VKZ};Q{-%a70kG{WK@U7ERxYgL|$%icM2PVtLM?czKd&rwo`0pQG zq&0Ow&_d$G35&W{PJiO3%kKe@px5wS16oM@@{5mmd(QcIph1FO+;eE3ocY6iJ7BZl zbTiH!4W6795?j6XcI^$UgrL_4K5=Vz!fS612wF(IPYNyy*Mglnwm1Oqk_XJ|hm#kKB-&gpjku}-%d+b%f1dt{B1Qc5m+;>2$KC(ldaN9G)@J%AK$30g=T zbnTbA>z=)0B?P^gBdrE4ByQO8jP75r_<5i~f?mwGR^u(#9;9_fifiT-2WWPm!e8xKb_Sb zI_1MD{QEZ_qg{%CpoIiWw$&g(uP2T@Mk~lbgL%dL`O=ezXmuA5dP3V_Blw<>#+@HX@@1ypoIi;z17fnwQN5j#dXdPW_EY|@Mmcr zy@%BW+ocFJXd%I8YBfmEOEt!8XiLySg1O!j)9%?{Yvh#Pmrnbn*3l*H)4OetdvWj_ zI(>BuiT6MGajn}{LbP7fJ3EyfLb!#*->>pk#n#no&_Y5r(RT3y4HEQHYqq_&IBC zz7S|IE_w~`OL&U>pIgo99-6buRQ0tyk8V>%3yFW;?uhQiAKfs~!wGt^?`jEJNbG2* zCbF!CcQ$-62Y7Zyqwa14K?WTQY{a_D(781js zS*JVH&zS-CyX4O&Pn-fX;k?3hi1 z=OEE~Ew=l~k%oQKqqi(e#BGp-!tOPC(Bt?8dp<{NsYKi6Nhq&wUi!z>4)jb8_V z618QnxSZJA`jzb#+?VL#1T7@gx_z;3|1_^pG4_ktLpGF+NHOaoRC1@d`KIZak9t?Uo67*tfTMb%BsK;1&3DRqL zdGG{FDfIiPJS%Kd)mkbc+E!#!m*1IKmT)hg@3b1Nh4HR7?WrfX4R$}4CESbWRINs9 zVZ5tNyWuqt2XoP73HKU)8@IJE-qofZbL){oEm@YRUUi&rpM&SMJXh7d1KSS@%7YdX zFS~FsZOhB@4Y5{(1if^YJ{X)AXz)Dqnty-Fyz>2mw!X1Xq=m$1?PT=Ea<`#P6^Yhs zMfa)wrZowj#Kt#LRI8n6y;6AuPhQ%2vXIEEQ&u$~YgSiceTptjUWx(rVB`LNVDIC(s~4ud?zE2wJq> zIrGeiUO=iyl-W|C!Bo+Ux!yiGEhNh9EYKi9FV>h=L#5_7`&H(vpZ!dVck|cZ*Z;jG zXd$8c_WBoPdN@HZrOH;w!E?}}=de}d3rH0S<(sWo0}Vb0y;Pd}?EPdwl=X75l+|_$ zv;DVEP74XeWcxFL1_^qVU5bEUThomEmrGwrJ13!eqOB|f4c04qX_k5G8y*MZcARei`T!k*W53m zMYjSEx-q}o*TmEiw2;WR-qv4Ps?s|+*^6%vwNKt!^ma`qbT`i4)D1L9&`USn;wK*r z4(;2-t(TnKhu2#3^E&wnG-x5gcbeMg*zcMBb!w5?^HFp5*XcqE|LQ9r=+3w|8aZhp zapsx(TM8EiJ;Sk^9HzanWckSJXKJS~g;#s<5WO=T5MNvE2<`SK3!mx!lMdJJS3uB0 zVz>qgdTsFFr?p2GXdLy&gSA(jEa%;HP(PC0vG)GmjBt#iWx<9A^fNu?VOt)wkl6UJ z89KoVQbmGZEZJ6rWw7n!PxW&u=0Z!*LSoXZKCQjJAXOyjH9U7&=EuJ02%S5ocv+fl zs%Rmx&)!E2sfi@$B|4t(vYc;lKMGJ|$|8PLRP8d$mi{;-EY-?(RzRqM_ zXbD}&1cTiS4fUaDhp8$93IgtzUZt*v;QXI*GDXd$7V&-UI|Qm^R6KBm=RdX=Nz zwwWU>K?{kytOVoQPJ&*1zE*=45~?wFHnEZ?rx$a*)nKhw>+*h{t)L}nA@P9qyK(PB zf?jIp@w%41DBFrk(`U@1@)@yoaXF5YP+_LWM59#|Z#cO(JCr!Z} zFKM`i1aG7*pDHI>uj!qgm<6}Oq~R74yo zcT!ug`URpkRU-V`L?m=SHNKfif?oL!Y;^mR7Tw0R6ReWQI)DpCiINin)JG%>N35nK= z->hPvNJ8VF-!CaEnLvXUjeT~yl)MQ!d40a0e&$#Pa+FQ+ie zrcD(sBove1pd3!nOLO@6*5q-v`tjR%WfhiE^}Z*+-2M9xqWf@+Ya?3^*zWlYcn%Vp zU)%0^qK7{Ry~@ZL)LmK{BCosx4HBA#*V})4Y4<$P&|JhVByO~MyX~F_8YJkYIg0I` z2O6}H&`iJH(q#J}K`+gHZ1+6SpoN6$uFa5x=OEE~rP*ts!Mdcift^~Wc!$?3T1b># zgCJET=+(AO<`pd@G>4DxEs>xXd!n}PvIkJ^+L>2MJ7a1IT1cq;y|)`q&`Y(_&b)%W zqDAe)P8wc7sz{VIb)doLpcnhG_Bm)FQT7}H4HEQX@7ijVwNr|#tkqKZw>N!WYr~-K z(n6xF6N6M~KhgWavUW~htf6hHmTg7#j_9x!RaSQ;y=lFiG|K8ONEHcs@%h?R(LzEa zs-2$)8YJk&TyHg)KV_Fe>97e~7`RTu4NU-B!p;r(y^b{}4F^>?~G zU;B!nme4|iInrv7pchly610#QUK2^si#4>>(0kPO)ywpRdJEg%YiDX(f_bGk@BO<5 zAXT)G7+&Ti%J-5kf?n*$S`FsO%kuZyUO+7&QNH{ZJUPpQUgdjq0a4zYNS5+`Lkcqw+vlK# zM7iZ1Xpo>6`^r{>?M{87e_^3~gD}wGTts(q{44gu=Owg|;8&H}RFR<9x3<1|$Si{v z68wr!t3iTZ!)G$Ikl;7gS`8BP;w-8qXd%J+Hk_ar>q1M=LSlH`B|$IN=~jbdk@^xJ z!`Yf!f)*0x8YUa9pvC*k&% zIWckPycVNc|E}mE;dh`)XpmqOzv=is^oiPTy83QxMJB(un4pJ*Z?`9Y6>|X18El_r zrp;J`9uhj*YrBoNPB6;vi)_7d?GPH4~f>_APGh>=gZ{Z_+pu#m-$E0eg`>kYh-0{wxCYWURGP@wA0q7 z?udK4_MItxOeJA+SUgd6QEoniqgCVYN4?N%>oxYAsZl%pexg4cOy=BuGO;iXn``7W zo><|o-rGDgv$tK>qOPgCqKOXLs&T=!hyUY%8{RC5;2BvV5ww-K^v=zD9kB7g%3nny zM1@&B?pM7!{QaKYZhpQbY`#zPdy4O)|H+5<(zil1f`N44d++Y^kFfKGBbM3q$>gsh;cV4Yjrlul zFmuk{H_5x_wM@hPD%{r&B!|0ym0|Cd_rbSDLh>%Z_m1Aj0}DTzdEer_N(~YriceYz$rJl5H~3fi zBI$|u-m%?*-20Gn@V zW|f5I?Iai#-}z^~+mz2r%BXsJQiOZDU!1$_KlE39+l(+;qvEH&$J>v{_cXq^`GDR3 z&Zo=XVLrDklf1pWk3#ZxdPuO}x6IqiH>i0#2}VtQ{B67s$=kJzDl~7WhXhC8%e=jO zR+_hyVAMSeKZAzk?WKn1?eviFYv27SvgGaMcO`jyJ&8EV%_4B`Zda6R`c2=)nGSN?K~z&^yz+Jap13?HXc9bs;=hIdIC?;GTY_z=lu7W;)-4G zZk+$bhh6D0TWLG(swF{Bif}cVeTSb~{Ib!Wjh|h*ZVd^uHOfwjavCJ)NfA!tl>uiJ zZ(elcyt`HzP(#9Ojk1$yoCXPcQiRjk=bE#MvsXH3=ry%_)Q~V+qwM4xr$K_A6yY@b z9(h`^@8et7zIekiH6+Z|C_9hGX^@~NML3O9tH%|uTs*z@e|t};Az`*g*||bag9JS( z!fDLxe^{~k#xK|I-1ov75@u_Ze#fCC`sZB-7u(NyzxKB`{yl^q5*$mcrCMp^1&x{;Hukp}5W5iSj`b=2tM zoPlc>U#G7|Kp2&b|6SA&ZYFK=0l-u2L%NtmrsJX0~tNYIlaoW}j_ zx)wj~vTgBb`|dMHn5|JfQ!&d((32vZMxQ;}6un37UDWJ&>kJZRYZOmmly?q-o)qCU zUfb=Z#(9SvRt#zX^$ZebYgBx?BMEv^gwr^9$Q6w%?lG?D{zT_`5@u@@&(zE^67-}9 zr}5Jo8#JEx;pxSa2ZqXCIgd7-+-bH(@odm6BSBA!a2j8nJ$vrlFV8AA+IF9M5@u^u zeDW#@dQybb`2L;`hBh8{W^vKSC)ATLTcdbhZkCatCq+1oT~0c=_Uye+E~cz|UOfr3 zHHzm9XBi24QiRj^YS($S^ZxzU;)A^=)srw=qj&@jjp8}wSw@1M6yY>}?AkG(bI{0Q(_T~SNtmrsJf}R%NYIlaoJQwm`{aLGv0ri5 zO;hVhn5|Jf**wcg(32vZ#)5_&@}tIfF4oy^ay<#NH7Y(aodi88!fEswwRhfIa-h|| zx~!gr*&4+&39_ustbOw}e*3Ml(+&5|p@+mYe{zA-X!q6u`Ph{gHE#dfqA9}%KOegyYcLSr`MA(Tcdb#L6(uA zCq+1ozpZm-{^FiL&Rc%bf%PQJ)~NU-0TT422&eJoPiN)toZD~6&}o0HCtkSrrXPl|9FUv2ou{NVp?nBTbFxzkCQtx-IEN^)ut^rQ%R{Kaka|2)1^{_PQGb|qo9M)AC=EF(crif|eSue_+Xz2rds zZ-1sM39~gSJ_m~gJt@LzJbTZ~+KC?>oj){il^POeYZOl$%Q6!5qzI?cxb0tRm$~bd ze9swM){rn;qvDgyNYIlaoW>uwpFQ+{Kb@J+{bpnh39~hdr#@yG33^h5(>VFWe)ASJ zo|Qjy?bsR;W@{ABkIOO=^rQ%<(f886jkhm4EuXRa_!<&sYZOn;%Q6!5qzI>R(?-`f zj=kmhe4mMbt07^wM)5qqEF(crif|h5-~D!D`|QyCrN3QPL&9v0;_0qgMuMIc;WQT4 ztXiBmc#r(2A12q3Fk7Q|N^O>rpeIE*jmM7Lw5YAG%cm7nYe<-_Q9L_0%Sh0ZBAmvJ zkLJZbSN$Qs;MFNLB+S+*&U?=?67-}9r*X{fyA?CfTRs1|_KF%3W@{AN>T(J)2zpY4 z(_kL}39~gS?gMycxv|9o2fR`H@Ou~5a1OQEZQuB|%9+wxMuMIcp>&pgwB1R?O6Q(i zo7bFCL&9v0if3SxpeIE*jTtLSkJsrlht7Rx?!EJB+S+*&dinC5(s)ygwyzC`M$+M z`9I;Uannhdtx=qrn`I>ENfAy%??Hdr({E3lLBec};#^*-y@H@8ML3O9kTN2$P^EML3O@<(v9KzO4-xbgd_0wnlNbah8#wCq+1o;>?-zZjdzcuQ8+Q zNtmrsoRcggKOpEy5l-WqGiMIfRJH!JW9mtmtx=rCoMj~FNfAzC8Of_YmS?qW-Nbql zW@}VDJDLPNDZ**&BYCc-s?EAwR!_ogjpAyzEF(crif|h5y}DNZgM7QarcbFSVYWtb zeO#82peIE*jn|j&o3F7#-(r`kQ|n2Xtx@qBEE4pj2&b{e{iE|jQq?-&Ur|rOY>nb- zt}G)#Pl|9F|5$Ep{+Oo2_b#j_VYWtb%~zI@peIE*jm6uYluws*xL(Z}^(4&JD6SHd z+7bwQQiRix^p_thsp`X5$JCQBTcfzfEXzpHlOmjkq`zFs!J$$P){`*X?!(rumE~X) zq1QD}if|fIs^wA+)=D{8-iHxJYm`2Pu+EDFJt@LzNczjA9ITaca0UspHOjqB+c$~? zJt@LzNZFA~iI7V@Q8pTy&WjWYH(32vZhLmc#l!LjHgI!3Ntx=k~!roLQ=t&Vy z<9)e@@8w?Je|utA5@u_Z<`Q9VDiZXh2&XYt-o;b$PF7v;NmmkPYn0}8wmMh(cR|pT zBAkYlYPC`h=28yUkT6@LG}pG(z-2kuM9`BWoQ9NYLp4=NIaou&Y>jfIkK4zsEC-ti zdQybbkWy`)rb8(QYe<-_QSnMW67-}9ry-?Uqm+ZWl!G-S%+@Ha4TSeWf}RxNG^A8( z)Kn$qU=0bgHA-tW;kzP1Pl|9F4@lY3R?3jArcbFMVYWtbg=?0PpeIE*4PUd&cb+=6 zhJ@J~rL|03IonhhEeU#3gwyy^%JR=79d`QuiW(ATYm}=kTYg1?o)qCUxGH|d;}%uE zfAU0`%N6Q|YA^n2QRU`ECzXGXXJFIAI-I^6T@Bh&g9M}YJLBuh5wDz*Am|~X??%_% zwbUTNsJ*`ax^mlrrzZ${NU#nc-#H0J?Y!qVmA_teRziaw68dg*g=5S6Ai<~s4d2L~ z%V#GDdPuNM72gL5MqR$(8`%kZLPCQc5^NjB8YCDsaplFb)7*Ip4SGnhjT>u_VAPUz z7t6e*3lbXikYHOq)*!(s)n0bsg$WIMNU+Z#)*!(seTH-P*LjxO!@^Wc4+(v4T3hEE8i55{%M3e}!vP8uXB0*&b_!czAi=0X$9&OBI;V#O+aj?B2}bR*{uiy}SM-oz zn<~~I!Kfwgf8I*IOAiUQ4Py-wj9Px)=dycis{Ejb1lzc=1_?%8@%PVLDF^8x!M1v= zL4r}L{cEy3r-y{<=}tN=(>V!7=`&2%OXwk?&rN&JTWXMC)UNVfrR!JpkZ|wc)tuvJ zMS@ZKO&^u4C(=WLeOa*v2}Wt!OxJhmA))C}_tkkEW3U2iAB zD9tOUC)*$NkkI^5cO7eaA0!xcu9P3&`L<8|bm<|X`MmD1(Ncp1qqOunR}-79cdI9k&7ZVf`S+NhCq=kt zwLtpX+e)ANFc}{tVYWu;nP?pv?Hpbb^rQ%?8d$AISJ13A4+n@pC0l{GGoK z5*a)x!f9M58XL;^;43mdNWyHp57|r8Ymm_EHhH`r38(RiJgYCH5BX9VA0%P6M(IlM6{ncu!`fclp^(4&JsQBDI67-}9r?H#lxzEcx-&Dp2Ntj(mxjkilIw#@x z+$}vR!fE_R`VyDOx7$<32T7Q%QM!li!TzMjEF%$l{4XKlG$j4ynyRER_)RQn*IjmyC% z!tVrIs;7vc(N)UYuVs9YgxPiVOF zgakb)!f8nQ%QaPfC*y-8%+@IPHeH=4%Sh0ZBAmuM^6j>HZLPexeVrL3%+@IVDz6*< zo8PmB1U)IjX{;=1@NF3%T<_oGx{xqiqcnB(ZTqv=AVE)xa2k^Sa!plpWPFf>*=3aE z5_3;;XQ9hXauAy1m?uRz4M~5snyS{6@j()1Yn0}8V=w>S-v^1vR~B(#QPo)qCUq*N=U9L%L0tRZ2xMrrLVqz@92$Lo=B8sAG9_@$&l z9UmlNwnk|!^V+6#PJ*5k;WV@!Dz(dUe2|3M8s%!smS2&eCq+07jx-!{$o-Z7UAUU; zw<2Q@r~$nA(fyUHmRsHZJsO*cJRmf!=qbl7HApb3IQAcvb4H~!=pmtLMbBPtsX-!+ znl0_~l!m4v^E4;)tml>*BwQMFQFWKhu1rYYN9+l8QB5m)%5_T(5{&BJ{()BB2R$S- zt)$-v2}WIg^#hd!_ANy3oE{Qvy~I5eBp7wY>JL`d{b<$1okt$DaWt*yIpr;%6$wUN zbo_&rjn_+Q&_hDgik_I>QiBAej(_YyS?Rq>f}n>4+qm(wBEhIC3H0UA0 zwtB2Vf>G5?9;%$(d8LE~JtWxY5NnWNRPWvom37gUPnRAN>}`oPNH9vZ&-!4+R_>$8 z)2vTMYn&~A6|beg%A)icPJcc{&_hC>o7P@iYLH-*ehbe&vwVV}hlJ(%Ej36mO26s1 z{+s$$^pId#62A`;jMB9EN&A!rJtSBr#u_9Tb&cd#oyIMjcvkd~U~M4QAi*fjE64u4 zOhO~_pw1B0QKDRw1fw+1KXYbEgB}vBYsL3LB959Z;~yyvEy>K&oY2~9%kPSWD+gVa zmci-!h&`b$8rOYUFCoDwtxKfe2R$UT{-CwjmiIw|QCcTTe^>O7VCyA*A0!xc)S_9H zg~{|0dCC{bomrWY z%y;P_!M1v=L4r~Fn=@M}KjxuM`(C=7# zIa}Tb2}Wt!OxJhmA))C}duv;2kYH5QhKq6rdPuOP7mxP&*?(o33^h5)6j7V?PbyNK@w(bls*MHJ=<%LpeIE*4IP(|e$hth7cJKh+O>?< zC_iJ*YmlHPML3OhWqfe9^vhf+j!POa-%g$XY9$z z?_PrhJt@LzaI}wv*&3xY2jrZ3uR(&I6yY?EkRGFqejj6JVGf}RxNG$j2sjSrGATciApJ+DE6o)qCUINC?T zY>mD+DF1{jnWxO;p7t%^rQ%D+DF1{jnbzOP7EPIPl|9F zGV3Lmc`~&!Po`WyXxB1Yqx5b5_S-oBtVqz4BAmtt@+JN%efrEUV{WZDZ**!JT<9Z<}y#FTt8^nGFqdw6dl@hA0+5W z5l%x&wWjew5@u_Z)&|1+AVE)xa2g!#BVo2iX{|Uwl)F8nqUDNbb+ba_UJtQ=( z*cTJ`Uy)#xuFcx=xyut8^pMcBqAjwP_d$YDevMgzpofH}6>X)q)F8nqT`PC!A(tcw zdPuO18$T-&jPk1l6B_i8U|T)bAi*fVb}^wr4+-`;#2O?R<=0>)H0UA0zLQvk1fx`2 z*0Cfs=pn&Apjd+hqx2bWbK``B20bM7xoNLj%kPQ=qx4&lbu0;j9uk)4x6~lPDE+2o zy>mi?9uh1|;%7yIQJOYo9ZN!k9uh1QV+|6F(mY1iu_QF;A;Gde)*!(s%`0zObW%ct z9ulmh#2O?Rl?~f>B!f9D2x!2@QIh6I$bJ`CXAv+oE(0rmV+F5cH5> z-8a4u5{%NigzRgO(4dC|>+rD#2}Wt1=&MGpzKMPdySjMBAPwC}AWs;8$zw@l|G7^Tlp_BBWl^pMc!roCz{ zHApZ@*Y>9CSM-q3_n&1`5*j2JrQfvdYmgx5A)()~_Hwqo4-$;hw3)8&(nCViW4gXe zf>CV4#a{_MB-m~%cS$QAlYSZ5SFMKU6q~Jg%hQNsf}RxNo|Wv9R>;0;wX&~T4GFU~ zDn8|y1U)IjY3P`N?5j3Z_EoDPVYWu`?A&r+wI+g|6yY?uTPO*$?LIU`xxMa5=ylDL zBAfgQ9RMtjUpRCPl|9F+%1%Z*&4-jf8+f{ z=}8ezgS&;2Fk7Q|QgG9rPUViI^rQ%M?#VYWu`WLnv!83a8k!fD7Z zX^pb4S|R(Y%^+d6M#U%IlAtF=I1TO=O2TZ7;)&q#{-X4x2&ci_LP?mdQ9P45-d~iS z6yY?uTPO*$HHs%U$NP)YlOmi3cMBz9wnp)+=PV;ZPl|9F+%1%Z*%}p}Ax(mw6yY>v zm$Y2=RV!p)wR#d}Ym}Z-Ze!l%zG_VbJt@Lz_?-&N^@AkL)+jx1J&X^MpeIE*4cR3v zmwnaB^@AkL)~H>-JG`s`xO|rcJt@Lz$gbJB?6Y02A0%P6M*Trfun+kz33^h5(~w=W zbJ=IRQTExcCtH=Rz zk)S617!SdQybb(6K1nUzCK| z8ns*bU0HuS33^h5)8PK1B+S+*{VKz_0SS6igwyaTs@z|cgxMOUsVj_skf0|;I1Sw+ zRezc6v)z@1*%~$O!J{#bLxP?Z;WT8|>{{7pJC}X7yOJ0@J%B8s%!s zmS2&eCq+07jt}aWVdH1+D{&)Z-|u!(D`R)`kkI#^9=jvKsF%l{tb4a5THExH(D$Dn zgCxPI+mAR!_ijsQ&_hDse|pS|1f#Cm{Z!q%EuldV34Q`S+z9o7{u>BcpkYLmg=bhe49~nI)*p7}h zNHFT{8%{6lS1nT%JtWv45NnWNlxnBPyyzjJdO8EU<*y>asMX|s$lh%Uf*un3+_Xm4 zQiBAe^jk=edC^0{^0Ag0Bp9XNwCvrM_*L|fVE!1t4-$;hw3#0BqK5?Y`B;MlqZ%Z? zN{@NbLxSa1tU-cNnpeu+ZHZ?^4+)mLu?7i7X`Y`RE24)4>kqL82}Wt@BYU?c?t`A@ zgzU_;6vCBiE^2Y7ak~F@f}n>4>vQpakYH5%-<{CPm=`@HSTBt=NHD6h!tuJ7cj7+i zA;J1}tU-cNqdOhfO8TIO1ltL*1_?&(H~QFC#F8F%%Fl(xm4P`kHrD`&iA^TA0?(WQ4c; zdrZ)iB3vC#RzVc9uUf6_t5%K=+O>?NHGFk7R1ZP{y(peIE*4Os;-Pu5Kox5@sZB+S+*&6Q+Mnb#mePl|9F+%1%Z z*&5|*%U**7Jt@Lz$SR1Y^@AkL)+k?F_8KJUNfAy%RzcLtzG{W+t5#3KY>m>=NBTv* z1_^pngwv2!5Ka4wk}zANv=r4H#@%;Cf}RxNG-MS-F8iuAjSt$jjMgY$TlN|x=t&Vy zL)R^7s?z;MNtmrszP9W&NYIlaoQ974XsVKZw(Ciltx;NAmKncZg9JS(!fD8=_*_@z z%0AomB+S+*t!3&C{O)~_peIE*4Xy?xVYWv3+OpRmK~IWs8oF*tQ*!~YFk7SatCSTA{#lWrCq+07Srwn_s$AJ;y9)`kHA+*L)WYq%0zprTa2nh#l!VzD zrLBAEJ@*Mw<0 zlz#cLZX!X@)11)SYs)()p|(Z&{_6xm4+++N<7Y*JQQ8lmJ`a)}5}H=DHPP}uNH9vr z6J*^)f}n?lrWI`!wbUTNC>Andm_84Z9un+xh&4zs%8!30?t>l@>^q4y zNH9vZ)8~27LqheW4>|FxNH9vDVfs8sdPwMV)7opx?}`MY^jna16A6MI5|-z;)F8nq z{if6BLDEBlWl8)#NH9v%rmUMt+y^}*SSH3ABp9W6O!_=XdPuNrk2OdzO7qI}d64vw zU>zmaAi*fj^V8=+(nErEtyqHuqqOu%p9e`#b3$vcEx#)gYFm`=zfKVJkYL?6z7GGVMl3AU+X4HAs<<2#A_poaw8 zhOq_-M(H?JI=`Za1lzc=1_?&_@wUW$&_jZ4^;m-hqjdZ;eV#BqB-rN=Ymi`+AOB3; z2R$U%cM@xmV3ca7&x53ggzBZwgCxNyeTK4*K5-xPkkIF*y=pD<5)zEkZy|jiBt0bD z`%l&MNia&k>GZkb^pMc+IDKw72}Wt!OrHly4+%|=+QZuNS&?8A+i>w$LJtYH+v3qa zzgzu$?Xxgje~I5=zWjSk(32wEeQ>mogxMP9cbNAYBV{!UA?Ggn^9PqHuVu7G=??R9?vn4zAVE)xa2g!#BVo2i`5orH z1_^pngwx<|p(M;MqudVjUW0_+t-kc62&W;voK5?Sk}zAN{0{S8gGA)hcUgxMP9cbNAYBVlMQ z+DF1{jnZ6OP5|>7BZ4 zTcflTl@r;#28r0?ehCSuA*EW=_#g?hHA-s(;eC*xCq+07j`oo-yNq%tj`{l_p*5r~ zm9opg$jHe(6CCz@N?I{vMra5qUspT9I>p675yI~u9VQwR3zsvm7eB=oV%3JAmP%Wi}GhaB{X7BsEcY^(VBD1`yjz6e|A+u zgB}u^R?_c-1f%>JTnP<&NU-%1_e_vrl%6Ff=Po5QA`jX)npWi0(8RMM!6<(wT0(;! z5}H=DmD=)skYJQQ+by9%4+*w$<7Y*JQF=z5oV%3Jpoaw8>ahk1M)|Y$5*qZ7V4p** zL4r~K%)o>OJtWxM5^IoPlxoYlO9_q0)2vTM>!>Z?ISKt$7NyTn&Rt3n^pMc!rnT3W z8YCE{--4XGlpyFKVR?Q_4HAsfZ(7b>N@&nSf@MkkK1eW1)25uel+d7u1k1!&g9M{A zkCC%;6B_i8U~M4QAi*fjE9D&Cghu2+ogu2DL?tH)Mroce=kO*p=pn(nR(u~M;;8bp z-GqjgWO5E~>1j@A?X~51MZ%SXE=tQ_Ifpkv#GX(WjqARwmylqT)+N&KgB}vB!^h8x z1fvd>^9SV|-o$;-LxQcBSc3$k{8?fNjmU#GPSmD~zAF-p(lgQI9NvTmJtWvRjPHX4 zqx{)!2@QHku#FpQkYJQQqb{LA4+*x_V+|6F@@MTOH0UA0K8IL?1f%?!fe8(INU*mh z)*!(s)t1wC6B?1HS)YuKS+q>&B=lEVls-c_hc`jcLqeaMj%KvfAi*g87UUe>1VIl8 z_x@ddK7Ljt7^UB|oWq;YpofHh$J)!;@;*o~O4FvC!<*2chlHlbbbXfuqoOuklrzvn zLUW?Ir!DdK@#L^IL)>?PIqyU5vqO@BXTo1Q(D=yvfl zy<(5iORD!*KlQ{Cxzd2|2KQFtC($6ms9>wMlm<2Oi|Uoy;O}2nrhKi>@hiB4yIUU~fZe)28o zQ*VAB_Ny2b-k=hHv6igVqsMH$?gOI_shlu%J+ILk!6>tx#(6TL_)l4Vw(!GGX3%4{ z`|bNzI@EXc8m$po#wceyjdx_l){ipE`-SYRYEjM;h_{CSsWP&DU9Zs^!6>ucmA;Xc zXZnBQ+vBFwW47MM{rl`**?9JvUZXXFQD!@h@8ljnkb9ZbuufNc%vO#6?K4`w1+6XV zJ8z9(l-W+>C3zRy$vauG>wR76F98Fu!|&0OQ#D#67-hE8kliVZHnRHc966bk z9<%kjS6n-?vh#<(NUBwh)(A$K?KE^hCBW4NZTNs`B=-VuT*ERl|SBUZXXF zQD!?0pQ7^7vhsxtxhNeGBRpkzU^qB45!Tyzw^&P!NYlP-RACBW4NZTNs&Xj@yV7H}dsaVd zIp{T7BeIN9&UPA_{v=i9QVw>tDCY^p+Hd`;<)GJSjbN17?n;uPa{VvmU>ADK*85ny zAsZ&;px0=XK$HuN z=`mY1v}P&gpx0=Ph@%|gG=AuNR{qYtH_iL~O8ZD%wDkBHG|pCy)81Ql*uN&|_=oDX zMli~3r?JiFC+APCa&+T$kDgplkJ)CBWjoY{TQ+~w!6^h?(zO0@ev-P@d+buKfvvbz) z8m$qGGTUi<-%!a1RW>O$J8w!oJ!Y#$ueGvak8i(@*JzDkl-W+BTV<1c`8z7bGY?Iz zr^js7II;RmW%n`dy+&&Uqs(?17tLQGpS<0liaiHRuBXRr)i`>cpDG{E=;Sq8BN%12 z(^%`vM{D<+aAa}O?=PvR$86Q;w$%@nmsVciYqUl%%50~x&#Fh)4*vY)V(Y`st*6Iq z)%beDZ!2G%ZEdyI2u7LhG}gZNrlCLfJ*&9%*Q4s`FLqn)+pU|=u59bf}S*?^fb{}JYMQQ(*7V3Y zU;Wf;kkIP}kNpx7s`0I~qpp*gFLR_FMIzYlecb%iM_z-3J|FX>3DszncYdSPN3ZH~ zUsn>rZYbY>mVM|oNa%YuPnuAT6=b*R=cHcU=8ko`k_dJ~b%&m3RAyiCp4T8jPnuAT zr=)G(SyskB_TISZB!b;gt)G2b<*(Pj<26XolO|MSBbi11w6t@&OFsjNU~AN=m9G8Y z@){)QNfSyh-2aWnkL8`*A}6?z2zEpD-i{|%E;#N@uR$XA*e@ZW8b?ao;7$3qUiz?W zJ&9m9RF7+WVr9>L-|!kF=t&c*vBw!R=iMx6BG?*r6uv7G^rQ);JG{15{(^kF{pAD~62We$?lb&Iqz@9Y$9@S3)$ld_ zLfYr`B!b;go&DV5l?R&AISG2wglc>)ZG*2QFVP*ENCaE^mJXA$%knD{^rQ*ZkWwv| za8~g& zAr{LCE+m4jQDc1{S+yBKPns}|m!$pij6lx1Ek! z>V1&Vd@y+Imyl46Go{~WiF{ilq~C``u%$0t%8%V%Gz}8;qzToSE8u9VK(17y3Mr z1U)1)e+)H%)(A$8{rRu5Q@XX)NYFz<^Z8H%XpLahnKSZCGAk^lp{28VniHW0z^6-sW&7Ek$F*`F zvB%2uYT2R>NHD5*?~`Qrq||ps4~bAxH`gG+ zsEyY6{)Cq1eN=s4|+&w|7E)TAi=0Z4>`4!a*!Sp zq35>w`yj!n334Cl@;vrf|8BMH*-n?|Btma(wW`lBT`!@BMCgZYejg+l^*{Npu1?mk z=pmu+-}-&y?}`MY^qYPlSx=;ggnq}NN0{Fg2}Wt!e8tyM<6lJ&2~CeylWm<~l;$yg zKe4_g{wjJ%XigM*gj*vRrFrFxKYWlV&tp%xuI7)SN0=HU7^Qjs&j+P6=pmu`eCQFT z28lT81ewK}($JF3Jk5#FBTNkvt{imz###pdl)R7FqvfC@LO*Qt^g)7ATKjk*`9A0& zq4kIK`yjz6trMlcD|$$1%_;p|kzf?taPik3d%|_uZi@+@C)T+-r|tx-^9!m~pC9|b z^9{zHKxp2zVDrUGAsFS$l>|W#3C+8t4{#|2qck5oCn(XG)&9!nLVq z6?@9IL3v%@7D;H3VAOQiR!iImJtQ>mO1}>hjCw}$L}?o&H0UAWTa$_VAi=1&UE4XK z5qruuXL()U#!YCDV3fAorEQSVpofIE)uj(`DFmamCoG*`(L+M}9AuVYLW2aO4s(4n z34$IH!=#T)+6GG@7^VF|%MScHLC`}&`+(Br2MI=9?fS?P8uXCxy%J;A)2zp4k_y6Hi2u5itkhVdBpofHh z$I^$q6oOG&!;!W@f}n?lulp>8V3g)D{XR+EIXxsaC#vcHRziaWqqP1gZG!|6d%|^n zopC7yqkKI$LC`}&^ZC8@ePby^9Cd=MyGz}NmSpB>PW<-U>j@1KYFpGf(#DatL4t@q zfzWa{eIFzk<=a;Y4SGoYUFs$0ANS@`2uAgBZO#Ni4+*U~rN1i@jH+>M=Y&S=3D>M6flAcTR$yG@-Q4 zQ`1rRpZt8$@D%O3?mj|IhJ;=>cv6IF=sY!evm}4ZN8}0EJ?Wc>^x~gHFTbu%swmjmK}RZ1iPWi7HdqeA~?zl@W#VT7lN6&|-}VdeVf_I!{e!VXyD!i^`lE|9kDa zZeB)cd68gSHt3O14X*kn5$vY9t5 ztT91PnlKHWg)QZv%@_4`1G}!fk5HcLuQGyd*`P;4HFTbu%s#7?bra=$QM*>4-TMeF zVG{a$%#$WmL+7c+L6Qh|(|l_G3`wvp znBf^FF}p&GhwNme7}U1fg;62Z25dsBV|!qualCry;kO6nw;&5 zj}Db}6E!4)tx-RqB}{^zG+`Q2yPPNMCS)EmuVuEo51IAi??W|=(CY?Iick%PZA!qjdGMwc$w6lO~kbTBT~Z^@F^Y*$ve{e)|>f zgGB5}5vrl}P+gTP>n7?+1iPVn``2IMeUP9hO{j*}L#1|E$hwJo62aD}FY#TGpeIcz z?dx!btecQ}JFjJSL-n4TFOWV+#GVwP8op*(t{)^3Y^jSL`Z-2MNzjufRKwSh%k_gK zg56Mk^4ZUHb%f7LNYIleRD-JlNd&v0I(^J%7#Sr&Pnu8-t_CC#?1t(d?LI>(L4uw% zp&D8bmHOyBSw~+_BG?-BndI$X`e#Lgo;0Df)!DH~&1D_^3=+Y1 z=|g5s`u9OXzgP353DwYgsMIcVSx4W6M6g{tw>Df%Xu2~`notd`he~}kmv!`ANd#M? zzSP-m{ys?1lO~k*E2MK-M=$L`UdwEk@5(GauR%id!Qe>|s-fc>M;KI{F$C!FJ_` z%$oEXBs4!aPnu8-9hZ>NhFsRs*N_OdMrr9|8YJjR6G}^|hV_HImf5a6w_h6*TD}HP zick$5m(W$YvW~unM6g}GBs_HzT2C-fnotdSgSvM@F6-!PNCaD>zQuP%f}S*?w2n*2 z_(U%2=%wDyYnkopiIxgtLhEh8lOj|@O0}l-gCv6O>bs#mNJ8tM=1CK(A*EW=`au%G zcJ+2^!^MQwqs@~hRD&amlLmdMYZuCNpt+BguYG>~Lf0Gk^g)6i5}H4z=M<4(RQ~1{ zy51n6K@SPd=R^C7zlsE-o_*#Evx+UYq(vB%26YFPsalvm9)NHFTC zMPIfur-&XBp}cCYL4r|-9P*XU3r{>NdPu~j9p5<#M!opaSFOw`iak~iR?8NP<;QV4 zClN}uYPC3ak*+sL+y^}*LV4BvS&@jNzSdO*2@Nd=&C{F+B`2R136`RDmwesIoTAuc z>64~e+6<9(1|)D^2Q z)-~ga`-nYO4pz$^mQX%YgG4CRs@02*U##oT6B_i82<27tXGMZh$3M2Xl{rQ9kYM>3 zrwkPbxKdEkXd(V3g*S=`|*?CtO$a$Iz2X4HAsfJYUwIC+>qD5}MD4o>Xd(h@-x4T1gUr zS6Y(U8k6Qk=t-pp30Drf{#Gr6)Atd3v>bGVmb>ZuAi*fDOUU~3#IvG@gw`L@?}G%R zv`&;>V?qxJtvRK?D-w*-x?MVb#GY_ntXME%NH9v%zs%E55cH7HTtY^EmqIW~ z(|>vmZ|n)z^>wX;1_?&_`eTBihlHki8P#735l4Nkv+)yz<_6|zPRNXcr4UM6l&1gm z8s69w2u<_p`yjz6-!4h~Dtbt0nwNR{OCcEL+gAyK9uk^Mq`xZ?jPmWoghuQM*VQyH z^YoWOFv_=g69hdZG|fw&(^3dVX^xTJ(}^AuzOA0nAi*f#|BxW)A>sQRmO?N}`%z?` zeuAKfg!Y}tjI^Z?jPgB534$IH+G`|Zc1s}`rN1`p+{79{>+Dmed_5w zo#-K<&rRkaBs54cO1}kJ2bmz~A>rQt&r2Z~<;%weK@SOECN70wlrQHK1U)2t**?GJ zx@{7SI@HyD5*qZ7@U@zR1_?%K?wa1yDfX0gpYpnzKgx{ega!#l`TAqxKIkFg>x>Bv z5^+>nb53aZ8gl7rPDtH1p+Q1zi_%hC)@>&=VoxA^9X_E!f>FL*lF*=sgw`L@?}G%R zv=)`#(}^Auz7>|Z4-$;>?Zm`=#GbOPR$kY)4HFt97^QX8^qx-ikkERm)TtA{iUgyy z-JZ^`=pmtPb(yW6&>+Dm-~W&x=pmtf4(UCeNH9wKQDohALW3R>+INyJKS(gj_Xj03 z=po^Ijg~?%O10B_I>nx{Z>hYl>ZQwb5{%MknBLQg9uoT8WDY{&K1eW1zlC)DiXIZ~ z{ij+*BpAguT-@@ahXmVgaQ|_-%`*cp&B|*O=n^2c@rdp?cPWD5=rRuF;ALM4V|YZv(Fl3-9%Rs!FJ=$ zVRtbS{Fc&$YWT73Le@=`^F{4ifo>W<_bG}5ztJ?I8h*sRTt7%6*bUXV2Z01VX+kx) zevm}4H7fKV!~{KQLTQ3X4 z$U6FRzNlR*&>9tb5MqL!G@-PVYE7#FNd(*7hn2xG!M=qwp&B|*O;_dWc@rdp?cPV| znINIh$2@65HT)Z_m38zpNCexyE34^~aPQf9(u8X0JT*PVMb^>#`J#>pbklrl|6P&L z@73BeX+kxmRBKv4NFvxx^TK`0i-e{-8RsZHX+kx)evm}4H7fKV!~{KQLTO!v6xI*& zT4uX^H?)LFXg(M`DMB^48jwV=o7NlnXGKEua~VG?J!wKUblsAy6v|~CeK}v$h(K#p z=s}1HdeVf_x(Z1(WF5WCf#kK!Zd(80?}G&U76MH|H8}f|M6g{gBRq8yT2C-fnotd{ zA0!cMjS4*oF+oq7P+He5=_xLuk))o1`lVIOM&?BK5x^78NaglZO zH6()V>bsVjV?yhn=1CK(q3f3P6c<@XUqd3;R&TfbibQCiRm+uHPLG6YOqkfASnsWo z#go@f=)cmh(<+^Rys`Sm))&^vN(AZgxT$*Qq`%d5Z+}(gfbG@3S^mDuzc$YAUTavM z$-i9>d#$q44p-Hw$L#+caCzN=yH+vkst-DBtnJHJ|a zapARfo2_+u-J9FJSm}JjZ6)3QwpS}Vy>w08B_*+A#}4@mHKX!Z9^88fJtR!e{i+dP zcFDIrVcUGo+4l}25l6jNdHSxaMNfa#xpQjr-+enQ?{>;31F|f5NW}M1nc6wuWcUvG z)zj9C?jy@ytz7@+8?4_kRueov3PBZ5&+p7cs((BvEHI?TL8hzCcln}5-7r+oO6n+@5p$19c3j=HgK z{8ty(y}$k|m33y^ShwL07dQJ=eP*@IJKerhK5qOE`|@Dk2c!Pg=9S7VAKzFvYLR|D3%j<@4}5)8-eKg0L->0ajd`VV{{L>M z+jWymn*FNIXSd4_-(|;qh5sHI{VEbyZSzXy@g6tI8=NE>lNYR;-}v~B`F;lsj|fKb ziDcOmqt?k+zGLTn>mHK^^Y<=U=9S92Ki*i^ukONTzv|cB*UmrRdvxA*r8fuh&PmAJ zd`&CztNtdx>W44a%vaxSm;ARsuP}!Mqka;-)kW{VH!l!k*NfN9zgu;u{PaneHxYYu z>RM;NaHY*Js5?d8$C>gz2Ay`k5FdcL?wv!Ay}^DjPHegly;7DP@=d#Z z>lJp)uf6Z7NP|Rw`Fd`ZuV>B8CknB{747r7OGo8X$1R8mMujJRo)F#pbjY_{cU1oO zud})IJSOjam5*+y`|;azoBgWi-|mptOdFZ6bi(iF+OyK%OTxaMp@*F-8pT%~^B#|l z$ggPMEg~3YY32DNCkU~t&#%^f@aoySNl3#etwk-&wHOlfa z{k1U>d%|_?@14v0IHLDP`F`(iS8A9?uVuDIS$@3bO6Q0M33^h*=o)=i|2Thxykr0E zOAQicyC|1Gu6mPdkg$AEJt^YK@AemB>M!f%cONy}KPz6#*%}qUa}u$qC9&GR`-#T* zn>y!{&)lKZAYryf**DhnpnZincF~&oO1tio?|s1XgDp2W;+);Y<8p)DJMG%+Yro;n zPWhUHN92#)Ie8$jWjWlfBgZtmk1yBhly|vjM1I$`D-E(=qF*%$OKE#_+DEh>ozOAg zz4OTYfCqPr2u4|+n7zNZ5a)c=AwS`wk@?D>O&LUwD=Yn zNP~ox45w_pr)YdRXN~-YS9Z;JTqPUA`(PB)f0nKE?8^C#tL&NYd&cypyj^n!5|%$+ z{omb1W9Mtu$j5)WYu@iBl~ zJyJSv@a&OIdHWunMl|KrUw=Bh*{|v&HGt2g25@bk3nLB7+m*0XaOz9ji-y&G?(1=P zL@>&}o*UlWP6(@CRd!oAH}<%6-eK!)oBb-Q!(BIRy?OB$7YNIV_E~Ei(fGbyhy3o1 zM&%Q~x;Xk(jIuhTD{FhNx>0`luiNEk%sFNbJtQngy=?DcqG7eyRc7D&Fo`(I@_8ku zNr|&$@vuB!^OFZdnK7)+$}7DtuO#)|Q#Z+9JEf9ecFy$!=pnJ*y{}bn`O~yIcjq^> z>y@`#&_BQS;k%;yVAQ3{y;XT`+{8L}=VLDKme-vzH1FMJzj=(xvezrmY(2G3-$zUg zx^c_=Z?6u{PrPB%d9f!Dork|(`DEynI`_`ojO?EGKV(q;(gi=yCBdlv7rb8SyU*l0 z_g(cE(>EV}cb|OY{+;Li?$_5V^Y6T(?wb2Y%Ts)#GOqrLI?bthCF$iH+b17)W8eI| zcb|y}Mh*Po^~w&_E9zW2Uog5?zQv6G`CVt8I``S91G1{di^F@(YJI`&Cb^-ZQ`Pg#r03L+*_rNN}-hU7m_-!eaZ!Tg9|)L41C*UHm>*Y1fy1)@p|RIORlV|O8p_rx-GXwzVp>X z^QrIOK9C-J|5|&Yc9yNPdbfPiiM3_jhn^JSYD;ha{SWy!cjqk#qg|9s!LAN>=&hUN zLw2j=@2xSvDfiKux8*)sFSQ)Q)fxYI+9r8-$*;6VO;3t&wbxZQ-7NoCo4OW+(JqR= ziiG7+`g>D^tG)8hNtmrs_7vP#a)5lh7mx0lx4*yJT>JX8MQ1tDsDEG3^tHRbjO~Bz znLqV&|9sUq-UvVx8M%fptZ9}Q;tkXU3+c+p+ z^5eF1Ep4B(_}n`CuI`+4Uem8~dHY-QyXQ}J8kGNQc8_E_SHjYHpRxsc-myLMgH9Tl zueM_6h+tIwtF{_DAiw6~p83avHyXk;$S2Bs%CbA_w#@fGVn}|&R%b^VBHMVT@TCbn|tSb9ndcydv>QG^w@Lz z>gJ1@{i+MT>6MRMsegXjOCyHxSCO#yp}j^~Hfon%`BT&T=hgjBjR;0r-gT+;Ic3>q zGkfOSNNLb>|0zT03E$PEX1{9q8a?yPrNp^)vwI^A5|)o0AiYM?nvhcMVky;rKjG-?{Z&B_uiZ3Tm7k762RlzGYkf{b>TreD;kIhCpY(FlGo`G<>969I z%4bz*9ZsKB>T5@1xKhRy}|28_bQH+`qj8APaRU* zV{+vjDPPZBq`jPz%legmue?&0)h+H-TqE_Xxz~+|G)SDi=H$wDQUkcU?B(2jdheo9 z>R0RU*(o9z^{+OQ%UYjHgF7DFqv$7J;vvU9ExnxK_kJ{Ha%HxZ$erbTjek}DHF_3< zS*cZjDOWBWBL}E)R3?Hyi@d*kdXe?vbOAcIcMD2uUO_!z4L3w5112Q zD?}N+u9Rg3%O`#yB@9D3{*YME$PawX0;zxFIPk#g{oS?@GysE5Qvd4qqF zH+Zy^k6HHiW<87Do*a-r_sNQL>9KdNWnZkZ=5alWcTXIcfAnpqx%80OOun}s^1WSF zmTGh6cP~Dca&X?mJtBfp;oWGz=zHsQFE*F5_JSqbO554q?Rj-8>^r%#k<`L3mvWcd zS$6ARwkpQI@(~y=3C4n-s4|{c6G6*AB3Bt~I3g zw@qp4Beh&YYie0m*=)vza2Zs?n8T>?CWdu!QOST#x7TFQCu#y*F!sZjtEBC zmp`Day-E&OSPn;Z`-NIJG`p$RS6Ho&9AMLAC( z?4Fux$Vq}xX1n(xweZ4f;q;iT*R{9ldLSQJZj0i{tA^%nwr?0{QF<*##ZUM1hqf#( zY%?TZ^6MRg_}1)e*ESBXlx0`!w^gy=uY>bZ*DV}G4++a3d)8??YU>YZ$T7 z5E6{y7n)@U{x-O{<+d&Jx_#$2<#3wLNm!b9t-Eacfa0~CdgecN+#(_vWqHgyWuNTL zl3y(=`PFx44j3GJTz;i}0P(LnS@OhXBu_l(i%wDQWBH&Gb|sm^A$PvN(oFpaA3uC9ur6;8M5zT(p8>{y$u9Q;kyg~Oy8YC?5 z+DQ5wvh34?dK8yQ$@%t#rz3(<_8q%k9IG>EzYjh3jcM;t{05~CSJq3kZ;2ifmYTI^ zs;t8mT8Hbj>kpqHnki-*K2M1&^6`wx&D%m_nKOcpF2Xv&kG$tf9t`$=h8!h+GP)9 zq2uS;14$x|np%#Z@6pNkKo+3~GI&VD_aS|+g^r(V-z)D!dNa%MbA49)g=PP4q2uS; zzZ-i3(P{X!a{S!&4oV+#q2uS;hfIP|{V$kSj-R{l>ggTVEo!9qe1&EHAU$`}Dl=sS z^x(4RZdy5huBnJuk`a?xZHxa(5B*M;trTf&@O~i1e=)5xR>o_mmOXc?t=6`7gGt=g8<+kr+E?S~-61dhU8GShrXxqX5_MFgzj{#V3+w7miw|=r7|RS9X{*hrid) z9I5+RdR60J_0aBX7wi3LbUx;;Hy);kgr93t_QT3dz^~UVR^4Tn{K~_Z8%%;xtI152 zO=bLi+;|;tn=`p>and6@<=tM{b1*&j3$@I!E4h}}R~N5aoGT;lV{W;;Nkcs(j+Hk! zMBd=j6)n~NKC)fWQ%2kmxaZ!%^w>Msk~7v=>FajIuoZXAUqAV&NQ1;D^1c1;=o{+} zcuz;-&bXp|(Md+!FFA8TL@+A68|@uDs85Gt1sQSQ`TJ}LJ)6o`@~nI%H;x$7>{qS- zPKV;-sU!30r~Q5ie=iC9-drt1M%)V>alfp6w}@brr7l0`B!eHg3N#@bjFs>fFQvr%e7riU&haiFyijsfqU-ZeZ=paMC@rvxcaV)xED6! zPQq-BvTw|_ab91vW-(uKhT}RfKgaTqGs}Lsa;{oA|AyammYsfQr=pvTxGyXwKg4TU zp7^fJNHIP4?XI^@r((X0xKH}s$`8{+!cv;{c*=aZb2=7(U2kOmhm&@X2u4{h+PiE) zcKD`4arWOv=Et_3@-RJ?GiWQ7+F5q#b{&fMrBr+A-De^V5>}QxUABbV%w3~+L`K{{ z{arSf*J4!stlB@ba?yX)J@f9DO>ZgAm#bS|30!QZ`U3n%c-B=_>yM7>U60y%$7RC zr$aA{G)Pz~aJ_0)ThiHvyhBFW*W-HbWW>F!k?D-a*yGZ<_73t&(re&reL8D0_5{N6 zVAlgFBkqNcxS#XY#nG=~l;u~hJeLvoLPy-k%{gW;JtQpGb~8+6#J#NV>U>cWag^oY z+LJ2tMT;^fD{`oV5it#U>|F9ojsNV9A(KfnN)%xeW zC*G)>ap$E~*T$*N+A2S5gTckX=O1{O9zW_(5`GM!`pnllQvEL(OPzky;NpWz7Dfc4 z{1`&jwNmeCvsHdfF}V0@+VAJkDk-`M+7J?rH+ z-8H?vmmm4u}z_Xh76+c~dq*rDh&eCER>80F_Mm0wJjT{N*nzOKx=KW+Ae z2P~!5l`~Sxxr0^hTjG_n?2bD+m@iv5vgkH>^N0Mr zzUp0)iu|mwGTo7u*2GF3^T$sfSxnicc#s|ve*RsxcR5$>g6BKrJJpXYUY@o~L@+A; zRj*#rDPLj75yb{whCR$@;%78gSNvpnvpfHL`%d{E?;KH_`|aX~_^U|xxoSS0uYFI) zeB{p~ih=X4j0i^YiDcPwQ#$0eFN`c6Uf8a`p9xsL13#~?I())zO~1;OIP+ickZ*Xy z$YSi|ZvE_iXkKe~t8Gp{d#^g6oCCS$Ivw+ej~Q8<(C_&E^w`tY79_7E<;VUV^KSh| z7MnlccK|&k{EWToh5ywSWS6-e^BIdq6lWj!QbaH+JOyn*e*T9}`KC9FD3)#5WgtC% zmR|Lt9mX{KRkLpGl)q9tqBwP>c?0>YNZ6ZoEy(@P>72hYWrw22>01vX!6-{Bu8ex- zz7F{<56idPZpZuiL`n1A$ZRTkgFin%viQ$~qwlAOguPief;Dol4*3JWj4Xclr?>t= zf>HLpxp#iy#U1jiUK?3_arxB#vB#xay{=v978zs9vb}Eakk6}*EM98&Lqssj?$6a; zUwy7a{+gty?N=Q=fFAo|){~LSSo;l0wMR*+eX7SJ1Lz@PUyK{oAF^A=eALz>i`t3Z z29jWueKFh07;Bc@e|N`xvZSa{hh9059{XanUdk)U3{y$9yGyEF{=>zQ1_}FO_LZ7! zmTe+A!$p!a?0Z9H5U<53`(j+}wX#9~{G#`I6%Q|7Yp#`+`u$j~=4DBbR!4Cymgi6G zo*yxGP%-s?TS)&^Ie)LLEm^(fkWQ{H(A- zW`#urqpXhdud+SpXN46qE9_xMP&M=wj2XutH{qJ;ZA< z%IYYtwe4qx6S@xdg)D6?Ik)9$})nfH5gaPemUBW+$^RdZ)Qv#PqWjB{CS$>j|DJ-bEz z>w80r#*R-9@^go(w~ZQOv#F$9+NT-u>egH4H75-z+K;?_5U*u#PzgUzs=95Nw{Lsv zmiYr6h7>DrcX328%DyrEwX*JR=C=8g3%e9YH{N|e4;?FzR z45o*KeG4vcUt#1H`44*xEe`+j+vry@icdu9?W4BJH#lo>@y>|t2JwkndeoAW+Ong= zja%ib^cq||xxq$}1_?i#uDVt^+IK?F?)fJTgNo^={&OI&6-SkGvC48j%lvG^^1I^K zV77isRxfqEcqHga5w3sEuPZ7wNSN)SUejJf`C<-~H%KDXaSv?zB_x`9Aaz}lPanLN zvo*?U$W6VRO+@TzNjN>fN~qKzVYWtDUE8H767-}9mumegp;Ci{*)Gb}$X)s;VYPep zqzIR<_*FvwS@BxV)~L8%LL&CGB$|3TbzM=ZLBec}vQo|EyM8@RA?tA-wp!|IQchUu ztfh?6F5mU*aSBhVAp~7mO-~UDbXL2}W7%!GXDz zC>2QwGcqCuGv2}6^G-8^5Q;)-?@mKDI?#VtyIueFTkE>+^0iv{Iy=UXX#13vvRc5_SKKgf4hF6;eERZ?|sq=q_40X z{EMdAM=8pCpEOQ($Az(ac~`$Ud58X+4w&2g_3pKc z9*2aT{+&&;iMyY=WB;@}p5J`r^baj9ua$ZkMX?VKv%9e3wK}YLz4Fra_V7OZnPIf; zeYnQz<(1xb*!KNLgt6$?H~(#MS0ubg{Zc&9xG=2ToxIr|%_o1lq#zi@90~7E2rFKD zh83@m&3<+d=A!rEH-{6A^YWF*(c8Mo*-A*fB8*lZ({^L*IEE4p%t#R9~YyZcvx%G`< z-$?H@=pq>9cG6gI_pAG_zVwk%gC4ha-T(XYUk>ki#O|iiMKH?kr1AR=-`c;ff5SYb zoF2EO@uquzJv@BN$D2kM!6>(r#_(7RQ3Nl}9yx25rvX3g+Lk6biJdDTTQ%I&0a z|B?^(=Nz>~)S$<0UHA5tcMczW)*RF5A{ga%(s=pLKhmFl;Uo4^UeV*WG~WJ~JBJ5u z{^BO3ql;ja+eu@an?BtC);TM$lm$>;8=FZ{MU;B~eNu!Hkl-o(;KTdvMXiMI( zOd9mKt?S-@-*1NfZ~n?Ox(G(OoivW?AJbp_qYI-3J#I_m1DE}3c;jz34=tSPM;E~; zx0A*We?Gjw`lfrL20d=;x;M}M=kUnayu>uR2u8V`G;aKV2le+jZv8mEqQ`A%yz8ky z8@}dE?=y`qf>CZKjoUxASO1<(wv8I}xGjycP3$5V<#y8e$439!|J)6`M-6)1PS1cd zmiL^pL;unH&27Fl`}Y}-O4rI!-s5P0r`MZVx_C@Y^?BX&PMw zqufp!fBX4Imz{mad!q(DZcAgEcYbGh^GjBmMi;>-x0A;9e_VUn1HbuD)S$<0Y2113 zqTvs|a+PUx5sY#>X{bdA?<$BI^tdgJIlIh2ql;ja+ig1Lc{=EETN<~V&>*iuI;sSt z+-{%8JbxbaxGjx0%&x*S56`1YFv{(u5lYECFIV)qEsez&U5m2YMKH?kq!CK{Jg*=0 zxGfF;mAUNjmVyp~QEn%VTb8ch|BcmJdfe7^Z9UoEC-d=>H|U=c&cki^y;l_P9AK2q z?&2saoUHo8uFXbIP2(#+t*l>d@YJl^DIH<7)cE*{9=CPx*Z%MEaeS51(M2%I?W7S# zOO21O=y6-u{q%XCiQ}uJ(M2%I?W7S#OO21O=y6-uJ?+V#isP%K(M2%I?W7S#OO21O z=y6-uy=U;rIKE06T?C`tP8wmf)cE*{9=CPft@ijt9A71kE`m{RCyg*#YJ7Y}kK4NL z$&da-9A71kE`m{RCyg*#YJ7Y}kK4NLlh6J{9A71kE`m{RCyg*#YJ7Y}kK4NLI{z{q z$5%B*$$dW^$5%B5?Yz&$@m133 zA{ga%(g>ra#>ZFmxUK7+aMuZOe3dl12u8V`G{R`9@$nTsZtJ>x@Af5}Na-RN<#y88 z>byD4nau&s{(G%`nT>sBcU!DeFY(lMJj3Gexl8F-@`E|eJz*#A)N5XP8Kdlk*z7Ov zKd^l>ULp>B{Km}&VJGh6o6TOvYmu-MVs`4~)`K^0ULE%6U;VVLXGk#0PKeF!f2e+& zvEKz7H(P|AxX;}8r5Sqc>{#3Z=aqWBD>mAs*(>bC-QD|Bp+Ukpo`t=26S{Xm-1H zz039c!H*vLrP=u})0v|9E9}^+@k+hk-r@IyJA^gM`TgH6rH6$5&Tsbp@wYO+ymoIN(2DWY~*x!HBQW{0q5 zdCj(mT}}@P`|Vn6QG31To*jN)8`dnhy=>=#U=(vC{7Ue^?VFoEv`6!Sg)f-v_p7~4 z`=#FO^(zv z^ZUQ-)9iHK0eg6>rkz}GAGPD^?Mm9Owck58X)PeN25DzBwKyWYjY<2eVQ;$$@7{?7 zJ#JH@-3_l2ekY1@JKdH2@+E4}<952Px2W0;Km7O4Y>s^Q3!00Lnhx*yjlYSRP1nj% z%#rrj%T4(8@=`Au>V>^6xib7#qRd_U#d;HdvA)z>gSnxH^pc_ewIu9U@lE(u{8D;I zc+2p^=jz=%_ABfr{0h4u7{$Bo_4ow+8Kftbo@Uz5&QCUcd*H(7>i6dp&)j~=IxE8O zHtke*5sY#>l|=i+deorD?XrME@`iw{ET3*@}#a!?8e)`@Wnxl@K z+wA)E?Jnn2^Y%kyI9@4?$o^%w=Ii(E)C_l9{|b6YcuRCwd^5!-t>}- z3xZLso4ww9Hr=rq-1_|HiBJCMQhG>uyPNh0y`}!b=4%x#1EZWiDxMwuru7DQO@C@G zJ)REjU{X8m@LsZgbL!LgXx_iyl0t)ox2|`_{lWLYKD5-KciwpUZwrD^UJ}#U!JESf z;Kj`z%`ZN;-X8RLD|%J>Z>l)Zxzau`wc|PcIQBU>>>|@c!b?xuclPm>cB)B~ zQK=55lLJ0_)j0rfm(rej{0;Z4_RM|6nfh8E^=bdyYpSm0bzTIu<2n5}veX_uJtVxX zOuPEwoPMKo`hWb&jRnD|@~&R_*Jm|1hI9HKc;})$=^^2x<#am1N8vipK!Q=skzVh* zr*Gc;*YEae-ns7I{rBgwZTH!PS_$vrQp>m1{+l)jE`L$8^Nx?*gB}t-lSzH;{R=i} z&JHJ+f4$F@Go1Z+lv*FomU_LzKDKG2lgq0=JXlH(3D--l=wtt|Zu61Xy}Y?)wA!3Ok&poAh<|KTMtC3n5Gu*sUbMot7+#EmnenBv*ysP`3v{`e; z$uDfadB}||kxsFtywb?YOMV)CT(n}-X0yXy)bzi%bNE^T$0eEYrIQMz6C`r6&`9hp9~r=da?bfzDr%V3a@EbQb4~g>#z6gx|5eVuQ7w z@AX69n;`9FI-Q7r%pn^$m-G*4?tIy{yZe*cBA%0pZ(EpEzeKv%`_bbzZr&Bv;WplC z`Sa=VQYpgA^ygwf`1l*(r#=r0O@x5O4zK=u=dfZOWU~%}~#MP$J zMf7@%N_MMprE7Rp@?>J$)4q#z1dS@eD7V|ZTIP90kK0Pe?gyQV=MnO%N-)apq!FIr zGJoduxGjw@?|Bx=RTsf1x06OFiOam~(&M%?ZaVIC)Q>KLQEn%VP@|f*4%)Tk@hEAq z#pw0A2u8V`G(yYJc*{VK+tTn=^)zGI?D+7eknn4#Xa2`O7JF2>R{k;&SJlG`@A8e|vB#}%8eIgVvMr5Ad~nIKXZ+)+s6kJ*XQtkK z!B>Xg`0f);ql;ivwx#j@ciy$^9~-?fYS5GInW^6B3&R~=|0vVwB8sS%kj8QEctZ2^ zi&Jlqqk^Z6nwdKJ%1;ju+wL!+^$B{N1f#MojjcA>ym{>X`^0q6lkJ(QIq(12@B_d4 zwP|z_jLNn&{JXDu=JaHHW@>oC`-WeC>JLn#i(pi?rJ*$F&ZI$4wr8eZ`j(@I7d`G$ z)94}?m2GM0S?HNagPv^9Ox^UYBSLTRHPh%K7?o{ls7$G(NQ0hi&rBWu(!+*V9{+yR z=pq=EZE2`(sKiTyo@~!d9sikE4VS%oo@sOujLNn&RL50wr9n@&XQn>(xWKAVy_d8rI`P4SKTO_JgL;MOd#Eqp~dx>uaM1J=qTRF7>;^R6n|iBB~{%VIzR3 zk)wjAjcUgwrqM;%C?iH?TN*Z!i5m1|yB%MdMi*hDr5KfMY1oJ?YS5GInJF93nMN1E zsBBBa#-dS!o@}?HSJUVsY$O|_vMmi8Ax8~*vaPmOv#^a#ql+k`oG^{OLTep0a+EwC zH8b_zCoa>7JZn@5MrGUbYF_Bsq6R(Lo|$^h+N(8g&v{iP7?o{lgeN#JwAN9Bo@~!d zz4F@YHEuVJE`m|nmPROv^FnJKHR#Fq%+x6d-J)^3X><{c%C!?9bwpGvX z(74?+x`-mGC8QBrhJI+RqehMjo;GS`>g~f{Y20q@RTsgiY)d1waQ)C)M-6(iJu`LZ zCx5GPdu|h}1f#MojnGoZFI%gRq9@xkQ~&Y&-)Y=#8eIgVvMmjzL1~c&J=qTBYX1i` zZa0lCf>GI)hMt9TSQ_+XduD2*@BUficGKu07?o{ls7$G(NQ0hi&rIF$ioa>xZW>(# zqp~dx)eV(+Y0#7HnW?#Z{6ph*)94}?m2GLLj;rQMgPv^9Or7!V-rix{ZW>(#qp~dx zwN;_DjvDl2duD3w7p=8-7`NMaw~Js@wxyvqH?-DqgiKGiRnOPj`_RjG$>a7aQAD)_ zG~(PKM+HwC)uv;4J8qZ81Yvg-qq2>>TBhegPqy3VG24#YmAey!=*f25f0#xWVZA|& z%C7LMh$wh-S+1z+Ht#j=Ly1k=MR?O5MgWn> zQNhzjwc`@g=pt;C5u>s#4I9Zs4SKTOj;~Cki?GpBjLNn&Y(y3{=*f0FPBe`!!bW{D zD%;XfyRKCh)em~I-Hvxnql>W7YmCaaG}NwZ1wzd*p0suNj0h^xyrrW|M#W zQzUZKnu0j-RVNP*SZljTcN2`twlwzr{Q=F?Tj#{Qq9@zagJ-Pz>Tt&s4l<1{f>GI) zMraut{VzO@9zEHf9?bp0X~VUD@=nv}A{dozX($c4GilJ1?dic!4m)GmoH}h9T?C`D zEe$;jJrilrlkMrjvk#v?{M2VpGL0^RQQ4Np|GQ_=vfuyo=%_(YwxA|7{FC1=o*f&h0i(pi?rLpA`^)U5<1F4JUdzYE2Q930*0qe4gdih@Nau5B~6f zX7M~g^m5diA}SNo2v2aHJ@XMg*`6NUcKT|RD-gXLwWf&5gfv1)oM&ZsL{GM-2hTm@ zTGS5^y&Scsh{}XCLXGNM9UReYl^5$NCTsc5k1+S9{lIro6%l@ z=;f$2MN}rF5z^3C>(C27-liwp(}QCc`~>YTh+d9bQ$%G#8sS;=)jCLno@`GK&OH3~ zwr41aUXEH*L}fx6p-lDFI!J?_Y)=n%{r5YD>%HWX*b@~*FGsB@qB0?kP&fK&9i%}| zw!<_3>d%HtpZh%10MW});h7^U+tLViysy?l8uVm)Iz;_^cA!^W* z?ND}8du1A31f#Mo4Qt_|20hts+g;P>BCLIkQQ4M;wbW6Ao@}@MhiP;X*3QSMY)iv> zoTx!hw%dNtG`a}uuVPfTrC~j1)SxHZZGUbWU4-?!F)G{Aun|DipeNhYAu5g^Orwh^ zqnt1ejeVjic#6tmDJ{{b?AjZda~V)6HTLwuu)%(%CI2m}NQ0hix8rux=pt+s9;31?4fW+}9i%}|w%hrKX><`b zn}|`_mPTk9G{=b=^klo8N0~+!VY8wbm2GK+G-$3CHR#Fq^uXqArqM+(D%;Ws&q8y~ z*tXM??RLg$8eN3VSYuSSr4hAp{^-f}^x)cWd_m(9>j%3CMrB(Xp>8y49i%}| zw!<@j^9dT49kVfeoJ7?)IuGRg^PXzUaI=yAJE$MSYu zB8>^c?kYxQ8+o-%3iM>VeIBM^xjR8v?#8HWOXI)KJ+|5PJ70+eJ=vZfa8;z&TXE~r z%~$STwCu!dx7ssDttq0c#LQ}Bpu6vl;{W$X4f~8ozvX*jp85Mh%%8!P*-pXn|3?jb zWR3tH{o5aP5H{Wk>eB;@iYZTaTHS#}xGQTpBk|X-d|TH|IlBCUYy%lJhwisvxc}M9 z;=SL0@BHDMvsXkr(JP~!5|FS~Bi6fKx-JOI1qF|s*y8BL!)spr#6%SNqyEbNy&zIg zRw1C5uI?J_Uw?D^;^EwDcZzz_-fhv&NgK$hAyG! z=$OXxONQ$lykoo;`@v1NytGYINzg;0TZ06nes+1f#m|O6AJ)EFMN{!^%Fr^Ts^3(+v5AS%+oJz_I4~Uu1Ts*vIdecmdlG3Q5hVJU# zXFYjBue>YP4-(3SdPyWvM4>j98Z6a%g6&M28rWee&+B+7o49pMu{tH6r*gmlnE0W zH7ZxvFL{6TXl8NAYd#unJ*UeazlW`!=le?K$~`2Wf69X4?fXqvGpG`C1W`uixq8mq zI2LVZ^dTp4UFFD>{=E7z=d>jw)ilfp+jKB0J%dydy9s(o=xNqVI|)W{ z_8Mc|}4stzHuIddc*FQL4dS@-3Uv&4qXHs2w~e=DXU*Ep~fn zw3R-u1tmcb3AMo+{pi@r6C}YX*3EP~NomyZe$`%i4QBevyP}7L+RFM}kzf?>w$z}9 zgj#LSw{C(_%=MCBo1t>-b%NR@K@W+!q2APMEeS^H-@_L+I-a0=NZh~OIc4i(x8}Wb zx)!5Eduvyw!>+qrYfF}nX!CAM!g~D}W#fmI2zMLplCTs`5LRm+f?$-@`3hnEVDxZ( z&w98DK@SP*B`O5-$4X3$>dq^ANLYVW(ICMn>k}&kJyy5>iMt|UtwcqGcf}}ci7JG( zgXYO?t+g=~qV#0K+La1H4Qr_<^vaUR)`x`k5)};+jN+PgsX-43>vt;}Bp795i3&jv z2^&8=1i>hl{4yQ%kdR(zODY;97}Z^)tX+!Nvi2(4DsK;?ElKTQB-oCX>0p~-ql|w- zgM{jT7$HZx)ZqOxis>r})*S1X+Piw_5daD6;X3ZhuT@6n+Ev~aOFIeccPkns7&TFA zM@ebau%%X=54#TWx-32AUC~2A8eyNJa#ti6WwWB$w1bsZ+Br`2kWiY!thl0~{0TGO z=tS(93VEZjuBCPw+LqcW2uLNL>U=;h{Zo<|aVw!A~qLOl39f%%VHHbFvwp)XQ ztx{Apcr8Zp4x`2>DTUo7!uaR zO1WZ`t*Sl*VJoTeS|t&89V+P{VS5uX%62v?gzc*&Pg;|+dyji86(a2kJ#mugOnE^d z%64li8ifZ$cRFm>Dqf2v-}VzK8n*TtJ+{XZZQHG>5QQi0-NYzfsVs?w2ZZf^R5VC1 zN~I_4u~Y~?LEBeLQN`2D_Z3#Q;VFr@r&rM+VLN{@%JvX4F-kh4##Wl6$JVT)T|65F zw*;S*?keo?MuJZ^T|NE(sG*01awO~t=eshjB+96`CtM*?*-dB6Cy8Aig0TJ57{xMH zrla)ePSSO454xg3f>A{Yg~+Jkld`>{bX}AM0NUq-hlK4@Rql!eqiioM6QiW$dtO^d zk2Ji5Pm~h7wf1zv1fleWea@^=C5ouD(^w%`*KD6NMzL<%<>PAEOACBafs5NQ`E-_fx0V61F#$HSE^Pa>XdNV`Vz*bZoqqonno)ofgU?fHocUkYHITHAoaucutXM zHTcX)JV?31wTh^;=UK@so?FVlBq+}?jin={Dam&g^D3>kF^ai9c~^cujpy`D zdoVdGqK5>3Nl?>BE0B!Rl{`l*2?=cIA(4L_F+J!e7{z=`7f;-%;W@i}{=Y4WoheVJ z*huiV2a|W@xyvZ#TS-{Gn^L~>e7lvm+Fjv{THh$46Uv=vOK=m?sB*P$|D85y-=mV9H78uIg(`BpAh9FEyCLq+#iJ zSapzu(&sr+YB1j!r4keNydENVnWGCAuj(My`Qgf3mSV|It=;OMuIwl!^rVuX2#a=Fq=v7U zlF;3Dlq=*Yqf$CjIW9H$Y}fhX)!H9yOS|V=NwAcV_`|kWYkx4O+_2EsqKq<%c{rwl z+DT%E*{jOj%^DyW#b;A$@JT)Ay{p@Me|UFAVx9F@xA|6T@LG(Ts2`)mjT$~FwO!si zKfF>xLK?mfJ9$@Lt{9~|EY@DzyHaX>#Z>v`E1T)AurAsXj7rZSt)xy6c5CH`jD()1 z>($bc)ESjpSKL+Bh;8^Jp)%&_8`A*6sH9Qb8KsAW>PnHjV|SIV#VGdFOupX|WL4r}%qh?~1?rqdqyBj^$)~35cZ7$Qn8b!kT`K)1B zDp%f;G0N&-g|JpFdaQj+cZGIr?5^M;VZCTYgC6Uh{|OBeHZrJa=y`a`8O7%`nU2sh z#A}hTu~vtM6O3XBEj9Se`82K9u4vFhBDE#yZcB}E!tc=f;H)u9+^At`u$DSTQLogX zhlKSES;MfhBr?i+q6%Rxa`aeB-QJa_Y4WbzL&AE7iUxC$QPvYx2zqRk@lV_p2^-Z^ zGVAUEMeFt3yYgBvnOE*1VdIC6yK;h2tZ8E!sDmVIR8!Lc!6>#$rH1v+ZEAhS zYJG4;gPxSrX;y6gZYD-asr-doYCjS|y1XlTNLWvuH4JM<0MWy!iMwhE_AJ(0M*88k za3rkXt=(049$upu#WanjJQ9|psn?I!wb4MQMj{x+Tqrdz+<575)!Qyf*NUrn-VRZRvf&FhxU!;`Rs44o=}rnF{(60RMI)_Q z`n_xa!=mCEvj2ObQFtP0&?!&7cPu9A+z z1A^@sB*I;hVAN4>Tpn^^P|;A7w?5%FuEQ4}wNpHG{qmb;hu?hdC;OGPJ`jweUU^sa zkho%>+2Q?%Jfh>SynZmMJ00d(uKP72+NK@t>RnZdoFkbj`&w#Pnwp1|R~D6XIxEBz z*r_Di{a&cr6>Te5IUS?KjT(BaB&Mk1N?FDCKhoTwAX1IW8U~d_+Jju4qEe}>5rrq# zs2F86_#p^JS&LC2N>6NwQdFT`q`dHC!s=#4!`hPQVbsGbS0t=%Ry24mMzKuiRH&5b zOi3=I3x_-2nriKLwqK}PTPcY=_eMIMPDy29QX|yCc)ujNHFzyX{hyhIs^>Z7qog!y z==tJl=c$cq^<2CAu1GBY!FSY(W(~vqG*wDR5%sX@2Z`70cY%7fibmRlOd4fWuEAwG z?A`}zGb|UPZFv~&NQ@HKrlU&avXE8EQbG-THkG!$@|-Oym$9s%l34b4F}3O5iyk#F zqr|msiKQ?TmTx)bCR7rPn#ik`pofG#&58yIM)5h><>P}B2D|c0luW;Sej#V{qEk;?(SJ9w{ z1m`74Mkt9S7{&Q+N$_-}J)7mKkM?Y$T@v(=VEykVim3E#DjN2jlP5jrWT!lQD1uSx z+0+PnKv*6=1i>hKHWh*%681bEf?$+AO(XO^a(|m{8jEbaLhoDgx7+F~b8e^iu;}gL z{*GUI+!kTq=~$7zQP)K<%I%~P-aI_(rMtFnr#CPK4@hEB7 zcT-HGi(r)7Nh7=odg42A@_1CtAN!tL%BwEIz7mt}#E7I3-hn;wow(@1b?rMgvq__i zV3gZQBfOb=;yZEjc$BVd-{UcjE`m{RCk=aJR(Q`#{!W}c9wiO?u8?VT5sY#>X@obW zPkbj%9*>fSeILm*x(G(Ooiy}zapkbmL66(gu-x06PAbN$43;^grtY1sFw zOrwinl-o%oyn%n>J8|-Olr-$STc*)PFv{(u5xyia@trt%JW3k&{V>z$A{ga%(okEa z7D&&79=E08-*b~4zfe&n80B`-Pz&l`cA&@Yblvnlw`6w_{?#`Ug@(P6G+irs@^wvb zP-sjLjB>lkt9i;Rdfe7^E#Ib+hUM-A!6>(rhCRVZ(BrnQYtP>_x(G(OoiwZ@Mh$x0 zmWGvM)94}?<#y7r8WlC@aa$TzA5Ei+V3gZQ!&-*;PC$CxmWH(}rqM+(%I&0KEnL)~ z$8Bj?`)C?n1f$$e8hjffJ#I_G+IiFHA{ga%(y$&Urh^{0rD6S*X><{cayw~Q&lxr7 zaa$VxJ-29AzbqH8WnX- zx08mA$f5>4ZcD?)bEeTnFv{(uVI#|^L66(guyLtrbPCZKjqn5~ zz7r>pM@hrJH)0xH1f$$e8lfakd?!vGkCKLcH^nr%2u8V`G(wG<_)eTW9u=Rtea|i0 z{*{>c1U)KVi&17LjnI}%d?#+4u^o1U(M2%I?W7S#02AMdlgFc^Vc)AVjV^*wZYPZ}l9~8UoID;S4g2nvX><{cayw~+ z5!u9d;^grtY1sF}Orwinl-o%oj4UU<6DN;HNyEN_X5-y1f>CZK4Yj$UwT>fXdfb+V zf6p!2)i2A%YuQ)dNE90BjlC8%PMF^ELSuqpl-o(eQoc;%c6!{_buHg!lSUW8D7TY_ zJ;A6!kK4MgJ%7{aA{ga%(y)>kHRy3$8di=?ql;ja+eyP}RMeoyZE0A2G>tBTQEn#< zYZ)3n4|?2|hP5lE(M2%I?WAEXT-2b)ZE0BhXc}Dvqufp!*0x6tdfb+VwezOYMKH?k zq+xwj)S$<0X;^<{8eIgV+)f(Sb4Cq%+?Ixa&n?>3FU!Si*;n64Bn=xgL=C^zIAJ4$ z6-lFuV3gZQ!$vYugC4haT^k3PMi;>-x08mA$f5>4ZcD?)bEeTnFv{(u5k}z?--(mQ zqoiTuQq$-n80B`-P`j>G7S%y|+)mFRj;~Fli|}=E60Jsc^_+yw6HG&Qlm15iJ^y;) zaNoN(n$njEk63eIm_a-v+H=Bw^vUnO*}i`2@nO@i|KYbU7+!z=J<+p#?m5GI7Osi* zL0`UTc*GIAL^{Wdxc>OdhQ}SUcl6j397^wV%a#o9JanH5K@SOgHjyqhNHA*2FBcCt z+x~?W4SGn}v#Ds1D5Dk+ufMLQp=aQpaUy@yJEvsSCt*)8-pPJXyR;)6r6MrsG`AZF^XlZ)bQ0It&M~BpAgf zTjte1r+$C9@Ba+r*OPaid+qSHjb0IL`}f#Bmc&=ryGE^OjPj9;?&S8LU!xW^{(DK# zLqZy_{n*bd#K*q0s?`{*TG?LryKh~pmU?zF<-9JVd>k}M&_lvnjEcrves^Zuf3S9K zwfUKCUs9%=9uiBB_?A*$=I%%>!!fsBIQ-Dzzla{y!BbCtLTaN%7Yt9m^@frNVxirI zhr|}UUNk)K3G0_FT+|@Js1^VAo#D5hc3DNk%2mu0YZ;=w?Vrx+c!KPO**hCi(V&Nf z`uWQ?cy^hNm~s+~V&5JD+rLqt9umrhLmt?!qCtXDY#&>JV2t{AhBK)?{p%^2PYVH#TD0ve*Wr;20bKv7B;Ctf>C#Gdfjm0 zU6)rh=po^=$w>_ojJoL+*A3sf%>@+=wpS~6xq3M7wZD&1%(wD+&_hD!^uKoMA1WFo z7{zv_)S!pNp+~Q7@35O-6x+&@u#sh~sXqTuj@nov{(DK#L&9fBlh1<$qckSkeyU&5 zpofId`X)6)>!V@{tzU{Y)%vSS%IP7o@==$ocaC(aL4r{n&y@r{B!2e&rRtq4 z8YCFS*0t1l{hce?{!T;~A;s%5M@oVo61u~%{!qCq5{zQLl^Prma-4Ymsx#WLL`l#? z!p|K{mJ$+-`agT0p&Y4{D|$%y`H4vl5{%mLSKrhKprXMs^`6(BrM@plF->L4=^>%F zlZM{8qCtXD-D5aYetU=IU6EiE*PL2nq;cX~w!CO~>(_r3@Aol(zG(PwAAj_e za+EWGmIy{UHz2X{`iq9kZ+L8^y9q|=Zrhm!kWt_I!FVmJMbR!+LJEQ&5>_88cSV9x zHrA>e&(2R$UL z@2Y5!V3hSl6~fBytV*BFaiZNlyQ7DM&8Z??rh^2dY^GNsUa|1p;p_HW8t?c0cb_}l z=BCBbK5~=q3}3L`rImDWwq-p-jOw0w(L=(<)D;a9jIt4Vg(ymR>Mf^~(=5|vUeROy zU?iyBO)$!47L~iAheUTeSaw;)Y}QxNpofIb^kSOIbdX?_&37vr^pLO_Yej7(oY^t8-LnaLDnuo(NSGa?IFl*w>eOF1s%y(tUgv$Y(dtmN z4_drpc+CSVqFoa7kl?thB)GQ3RzmBg^%*2RBy6pwa#ti6WxaESV2g9-P78;ptb55o zxzOGE&_m*zA6+;{V>U8bA_quzh>!r|-wcwvR0XQ$_$H$3rz6vZobYmhkhL+1@Y zy#GZN4PJ{;zx%;?!`oKY(!rj^<|6UBtn=kv(L=)KpOw2J!6?p(OAUG|L`8#y*)fW> ztJF{{di`~q#wfMgVGUrpx9z?jP!bk3L0BD(bT`2$*5;Bp@#Lk$#a~M+@khL3>2TeB z?~d2qbEl;mC(h~)OF})e@1=6(R(<=#8gf8KeR@coxzV{Dvk4N6>RxrGhs1aHJ6Ekw z%)>GrBpAgqT@v(==pP%>@%m*I4HAsvc%{_fNdK6(U8H9dugfufNzg;$Yu~;|PqT7Y zBp5aKrxy*M^6C33#Md`jG<@lc{~SH1J$upcKac<4Xn$$TMZ;U)zE-7I<2b?QwK2-( zyA=(3NZ35OqCtXDnpxCmENsJV=CxcUoNa!YyY!H-eY_Qu^@9YXY~Qd_qv#=F`;iq5 z5{$C_&x!^;By3-`qCtXDwy$2%pofH?%b3h75@l38QBcvalLOH+PK2`tm2{A>vj#EB z&N);xN>4hsqI>uAER*RV!6>e(m*t8c5`HdcQiBAexb|LZus+|t)}rAr`}fCs$NFCq z^pIfv?^(gur$gU38_YBC-4kmznpez1Dw@NG|?-`BO+i+=vD)x&oj^0Z1@!Vx4# zmexvCo;f`vdZR0~ml|7%GUX%~Wvx#|qwwImCqDb~;Rg@@MMZ-IqaLJpM!!wstG6%J z3Q|Rb*J2b$24%`QPFVe{rRp={b$O+dpoheUf1gpQe2BYZ)L$O6RI6W=+@*)a(Ra_N zBvuGpNsa1u>LEtiPJHFA=pkX}Cn_2w7-egj6%Bew*g23&3rB)cw&GdQC_MJ-Wz{bB zK4VWXt+&Q&G0IjvD;o5WU@ux~a0bb_;lJ#-T(gOa20bKZKNnW+U%%`j2u7WI$O^3> zRfr$_c)8|I(KF}zStd zj5_{f%Qd^J+!Z|}m?NbISLke>5bFeI-X%c~37Y{_Y7_}Z+03Gn4thw~%63IVErYMH zaBo8UB7W+rOb0zA{5PtT{U8ZOX-EUMA{ z-v7H*!^i#0M$2VyG*~^{_p_TsyCmND>lw`lqvuVx&S*XuZT7n*K@W*{+&-fjWTg(0 zU{rU1&gX2UB;Hl`GpC1ymE+1?kzkZcN&QR_JtV9?Ry0U3N~N-XHi{k+)?!pNNH9wE zzkbGx9uih>DjFmhWxLCjazzgb+flA)kYE(Yc4bMVhlK6?Ry0U3iX*^MgKdVDn1N~( z+nAD|hlG`dNOu#AvL{<1*vi;QKSr@tDmCaKp_zrBJnbeJ)x9QTqnCImHgbx#jW{al zpofHwuPOxFzHfyy!tZ*;4gW+dO5$IemBRyfT3TsE+3qrmv)3}OIG1GsQi2f>G>6OAX$ymCAVUOkYXRLxS4f1fy&$ zQAr0qB)UfcnsbH|jqzHVP5N$z=DXoU<6yE}aZGJv-x$S~uS^F$By5aY(ICMnwTWT$ zS|K=wV{2!lj|xE#30r@dnoKzfM%hTFLa?=DE6Nq`GOy?%VJlOWbdX?_t({ef!jsmo zVwA0yJp{oho2yp{dPvyXz(Wv>vKexPpvUI8F^bw{?$SfTX2KN>5{zPh)oP5iOU8cC z)&t^ot3*HpkyapL6bW0`sN59^M)7XjyNVjtlErIT3m0u`A1fN1RqK43uWWJ_UTV-o z!hUgjOc4c1CLxSyb zH^C^=9!%ygJtVr@cD7_TSBtG0TfXwH=pkWq!^&NeV3f^8D+K4x)|163>*4y7DW``7 zYeAU~5{$CZN9C^QA@T5Pl%33svy`H);I`7~Pp@|*Y=0-x076^BYca}pYbpdiws-SS z+!YDiQC>dzJa|`(vVEfpvD5D7w0lKbf%X#@z1}&)8`o@I86nd{!bUZfCrE-(rd=6} zG99+#9`D_D`zz_7hlK6$R|vK;cK#+tu~jOcIXxuoBu_o&_lxd_V_eQ4HAs%9s#gqeC*Ysl>BY|c-?9#iMdM;iFMWsrNpA5ZFd{(GUfD;FujK$7-eZHiIK_`?}~aXJ>^}| zL&EB2sS$IR1fy6tOAXd@=5)12MGbmLSY0XW-~_=a*5>lA_-rlT26~#*D+zi?SdK)x zn_v`21CbadZq(#2%I7!f=sh(DUUd0z!^6H2zOlY$kYb&n$4~Dl%Fq6^#HdD;Q96-y zM%HMFbh;^dCW-X6`E+&HAmL}DbSH}rys#r3bKiWzaOrcOH&B%C_Q}5X8($c%_Y!@B zYdq!jknsJ;2PYWy`qNJuUU%Ok!}r9;HRvJXJEjj#FzUotojg2Xt?eormX7c?|2F0E z8CZ_Qe=l>F9^d&9?K@4AcSWL%I$`*}`8$U%T#cu^*UO%g;Crj{eTDC4fbbnNU6)Tb z$A|W+DLwhRrdN69BpAi#A2mivsr{y2%u)MwRkZD!?$IvqiXIaFtM4|iS`8A6vMB-=a@ykYE&Bj4~bcknnSTt%hM`>%%CvE2YMN&b@iK;|T{%>017)6xqit z_(?};r-y|9Zf5eXNHFTm!*B1Xwe*ni^ZSz;Bp9{pzu(c(`mk>M>aeccUC-$u;lFB~ zyekrndd8}+wz*zD4|+)WuTLj6NHA*d4^A7d{gZdbCtKBsrP}v7k@8Auw{%PpmJ1I- zFv{BF3PBGE-%*}SISEFwJuXvD4+-BHpVT11D7MQ@RQP$cSV9x zPr7{J@Rm=UTFG5{Ncf5GNevQ=diLS-hoAcFNfixxNcb7QNevQ=`pIEu44YG@v&Jap z@u;!3Bzmm%iMF+4nXrd4YUm;1Z(C{as?{LDsMR~(s2Ww#pofIN_oLNl?}`MYivCK` z?Om<@>d!R3ilYgCGli~eEnH=kK@SOkcSd_xtp*83S?gL!IXxt-4bDWXL4r|yvLW5= zU-`^QSkI6(j4265@%hK#Q9?!y`wUCR6mqvRl3~w6!rzzC=5BjeBp78+wxU4~34cGw zqy~vH>gU5_SJ%gh*;5dFPqL*!|Is)x6aF?5-3d!5fIt);T-Wp}WtRk_SdL2#8^gt? z=D)&^ca>^w{P&WuIygc2?`tc$i)%58qo`7Y9uoe0-boD-jN(|U)UX+3Ooxs1hPtke zA1f)RhlGt8BVB5cV3dt&D;o5Wu#s#^ZX=^^27s+_D*Bp79*j7sj(L&D#0@ell}Xg9M{&epS(+hlHO5ozx(~D9*xqy(2%eXs@q7nqQ)MqLm-jLD|!TpPhK= z@R}FzxO|D|_gm*({)jh6 z4HDT7QOhqGK5+iJt^tCcIw6gp-?D!HFBcyaHArN8dhm@mUNXG>{Pj$OMB!=ggoHGH z5x%bSs7LJ@HArN8dT{v$mkjTH){{+x1U+>^8jrZ-p#F^^E#YzWNMw6@uC!}#rcos*69F_)&Y)=nPU2yU6j_1rV4HER!32Eqi6ZeI(B@GhUo*vA6=HlT! z)0>(G33}>;G`9(dpLgm#xbwV1df1y@I4HDT-wRWq6cQ6eSs(0?G6VkAj zA!?Awc8ChC#5xD>Xc{EwsT0!JHPpW!KjO_%gG9DdyF2&VolJv-+QHV--U$h5?D&aK z%=<<7s%I}e4-(l<{l{*Lb~X(XYR}zMC!}FLPShZgZAGc~*~K(S&{HQ&o;o3o(5p4pmJ4B6?SLg>@f}T3z8s68E$aYFc z?$32sPUyO=r@a#r$g6pJ9wf4zo<|;+Snftb`Qx5CAq{)x6GW!HT>1ElM0(E2QzxVm zMr4hT;YegV)sH+*B%$)^o;o27)juDLlE`+d=XtzKLiNr)bwV1}mh^k!k3_aZRA?pg zxSa$&bwV2Fh5F}n0}|Oz?JnjYAk+@Fp7u^iM2%4Ye2zmR+o}J^^QbV#X$iIG?x_>f z2)&wmoS0W6vaKlfKA5Yu1U+>^^vhoP%I0NvJT_|N-<6y+mF<}+{w}1~`%M^;{XWbl z_FwCWx&D?`%|`RvTThzO8}pvG`cc+9KlzmX`*-fRNz|aHMx6Kglfs+7eivp%e-8ia zg+CH*D@t!X`r)#kX^^0&MkI{~LK^Ba+6YVMe5Rj?zKG z?G&{*yg}eT(;%Ue=$;zUYFz0WB-~b%-guPL5j0w&^dvnJNh73undcP=w-u!~9_8mj zf}R?YG{O^H=Fgmj+ltaR339n2K~IfH8lfaMUUo^ittfqyAlDBP^wfx?5o%Q9b&!PH ziqgB7b3G?PPmM?#cZU&~YL&_r3AYvHtxsC<3hh&h6dG|YgM{0jj{JQbyQ@g(y6&kFNrP({B-~b%av^^ohXg$} zB5A0`+PHm0!fi$AY38r+k)WqWSUN&)qk0$$`-p_wic){&UxN!HeGv52h@{aAYZ+^7 zErW#Hic)`tFUx_Tr$!`=yF!h2hutu~R>IbC} z{xadVqSRmIbXdR^wA+lo>Tm+LtRdTK<{u%0vK6$!T$rJggl zS0w1E5lJJoaP3+K3AYuc_YvlHmjpdE!qS1Y3=(cDY9-!DU#@=8QzMdw>PG0*)Z_F> zxUDF@IX10+I6+U1C^Ytx1_`%49sUmERwEL+u6t@k(g-7f#>WgK+*XuwA-@lq1U)q( zX@rqX<6|EZZYxSpGmo!G&{HFl2Irh4+*VYce`-Fs_9^=}w}lzxh0po%TzW{T9BV9^ zMwWUG>2K7}EC0CeE9)cc?O*o_R(}f>FwKUv10r{yf}6LiwiBKB>WL zF)Eb>Ux&*oUP_XOgr2`j`=kc1#VG9p`D$BMP&()#p|Mt;M`flY7^PhxUv10r(x8Wg z##(tkn3<9&qS{^SiE;%G35~V#yp|f;gYq>!MrjwQU2V%iNC!P6G}g-V^Nf@PqqGa; zt8F=6c|{KijkWSRLuN{%jN&>R35~*hg>IbiRgoO8yCNamqw*@=`12?|nb26Po(>X> z%Bzv%8uXCRSgZa#NEA`+s_M8#UZG8+Nx!bfS{>yI*J4y&9Uj-9hlIvj_4+}AQF)bn zT!S7G-bYQgB_tS?SL??$=pn&Au`E|47?pP&#x>|6!M?rJAi=1-dor#;4+)M@N(~Z4 zRJ#i_u90_?(rD8AC62X94HAr!c6<5)$f!>b3EiRhy8uExC&4J?p`X4e33^B<-!uxJ zELS8LmCAzeb7qxMpB@r={+dlpYLH-*%Cw)p$O>xV=pmtUtXa{d1_?%~Zu;qqQiC26 zoKtlZMO0{G^0|!6gq9i}5}X_6_}I3CV3gX*_VfjiQJ)?XoZ|urxl4jkYV-Z{MM=;@ zf^+q5qKxv>5EFGU_JgVXj1yYpn0)4`AM_HJS0?hQj&Y6BlZkTeB&Q_x=bk5w%BNGt zHRvJ1HK44ZXHKGsYERjWYvdCaT!S7G zTw5$PNHB_XxRRiU1m|tN-c?~8{B+yF(l6|Ly<_4|Rko)GH_bbHxW#Vov>hxG^wf#z zL9eH?iCTHq{gKG_^x#Q9I%~MmkB&7B67Za@cJe1Hw_Z> z)Cp<)HmuhE(RM~jWP5sW()wo&FL}*JO@jnIbwV0;f-a_mM7E~~-~Ha1!`t_pHVqQ= z)CpvD_7yd|OJLJ)BXAW;&=Ty@mK~J5K#+jjR?E0Z}?v+HgL%G^cd3A?yK{b=_KHYkJJpXZ7tdHaNT|HJr%p)2YE+}VB9ZM> z&-XujnQ4$vy>m~UkcPDkQG-ObQ+qY%>=mX#LhXlp>V!0`g^L;_vYp!9cYkG-X^>Dm z=$<+u4Qr{R28nE^{^O`OUS%32)SkPiPDtaB^xKT6K_c5BuVUYIwP}!`r%sqgdy17r zwxf|K}pb4C!}$I*sIn5LRR%iWP5t>{8JXR zwYendsT0yr8k81kkjVD*VAoq0gtpz=D-!h732AWWheWog2d{q2Ic@7&67xUDWPW3#GcS)$;xu;G@!`hOlK_c6!y~^Wu z5^6u(QzxWhZDQ0Qk?qv(=J^K+wS(@d6Vg!q^EnQQY^VMs&!b4FJ$Fx?kVcq!UFmZ* z64~~CFwNmgBK1qjQzxWhJ!i_R)Tb`j4BL9OV7L8w{P&Wu{`El!%d28O7)Ah*$aFg{ zF%26t#JjR_!h;afu#wCJk?D|EX%uA|B^VdLoNsT0!R?2bgX+xdrSkg)kc^wbGy zaCS!`+wDBcG)UOICVJ|GG&H*lGq2c3k;rx^S7|wB(j~-5qdjl zIHBvhr%oWRG-inNK_@cZ&dB-9RuelU9Kgfy(Bjv6Gg-L5B^1_|{5p&yK%Iw1{Pfs7g? zvK{g&t!0`933}>;X{fK2Mvp|c+x|Rjw1oAq(NiZZuiDuiiEOvy64S6TL%b^+Cqz%3 zkVbfd#eC48V5UP}rBRe=kf5hdNF$WQVm|04G1Kih(KJZdxGj3>gfzzIgI=RD-Hvxn zgM^Jgqo+!Q(9C#1pIopRKPYF83+tlMQzxWhEkjHPiEO9#%E#Izq4vW)bwV1} z!bJ@d*>2b2EFC1&4u*Bn=&2LZu$DS%kjQqso@g2*)SmmSs7^>j>oK8LMGX?!_I~hc z(;$)hrR1p-(%@TeY~Oh{?MTP{>|nR=HL!mtVf)SxLP*2jgb>p~BHPpPy*S|V!1x2~H51_HwnMX^==I zBYEnCH0%vcO?c$?UYtZ^x_xhyX^>EP4JVYNr%p&C{JLN7rivOQvfaMT$}~u*-h~s& z(Nia+VJ$<{Ad&45mCg>E1_^rVgfznY0Q9b~s6iszsof3dkWGVx+QHV--U*4Q5$a!f zA3)R~k?qufgmcKQ0YdG$d+LNV_?8uk^sT0!BZ^^93 z@%PC@BGVx%okKPa67i5DQiEOv;jk0u*P2xQW*Q{a z4z@Fs_D)Dh!`@&PHArMT^#sT0x&Gy3+t zD2Z%O57t?Kb-S8S67LKA|(nUZry~w$4C;o;o278|lY3kwmtq2MhkZvRykX z33}>;G*qU1K1d?l(}UGNUD>W0mIOU@LK>8_m6b=^}ZkXOsXBOj5-c6uJZw%q1bB$PkysT0z$XFfq>+RK&i50XgF zIeF@YG{OpfKb(_klnxTvPW8ig0ZT&V)jf4W8de9R28nE^dhUA`C82ufo;o27YfGXA ziEO9#%J*JMLhXlp>V!0`O^g~OvYpyp-$N=1wS(@d6VkA@J!+81cIrQT7qBGMp1Y?` zNQ1k5B(fdyD)wE+SREumPn|H0cDIj2wx%wE;rZF?3+Deuu!CoHep{Xr7ho*w*R z+pF7Lk9pM+^wbGy*vfXiD-zibdG*Ds+tO1K^wbGy*qVOSAd&6q!O{0#-PVGVpr=kq z!$y`-gG9Ec2M6tWO;G{UKuMx#q{w!I&$?GL7YDS7IIG_2>0>9C$`p#8yYxBYqi_mZ&w z^+5>Bt71OrCuK9;j!R5~Ge{dJL{FWN#`t_NjASB_>5x}x6lEGD=&2LZurXZ9D_kqn z?KsgiNZ7b7dg_EU#^-}!WEqJ}x8q&YAYtRr2O*?kW9pa=64`FY?WRG(#?jGJC!{es zA3Q!1nQrGFra{8y0}nz-V|+dsW-O7&bUTkS4H7o5c@RPxn%(&?6i8${l&dr!Gz}8; z)Ct#6UGIfC4vB2H^IB*)q3inZ2kQj#N@IpNA9Nzq?fksVt4JtELq8ZjbwV1P-I2() zmn;804vADUlBZ5c!&W95rGrGa+w~Gl2MLu||NUT{kjD6Y(1}d9>prGILN(QYKUgQE zVJ$;U2Z?N__A2ytra?mOhkNRTG^~Y-8YHsauEUuI3AKa%`@uRPjq&-Q6Pa$;6HSAJ z+Vjv4Mo*oPhSp<3t%~U&k?oLIX)V(1Ti;~E8J5DqW5;ks& zo;o3o@%f1<}ra{8S(a}>Uq%k=kOf6id+xdrS zkg)kc^wbGyjL!$XrOtFak1`DsHm`}EIw1|s?(7%qK97n-rbD?(^Fh-fK~J4<4gak^ ziEOv?T4*?->xOmF=&2LPt2kF9k?nSVZW@+X?d;A+8FfM$oZTr$oyfMAt28DmiS(S4 zr%p)2Rwnwr@JAxs?Rtr&gM`Yf{~EAPNMn3H=tQR5bsy6pp?c?|*E%5$YZ+oXNMt*; zS7G(jG)SoZa8I3(hP7}}gG9F5bvV-?p?1(`6Lmrw)>20e64`Fo6HSAJ+H;>3)d^{Y zxmx@CK@!>ae()I6Ad&i|=y`d>e_Vz}_G%k8eV+WGDM z^N(4jk!6pb8j;?5s&5;tv0q4&a9dIP9k62f&TTF*4HER!h@_!&eg1A-5^gK%-Opd4 z6))2uK~Ie+G~#JP5^j4szHswNrA8!lUH8<8q+uzK?G*{P6{TD_^r@dH^C}Yb)QF^U zRe0vd+1p`AxUDFag(HqQ$}~vOQzMeb17YW9jqO^Ja9dG#zU6zv+ctWIX^^0&MkEb= z2SQ(1QAs4>wxVu+{L10J|1&fV67Rt?{D_Ex4rf}R>-=?J^}{*4h5ZY%20qgM|C36{Y8Y z^1E*~4HER!h@`<8Bnh__rRV?JkNw;6KYk|AmO&6uDIgbwpHr&NYGOw zl15lnYxD&PrGtdqin@E#>*9zkwTUF?sS!yd^aPEM$Vj-YsGDAKT^x}m4HER!h@_#C zt`e_wkZ@a33*L5J9FZjr670MZ#@GDHk*% zEAlE5^wfx?5yn@IkH|>4ttdTBjmVM)33_To(y)@)_j2Xea#~R;l^T&H4HER!h@=s} zFJj*fC*iiDRJ$}HOBy8TsS!!TT85Yo5^gI>t%OEoNrMDEH6m$P3l}v=xUDF)b{df- z4HER!h@|m5>_L)nTTyDYH6lwIB_(j%r564>F z1f%k+lD4lJ=6F4GdPw-Jcv6D|qm+lf23Ts)L&9gplNux#mCAyzCuWsV zpB@r={&{}hMKDUWz}EnCyw?x+kWe|!^YhH48s!9|R5yLqFvm-S9ulgLd48Uml3HSt!FbuFhlJ)Ld45g}5{%MrmaiJ-c%_3L65b|GmMapB zQj6;ElrA;s87I^mOlpu|OPyCE$McFF66{OLyCT7;ysA2`K@SP`iKPY!M&;GvaSeJ% zux~FlNH8j|a*u1!LxN+JQiBAe@@oCK20bJ=)+#kfFe>jljBC(Cf@8)~g9M}U?#Z|Y zJtR2xEj36mD(?b~YtTc2WB5{o1f%k9*0=^eBsdo-HApZ@+I}XaBFvt z-mP6 zR6b=hu0an8u9220C&8$ET4-E@9ui#ZEj36migUPl*-TlrtE-Gyw= z#2u{AGK7EEKIa8tZ{n+AMQV#j9x+$XAdGRA>)G1;GtxE=ivQm0eId+J2X}v{(f!d= zBhvmySW(j+%LL)HqHH{88YJkc5lI6p^gR-8E6T>Dra^+98e!>3dtNaeB-~b%jjuf& zAn2(PNyB#Hq6P`K6=m}T(;z`ljYt|{{Yra~QGf}R>tXvDQw z5^j4s!nmZ=h=i`|o*I!fEakCfAmO&6lnY^8Qsz}8=&2D&L+4&qtJE@(a9dG&nreMg z|6yxnDv6`qe$4o}jM(~ktCZR+67*!c-AgqMTe*v+orK%E6PqDfn@ED58j;drE09rx zgxiX;8Ioy`pr=M84el+lo?a z7iM0jL4uwdku>b&K+G!=ZYxTyc9^l41_^pN z4+*9z$Bz??vRQaVgB}umHl+p$M%mgxMS~s^EMuhx2}ao(M@54k609qw1_?&lT1`cR z9ulncr3MK`sU`AvJ(UDKiH)F8nq+q0->&_jY_-%^7FqipY`qCpP{j^RrU5{#0zza6S1 z=piA!aE7gNS0osvJPhXitJ!qG!Q^)Z}hsA!O2l-d}7J5;Gb4+*s^;XFe{ zg9M}0R{GnaN)38QsC^9Q87dki7^ODf-wsu3&_hD)d^qD((ICO7)OQ_IA?O(=e67E{ zD-yCjN_}uW9rTb;zgtfS2}WrwQGXuvkkI&{{ya!9N@Jpqas>|wje|PM6$nOYY*()z z^pMbau3kS#Fv`v?Rh~ILBs4Cq*K-n#vQt(S4SGmud|hv^NHEIIepNK+A)&cJz1=0j zC_BSe(V&NfR=Ml_2MI>mS-gq{JtTa!zA_fYyBHZIZGSsdS!?MbAwAz6=q4DYJoL9i zl>|K`e6BW`4ibz?Wg*SsN)38QaNgGIz3i2*?7!@e$2MYDUVqVW`3;Yq)$T&J!*8X& ze9`dKQ=bt2UHhEB3BOSIec1Ebf2||te)p|Qqeu6<=T1vodaJu;hR<95D0|cGlTX>d zxpT)&q6R%RBJF>K-`q7}H*SJ(T2Z_2J2U*@vYu&>pr=M8jR!&+{>y$bLc(oDU4Q&# z!zUl|7b}S*=&2D&BdnLSZ(AVYwxT|_Y{_t^gYP#D674-)j$h@@d_WHB8i+*Z`i@4gu2iUd71B58z@*!Qwa z!fi!eb=e}+4-)j$h@_$4y?Pxa;kKe~f9fLCa}xB_h@^3MSXEQ4QrRWpwxYcCNo`_i zuNrT!a{DnemF<(Jyj4o=6$yH3MAEn+{8r{=_WLLjZY%0%-(NaB?+NQ$n@ED58j&>a z3N`j0_KS5AZYyf#qb?urd-q1BL4uwdkuxp2q>+nELldTK<{(C$)rt3%Wv;kKgm zG>MnYZs-~$)c3ikMzk93?h*;N6{Y?v zr^9;Acvqz->5)hp)(=h)PAf|NRel~M=&2D&!}`IfLBefCslUqQiUd71B58z@*!Qwa z!fi#VzsmK41U)q(X@nZp_c}riiF#WQqP&&D-!h7h@=r( zxb_=vB-~ci7Q0@Ac9#S_HNw(?clMKTTTy%d^}@E7DBtQxPmM?#p;yz%v)JR1a9dGF zthuo42U~)k8c}Fm8JhMH3Aa5Rxj(nNiiED~o*I!f!U&*mV}=n4w-u#a$m0?c^wfx? z5k@k78~cn%xUDEX%{(6@K~IfH8klpANVu)2Jpa@_=h~<2-@h%)ATNB*kLS`uLgiR< z&NQ-AADjM0{rsi3eDBi8Uzr;}hfEJOm?poz{yXZEU{wBE-na%mB=~Gf4H89E`_;d3 zjr;|{REt!`lya7_QiBAer2UllZDF(R%#8Zq;d- z4+-`q-9!=9ex-DxT){(vePXH61HmYL^{@T95|B}!9un-^0fgKo!6<$8FMoF_GowB| zBsfON@p^(J$|!z!DKn$cLub!8p|Ra$xgxfg)`12?|c??&M8F^PE7?r<1HLgJq z366cUg7S()5!HT0Yg{9Lkt>hxl|LNAml`A(mA?iyu0an8&P7TM5{$}UH5=EUhXm(T zr3MK`<*&1iYtTc2bHh@D1f%j-=EgPXA;CFrsX>BK`D=OO8uXChT)osFQAD+0{TtWF zUl2^ID&8+~&7ssF!6<3BU)u#T>eE9)cj)~tfKWe3FiLsoU)wDSdPpeWH0qmdOGq#( zl?DF}Z&n%g=^>%#uTkHm1_?%~O#9b%vw~U%dPt}o=Y50Blmw$xH~nk7IbIs{kWhWh z`v#dQi6W}~uIWU%f`^3KmAr324YgPPy;Mf2t!%%xn*nP@-9thxYTh@pZI?5FYM&++Vk899FLgTr5 z{UE`p{FUo*4SGoUTy3%~A;Bol;o4FX3?H|rmW%}FZSlReSBCf2He%oX)cJaEZ8-lO zesR{?GgJ4Ue|9{hk@gM3duyBU-r9M3Z|#{Iof|yqw^rZX?_9mNHqtl#-*fRhukha5 zCcL*ct|8M?BhoCDzndW8wxX6?d@lB#NzhXxl7_A6$JGxKZY%2ZSDhPHKm1EgBNikkD4Z{vIk33_To($K!0cEpueB-~ciwtqSY=VVCGQzMdwe)p<7 zlLiU56}5csIXLe_f}R?YG;B>jYLIYSQ6GN$0-ReSK~IgabYTCSgxiW*c;bAVztZo> zRJN3IdTK<{u-}+W5Kb$~Tc6Y>hTj4-;k~u7Ey?Z2%v82hNzA{GBB7Guo*I!ftX%b# z4iauFO3y$4Zh{0oH6m$*Us^Q!wS_cDxUDEX|NQ$867b5wOUss+?J>}{m*%L9wg|g z5m_Vs!fh&jw^lVsxGhmnc!BTdNu*+?J^84*oRy2MKy=MAk^Z zIP9nI)~W^xwggAs+x{lD*CRnsjmR4I=0{g#B;1y$ z15P_vS7doDN`jsmQE15eYDmIuFNdtV3JoRXy6&kFS;I;$E3zR8wrbE1SSZlB}$&AtjKaXNYGOwvWB(Yv6O>^+Y%+MQcnD44HER!h^(RSgY&ne zha}vVDCu2taye^|pr=M;4I3G>93bT>1a{USK~Igy8aBeI1_`$%N=7?5NuD)G z&{HF_M*5%uf%)y^T)LxO9@QiBAe4%q0Tj`P&?kdR$ie1|1ehJ6x@dhWIt zb({;QhlK1V>*vBrFzPo?y$HK)-W5G0d{>;?RTsf1(XRi_iyjibE1uLK!6>Q2`tQ8x zA>q5?NevQ=%59rFPD%lTdH3LX-i+e-~zi&4{?o!`+v=pn&1N~uADQCI%^c^&9^!b6&@|OAiUIeM=1zjJo{U=XJ~<^pM~hzSJPWsNXzQ z>dLdu!K5Aq4+-u?B3}C-2u6u^{dZpUkPyB4d`^NaD&mA;GBJ7HaD& zdPvCg_jeX$U6EjvwCVKS+RB(n4+&|ASTRf*ukwu1I!pQiBAeWUNfzt*sFBkdX0FvV)TvBp4-Qe)?{0g`kIojPsHmoYWw} zs62Q1R|KP-_^g&abBX$QKX@&%Jxb=_dO7GJA@gp%93&VeYl-^vpoau=q)~1eOGq$E z)uwC2=nIW1APE;S7j^wbC|M}Fs}njrU)QGHMEpaU6AmO$|NvljdFDnNLdTK=0us6J_LBef`lHQeeUZz2Uo*I!g z_;!he+Y%+CMA~_o1_^p+9&}B0yf5X1zcXf3qBSU&iqPFFhZPn-TnjOq}>Ip*ne0u+}0Kq8B zkyi+MNJyXey=dH%+!YB%S+2jLK@SP(^XZ-N0tBO^2iN~@A3bvk&kdC2AR)F#*}Ip@ zUC~2A`h2|{Bp7AykSZGVkdQuKe;y64K{AH&AMjV3fUMt!U6gLi&7qU%LRoD0^32A?P6?V@W!Nv;e^< zd*@vt=piAy;&f(e0fJHXw!cEqL&A6WdEAXBB5zFeOo3jDQF6ESzuQL-3E$mMYLH-* z)O!8z_R&Ma$M#7L5{$~NXH})H=pn(mBx*{=T@s9vHeLU_ee{svoLFj*V3cKXE9Ibv z1n2frg9M{2w_MSnhXmIsr3MK`S&qD-K@SP8wMq>VjIvyRMS~s^Tr-v$Bp8+FF3&~< z)4u;u^|^$s!YA7oiUvI-xK}SVNHEIY6<0Lq zA;FwOsX>BK_RhPaK@SP$PD%|DjIy`=6%BewFb7m>kYJQ(*Z+lkdSsbhFn0L(TzZV)~dPuBT_vYs4 z^B$>msX>BKcf9V4&4nv&u4vFh;++qhX*Pb+))fsBWt9A;`b!m!{0r&qnI!(PqCq0t zIqE5AUs;x;t=-Zican(@{N}S|Ijo9@V-k#7^3qE>o(H2Y`0EAjGw3GhA#w3epKPCh z`OHZ$>SND4zimAwK@W*HUU7Q!$txcgwcD1Q1f#xw#5v7z%dV(AL3&8^h97O7{)!DM z8YCF?^sUZpUj4#PRWu3@u6x=ICpNEq>Vpdqj9T{WQ=6kM`)CluT=e1iZCn1JS@HUJ ztLML-^FPfew!B^K8@_Z`NwjrE4~ct^`)Tu@dwx{WAi=1w-}}vulG8)tkmjDULI1*>R^jjS*k=J4rN4rvE^Uu7$dCY;w ztd^1Uk9WSTdFw4hwNKmd{mn}r`{J?udr8nkqSt#_^PSCi++lu#QBU~i_ct4#zjewQ z&ebSAab43}fMC=EOOI>zSbt@Opohe<2kqP3wOMa4c~>MDb@t{bG_Tq2Ar*qXXzL@7 zZCm(6kFqKrj_D!MeB|A2?<$`M2}XV7zK^thvn1#tvDcdpYp&Yln&^Y=U6EkaQ>H%D zykW(^R0w)VeEri0r@7>;1qenRx7&%$*M9og3PBHv*X;Gm=7y7wT!3KIrjIzj>7RR# zw*0cL=pk{^2lj7f4w$NFkYE&hTB$(~32S2&4HAqh`(vmK$JbtUYjgH9R}HjP=P{}g z`#UfAdh@7HUX=emfZlLictF@_w*bMYz2EfhW|KY6tPu2&uu*#ff>9q`?|aSd?>N3f z&_lvzp9Kg;?Y!=PHRHQpS0U&j@$x-?D?Mrff>H0<=ZDP$>n#alm>IA&Wi4Q)#k?W)zFhlJHaw8SdGsMkO6qmFry9uoF6D;gviwZ-@+ z9rHOoB&=0dG)OS&yEoq3u`Z#9g!Qh0*qg0l^*_~qp07JxXW4$&?^Ib|71u%( z`+TXv)r-wIT0h+@8G1?9V0b8By5dR z(ICO7xBlhijv0p@61LW=XpmskXHWlF$IM9&30pH(G)OS&iKDYRRsi?jy0W?b^jqv& zngh@^!`3^E@bA&GhU3x`gk>p|j`)<>E(k__>m%dlj(@qaQVx1ZShl62L4r}QoxQ2K z_^UTmH0U8=`>2Wr2}Tv`E)>07k&&={TSbG{Dx$DDgM`#>-g9UPZ7-sB_cN!5gykG6 zcSV9xd%WaRvEsyS4abEiXD0NzmIArX_41CENDm3i zOjR^UFskfnQCY(=JtQo5R?#3)Mn!)N1$n#V`K$f5dHldLUSfOhOze`NhlJr+Keu7cnHzx^tNO*sopJ0@aF_VO6Kg8qt z60tq=GD*-w!ZSMa6O8gK?j%7E3C}srPcX`J%aa5>Bs>E>Kfx%DG38iNcq~sX*Y&*k zqy`B_aU?1=e4QxQ@|C67zDAwYpofI7edi|_C6W2+2_@>R|J1fzWAJW0?)!q;8%6O8g5 zz$8Hr319WkPcX`NGLr;7Bz*TWKfx&WwC+Ag!gpbl8oU;x*dI#`&lx<+;pBf*ul{jhvrgl;>n833^C)R&{=YQJ!0#BpBrx zVTtM{=pkWm%$i9J5{&Zw)g)1PY_}y*z6+b5V3h9@Ckc8;_}*}Sf>FNToh0ZX;d|Wq z2}YGG&gg~1K0PFSuRf_kqKt}lX(-5!#or0bwLBLpw&z|aHRvH>eWkKDAi*fl`%Y@m zL&ExeMS}#RJbyi@K@SNVyDAza80C5RNey~PcHiHVUpm!##)K)in{kW^pLQ2 zT-mFUV3fZlpS&x2NLYWYXpmr(zwMvYpofIN;h&#il%HCdBnnR+uk_w+e5|w*5{zO` z>+XXjYy_`p@LG&we=Ie){`8XrQrhmdXz9r(2ZZo9qmy+-f>HjCb&{ZmgsrbDB`3is ze^)%IK@SPrCsZ^@Fv{POPioLZ!q!(64HAsi?Y@lT0(;LvktFW*;)7q0u-{?X6*(FIlA=>A(GFpLl1p^NQ1EkNn092anqQ&gTAIJ~sH|cV6K3tk}KY zDfTPYr>}Zx-=fq*qSw2#`O4DM2U{=QbsnOOQerj}AF;pszDB?LPETC-(N})Ex!`~^ z1}ipue$wb77-jZsCemLr*I&w}FC6#jA#vZ!zukQMy=M+i-hWxr=pqYP%L?p1AIhuf3yr@N4I2%kTBN2u7K0{X=?^_b7TueEFSsG|xTl zlLP5#x$o5oMwzXBv)9{W(>+yVuY0%Y(?jB>1Mg@adhaI(zy8_oNn@RL_w2v!v)f&> z&hJZtQNK#W2|xMd?1uLX@!KCP?_YemIR~BPAybM zpW`-utrFXu`oI)DBsg~UdJnyI`S_jxviFipuG^&l#_R8FHvjagspsrDc<{VCn;rgi z>R|n!?mpl+mPUrZ>@k+w-TJTF6eC=Pi07fi+%eIvt5M}>_v@tb$BkEvPX9}(vFZ7D zHa~pu)Y<#fUGZ+yUuXK}a@E*3)fGJz!s_Y=>%LZrZ(RJq6bZ96>b9@m*}QzeQwML* z`QyyP4;g>refutX#j|dlqKCwyyYFm1{m4^oj{3^_uN@yWK4A3vPq!L+-TzA0-DEn-d-jh{nf=PI zUot3(TYmCxy{pGR?G;n>RESwwOQdhh-gcA{-}=uD3c_fO+W3F(Y}Q-83=xr*0PTceB~Z1moJ?5^JY=lz$YyP7FI zL3ka0{D=Em$shWhmyb@kxYf|>S}n|OcI-aw^T-5hcZS!h5VM)U6D$a?U5T=%Ir#5o z%hO$1D_N3S$qYRtyiG4X?d6HEmN-f+(KS@vTIK9^gXL}i$OKyZ46juoW;1~vRS@3V zCCYl&;L&&QpYFjAHqUb>i4peJ|biHR)P;WqIoFU*+~}w!doY-St<=-&o6QQA7>I_Ss<5 zgI<~FE`m{J&t?Lv@G(6kSPR9vy&xE6_N>%fS~J)@_}0H}Gp2_GpHr{5>0bsjmpuKl zB`-bbJ>wszmGBSKO8Buqc+J4yI(+fpUo$A{@ad3n$Pv4xRy05PvmF|#t+v^>lR^e}c!EuYzD!eEMiC8(mHr3S|kI3ux zYvvGTl&`Oaz?wR>5_){C{@Q`BoaGL?2}b$)Iulq^kLe-dE9YEqT?C_iece6}Uxkn9 zA>k|M+zYS@FNiWKudg%lpsm91)xTOuPhP7_l&_p~|L7tZV73*suunM1{hlH)d2R)r}EYGkiMd*$?XcVY!T* zQZAz)80A@!JP#sYGE<4t*|H>%lbNB%^Cfa!%kIoRXQ`|JEbp^8<$Vf*QI-Q5yjuy& zEnS^*OEdJ4u$+^vOD=fe-P#i0bz?~|%Cl5?C9~yi`J2v{J+Q$HJtQ7n=Z@x)e>!*Y z=CpF^^`7>Xqxz?A`_5JUjW?X3hs2)~@ppeZcXs#p3Gt)V$MnB+@{v2Of9>KMNR&}` zq*HpIvbE^xiI5((!*)BRbz*obgsm){xOlsr(poeKvo*@-!E3LUm8{&=HYXps>b=)4 z-lg;?t%Tj}>_FGlR`Q)v$)`v#%Ih$%+flnkcCbR&N*_dR4iZI^AVOH!++C$8&jl&5YY8eIgVe7%y1G&@gZAjLz%GlgHe{Jlw| zi(r(mYBEvFCyIxJuU9VnuxNAWZGc4w5KeujF>z zMKH=&HJQLlrcVzEU$00{t7jnPT8#2lO(tp?Nb!*HOyQq?CmOQ$IphP|Uz658ZO&2% zMtPobJtbDB4CEiSee%xxApnpDN(i)p8Z|AE8hv{l4I}O zW+25=A!akN-g-F$IfV?Qczmxew&xjl(%InXlz}|z=zW)b4;e`DknpTXo}+3RNV%@( z6K_d$Ng!X+<`d;w6=F7PASY80p8b$0&oln}kup2iGLYgS;aMt~=X<>)QU>xnPd;!o zg$$%z*Yk-7zx#wX5GGLR_`wJ4<^F$qD2NWdxG%i@#0?zVY$~)%DuXVs(U_hlfehQ76zF>?Ru_HJr!a$ z6SWMac)WJS_B`V+KmDO}SG5eJcu06_|EE1pO2i{lF8n!nEg#+c-;sfo>v}%%)K7iL zTjd}Vud{snMw^}0<`czJA!ai%w4DCkX|G0gZ|xH0dB%_aQtnE6?R(c8P-Gy*Ln20> z4<|x0kn6p7-y#Ef*@r(|5T09n+^<9fqfeWG6oOGPu8786|FL}h$36ERJ%|kC9Z&d( zkIsXwSAGN|kr1^Eq-glKD};@YgIA|3)iaPnFsdv$)`@NY>Pef)*O>Fla`*R~?DlN7 z@y31ZYf(fE#P-?XgeyLp=q`d$X3u5{qiEA^E;vwM~ zNO?~64CKj&PPZAz|9thdua;+X9o90C;_(b5h(RX0o`W`qIe@bh5o>kv_=_w=RNFzP@gshp(yIe4=ZOW z*O|au{Zv=<k1m2yzP@gIR9fNZenJlkUsLD)fpvSEfs|`8%GcMKz$(1W zK#GTiX9^G6PI{D`1K2s811Jbad7g1^?SrxkU-yKkUXxbgZ9Y*vBw|f1qv)}A4&V*x ztqiZls90YMak-rXIN_8B+6<(Oq9i=eIMf;EuyoRCzi0k()e)CQ22wmEJZreC&L6c5 zq!5hqd`X@MkuPa8ka8{0en?bF+-;}AmaQB4L`3QQ>Y2hvrhV`z{mbhjpC}#@o|($)66CMioTU(q@*G(vwy+H3#y^h?q+r z<&?65DFgZGC%kjjImkeYhlFPeFHoYEffS;Q%2~s_8uWZ3Gmzq`5Vo=e(Pkj?wQ@cY z^x&%R$O_r+YE{aMwi(Fm3Bogl|DpD}6k{HUlYy*RI&i z6sEsF__%yNam^#nntAUdPHSF}PE$NHy`8@MF{kNy56Oj_ZSS2gPPx|&Rxcm@zlTb; z_B1(#p!wE6t#exQAL*>Y?I}Zh%SNZ+l*N_lnac?G+dpoQ?kYSL!ZNAvxTb%aqSq{%6uS{pRJPxBsZs z(Cb<)%pRG}l#~SOD&<9U{m8W{gq>me?z{3?&O09~XE}o~Tce)zjMJKDq_a4W(UX~5 ztoPdffg7z@^4E(Vn4*Wona@A1JX?>tRTY}&b{+unLe|K#8AGy3MT_OA3!rqZ3fH=W+OVDA^D@sS!E_wxCxE3TIF zSK+A;s@?0I`_+8L>*%Z7yBf&(E8gJ-2c6bDHl4+KY&!Ln_RfFYqkr6IRxJ6;x{vD9 zL!vClBR9yW+y3`g+w?1?)iZD-#T(nDgai#{gjUMr_R zNifQ6J7Jn~$Y~7e_2k?uJtTU))8*W2YFBcKwTmdDlt}GOh?GN4JNfjNZuHzMJ#pRp zUVgfqd$n?O5sWh1%E5d)JtQ7|<>_+n)t*Ne!6>usd0_w1r-wwZcZQsMwRY7-lu=4p z>q)EEw9ZZ013mXjPh5AK-OrG7uhu`h2u7K0{R2D5K0PF!ec~B%?p6C^v4boKMwx9R z+@l}1r_7u#(R#Bz3H%3JN#msK0PF!n26ib zxz|mV_{R5_k3aMBBX;`ACpRewM!oU+GjN9fDc{LwIgk6yCjCm3j+`a2)kAY8b;$?h zoMl|gY$fjh>KV<(hn+jS=YDdsf4h`>eel&=?|gllKS(g@wnVHE3UY1fw=d#G}$X`oF9a;?#69^CKU+Zq-I#+;JCrNTj@&ym7bp z=Zowt=L=u6xFE_XB?kE{rxUlnTC$w<#C1)3_H%lc^R%S#kdv<4>4VqrSP+b|I~=@Y zC?^N32${JJ3U-eCAkX6a=GuZqKa*Ylf6{ z&g&2HkYF3@_1^Nqlcu&f?i0_s>d8l>45Y5M^|Y#gTSm^kmhJ6nO*8ejUp#5$|Lp&s zq9u~pCbdvML7U!r9kFtkbN4)Mv79jFwaTbymA&3K*U!76{eHd8*mgyO=cF@&zI%}} z`F(gD4o&_f1JDK)*^rh`eEt6oB?{_kh&N?e0r=#g1;ro)@uDXaaD(`nP z!Thd8+1c#8cakVRCvEL*MwkSn%${xgpc2w+=^?@Al=tUf+1qplfNWGjFv{~xS>vdb z@p^i1#gg0px0>-9d`(X=M((WFyTVRQp1oc*t46}sa85jCJvnE|YpJbKo?-jGp8k}( z+B`kMbXPN_Cy25flIz=R_3|Y@f5=WZl%62$N`oJ$26BB~S9-pcQLOb|@0FH;+&;Z` z_6+35Q`XsANzRMs7AkhHCwKLQ@$%7|kb#s8t(WP(lvQ<&oJn128OYO-ffP@LuuLkR zd7FXEnN-b2YLw?057VkopD#)Myv;z0hlKaReBMVgkZFV~GLYi&oZNHM$ts^q^0}p222$?C z^NHWs{&*it23Z3mLz{sVPlZT1eK{|Bh-DyeM+QM3U+U-zjp11TO7 zWjQd{wi!s2R?l^n1m@Z{11WXlW4qWsKTe*~-r8LUkUqkDc+D*HORC0Rq&O)Mm2asEP z7r`jsC$v3EHKZ@nL&A3edAyQ!uH4mJf>FLt$OLv1Z3a?2Bs|afUwVqw_O+|hzP8OL ziid<}4UbpC_Rc${y>me@%6H*;OvL`Y%|Obve77x8C4n43n@>cPj)zbfVW+I*sT zNO*2Bza{s4A~TTrS~;JXqjH{cf=FW{JwbS;@Gd>eX?f9|QeLzm80C4!=PFUlK#GTi z*K|J5fZA;{kU}uZpGPJ>Y&qno{oO0t45WBSc%JcKJ$aRnTbCH1*4+(3Dvmerv z97m>>__)n`JAWG)NFf;Itv#=hYZ*wnmbYDrDhcHD+k7IT^hAnh3LmfMWbC~`k%1I~ zQJ!afhMvWdk>S*Xwk|S|;vo?uk(~GG+xw3TPK=zT5R8iPN{9#V%I{dd^%?o4cg{e{ z2_X`mXZ)(3bdpi@#J!FvGLYgS;d!5TDq-)6c1rJx+6<%+jPltapTF8|nBQ~CxjtWu zZN-)Y-1MMk2UjeikNb!*H6+nARuSzh= zR|D-SJzoK|`9$%M@Oi#HrB@}&sJt3zPwDCGoZecd|I(A!4-)0`e0xf-N-)Y-1MMk2 zUjelFMDdU)pE=eH1;Hqv+jA?ynxV}=iiZT-SUm$Nwd?srImKGGw^{~Lo;eB6E#@<+ z+rN9|E+60hxW#h9l-DYwqE+^KIG538ydITK0{ZSHpFGTY#$0k)SK0ci%_kyCPhk5V zr+pq(f>FNT$plVWv>8b8knnv;ZdYAI8I|`tZQGraa!9`2qU>yT-aAQ@?@QYLQ6(7V z`<+biq%1uo_?*(&!L&cWWB+}YJmt#BK;n7msq5I$%P1;maneqBl+NO``9v8-eU~cF z#&e4|>FH1GwhMw$v5yuFoQ-NTkTQRG#zSn+Gv1=}hh!$6yndO16c33~8Yt7**EQz3Cj;`@Xz<$@lMx3?%YbI&*q9Dz6z%O=s1b zyAK%sH!_go@eGTU+;fZf>Iz_J=i#>g*+HIF)8Cjd%JWQFz&P5ts`Z_x4mU+?-{bJT0@PJg#;dJy(#&>LRS zeEhDj>c6MIf(nA3I+5t!7cSbY-`pYdQ~DpT)!L)Mnpa)keEQK}Fbxugr%ISc`qNuk zW9r;-d#$jg95-_~JC6rT1@NQlOJA9~FAs2e`F zi&WL^H{aO2dGia>Uo)N_ge_4wHE;Xw3)A1!lhqOldg=r;bj3s>?2+sB3k@agy5{ja zA%VKmc}hzDZ?Cy~wOlLg6qRd1|Glj%CFrRWqG3;Pf(Uvvu%~GnBnnS^CnQWm+OBF? zOVn$HE#=Vu5gIK)Pn{4A>rqw?T&unANc*GLVM$28Yduv$G*T<+r*@@JaK|MVNxRY~ z7`8-R)O_tHPmXrg67(eo8A80XuU7J z>Bi=Xm+q+c7hf>j{AS00mCb*j^jEcS`NGQP8#D5^Wu-^O z|Aze~yN$$?M*Zo*>wYv6da2m2ziTA4+7T~b`Ct6@tDDXDeNa8u-hO#=<{d|*ftA1U)1+`r}p2tKPTa0tBOOyzQ!H^;b8p5M{l8uDSaK z7wR+Mb1Lhq^aQcjkFRQOdh;r!y9q|UW3Z~(@nyfM5I4Q%rsm{-eVBTVz989u*-Y(Y zPra#m{b!y~A@1Gr(&o&+%j%!M`jY0YJ6xer=f3ySX5)X5zZE~X?b1Wy$U81=4*K=y zDulHX^;lm~+n(%TQp0L@wRo(xt1WsTy<=MKvaZ;3-tyg%v_!owds<1*L*lUeN7522 zcSV9xPq=R+EwMt-L*l`Wu9KFy0Kur|?RcHE#0tSDc;x+;G&_9#TCH6^o3iBekXU}{ zCCx#*U#E08!Kkmj>yqZu`>wAL^pNNueo1rND`plT7bMAr1*%~!ehJAWSSUD;hB+96+ zw#)JSH~(`}v&kd2((87Q?evh?YU$0*ZXevHa#ti6wclYkH^=R^s6x;~;<{6BZhrJH zk6wUa)Q9i8xp~XJHNsl8Udvj$+SV#78uXB`UQi*d?W)JxtJ*=#ufMAr|ZCbrnh|&|+wbru$!Ki1Putr*Yg`kIowc`Z{M!n+R zHPUM<1U)1Uecfsq85STIWqZyFK@SPru`WO`%J#bzf*un4e0{cK1wevPmO-d!&_g1< z>u6qlXl?b%dFc_)T-|)<#=Ji(TV=HOVV@onAOF#~+4bSqRPKrdqauGfcR$EA=kfor zM)n`8Wn8hosdn6xjBxajxMbfovj13sV3f4!wEw6O^pKeS&>Go)EI=^orPr>J{YQo1 zp2JoEHiyT`pe#9803`nI2^TekU))n!0gzx6R|BO6JtPiU|DxvM2mhg>L4r};t8jWq zy#Cu4Hk+KiexDPbb(!qEDunH-S4)lBZd+~Jx2s*2gB}vL zyI+7{l$EJM&_lwq6eTf~vE&)!8)e_$mvVeMWovyE-aU%aL*m!pxl#I{Ua2fO2}W@Q zF9~``oc8A%r4Lp#NHB^!vQmQ{5@&Cp_J(J#zf@|Zn_v{Ph9zOOt7C@EQEFSgsa+EE zkYGN!n_!gHTSdcmirN}%2dTF0Max!_#D;x(NZ5{b0fJFh>lK0?61MZM5X|E;zq|XR zuW8nt|36D7pCCOXK63xn&947&!vaJZb!}S1)mGuXUU=pb=~qq_4H9B|)aQSAZAUpu zPY`eWhc9%Lg9M{&k5joTdPs1EQ?^7BjI#YzMS~s^-FqAojACxNyeoQ0Jo0}>%@6yv zw*Vv<#Wzi*MzOkU-y%;BSf-LFJRpkq(Ll_C@dc7YuG|#~MqPUH1(HLq5cH6E!66q&4tW8B zQE%V!0?8p)2=gqJ@xutUOo@6$lhlIU}SGt>E6yJZA1U)2d_gc{)!6@6kRtWAU z;vCuZfcu2nh}bfPM*#VGDYBVL}M<&c)jbGF=) z+LonKyCsG~&_lv!~z7PxPB}(=pkX}Kq?v}7{yaor3T+r^BuIko2t|}^(spofIL z3tNC-l#ELCw;A-1c*8cAcVwMOFp9aXvUceq@jtg;*5<{#2}X72$n5mjKzgm63RBz8 zm#JN9&_lvbp)Ei#igQ<~K@SN#O;^z%!6=@~DmC7;-Bt2_aJ7{DU*CL{ydPA%JOLBT zuul((vo5|$-VZ7r@iJbKV3f_A6@r-*I}M>x%)FEu^pLQOS4D#aqbxsHA?P7t8MXxo zMsbH!mV+J=miMdV$Vf1%JF8ag``VMs(*y2z%DXB&Ac`~4K!$x1jN*O=Kx!piM_DUb zDy@?1u9BdKgtbbgy9q{d>?#R*NLatAXpmr3{JvrCN``OmE!(1P$uePTmv==E3Cn&h zK$KCM1FR61>r>BMBIW%SAS^qmQI^ZB5T!@6gBoSo$OQ;SS%$Sj&_jZwQdzqs7-j9P zqCpRd?h%dzqih79m6l)L6+I+uFH*TH5{%+0_EMv0qwQ~H+LO6UC+~`_oxjZ~esu$p zVV?w}IJW~xBLnvtHiv6zxi2XRdPvx6pi);P7{#YqYS2T%%2ClE!KnCU$J}RLc-r4) zlqXud?~1=3DSqVvq@0}@#g##?_Ybexe0=;%^Y2(Vo`*de#MmyswCExj6}FUo`B^`h zIr5f+^>-}vggqKW_DeLn2u6i18e6RR$jndgeTQn$6ZU8jSvAqh^RJ~q1TObGNRE%Fe+@(c*h@(9zW)e&+D(Y zBG=RY0#Mhu%pi3Wj0#)s>L<-H>K2H&=Yohion*?T?F5Ahbd1I-2|h;7L5;Ff6>fg|MgbYpeO9~Wr}>V-&Pr21f#+h zjVl-JF!TQo{x{X2C+z6~&rfs{j0#&cwmoTs>woZn@|V(jJ$k~P9`J-mH^Hc|MZ?At z?dQzUhCLcspHFWZ<|7ytwv1OcGU#|kPuL@zND_@M!bS$Yldwg@Mh5+!1wCPpd@QkY zbP+Z(XjIsuVPlDE&=dB^#}d=%B5Y*PsIW!D#*#k9k`&dBQA${!Uz(ps7s05oMZ?At z)u1Qrk&h*&(M8zEpiyCqhK(hvK~LBtA4^Q5i?ESFqrw&q8%tD!p0GzgmY7BtVIzY^ zg)JI3GN=YUVUK()F^w+5Mh1-vTQqDeQ4M;+9{E^e8eN2q3>p=-XxLby8uWxc^0CA; zx(FLTG%9S-upP@-+OF+uG%DT|i$;Yl8n$Cm4SK>(-<-&M9Mk9`7!|f?*p5XshV+Cz?Ry;4 z0MU!6b|<7!wtGpoXxNTLHRuU@+V?o70iqXC?M_IeZ1-XswqsEZdcvOeJ&tLB=tWe! z6VfQ#y_kmWSX6_auv1;-J&tLB=tWe!6Vj+4q^@kolIyCyR!P`i#56$ou1N2fQDKXQ z?O0TUp0L}!h-rZ6MO3@5(WrQ@DjK$9Q4M;+o*wW$Zb9@SYE(o8AsQz<`OcY*UL;?# z>h*XAF6_}D&cn?|Fe+>reZKaNhmS9O`QEBQPuS_}Fzs)?M5BvfRM?{Nm{&e?yziOM z$>nIT#ov;R2JxFO(dZ%=6}D*X`u|=${`Z@=QVn{-9u49=q-b;zj0#&ce)9F#j;}xA zr@D`#C+yK6PEd+Q7s05oMdQnVeEayOt7Cv{E(b341h%FE5Bj7s05oMdN+HKWIGM>i<-O zp0G!Q_@aYobP%kHkJ(O3A=qi zY~wD7UPPt4%5RZ1Ds0h6BSYWDk|8}|PY?JWuONC6H7cTl5REi4^ldB|(i8Udz}}u% zIY9IxYE(o8AsT69=-XH_q$lj@0Z)h(L@%O7MN|-?k;am~jU_{R!k!-R+*(2OB5G7b z1tA(~Wa!&iGNdQ$l=sPBIkLI}(Tk{25fy}Jq>-WTV+lQBPY-xfp_^b-*rJg}hQ5y_ z^n^V<;Q5Jef>B|MMj9FVK9_N71f#+hjkL$< zr}sEI*YfRK*rP$biJOmLRM;|Jr5(#udXJ+T^n^Vc#JL>N=pq;uwrHds%T#)gqZ;&t zJsQM$AJOO{7!|f?q#esH={=5W&=Yq0x>)<$KGEnR7!|f?q#er*={=5W&=dA(5Wg!F zjV^*wVT(rEvCO3RII2NU*rP#w>q#`a2u6i18fnKeliuT~20dYq2J!tO(dZ%=6}D)k z9m_bq$59P>!cKM7eiunJx(G&vEgEUZGEVPta$U98nl7#zUpW$uE`m{Ei$>b9jMIA@ z)u1Qrk^fRNjk}`JMa0*WNQg$-liE-3ar&}urzh<6-NF33ZJW=# z2u6i18Yz?7Pw#P5gPySG{%*UA;I9?J7LAli?WgxRszFcK(}VI?5M2bL!WNB`Nu5gX zaa4nzu%`$7)kQbKsIWyNWm2codmPoEC+zgS`26b{dmdc`qrw)Alu4aR?{QRvp0LYb z!E_V+;m?>+|FGJ&ue%69l8e zmhs9)1{tq<^n^X~vBWgG2pbtRDs0iPv1CRx=m~q|V~J^W5jHYtRM?_nV~J|e6ZXi* z64U4+Y-G@=utmd0hOv}`p0GzgmaJ~yL^bFMd*ow@X><`bGH6uTqG2P0YS0t*$j1`X z=pt-n(5SFQ!^RTTpeO8+|Dw(`x(FK?G%9S-u(3on=m~q|V~J^W5jK8kRM?_ndz`+s z-8ezlej_{))4s=1yPL2b%N#<+E8DTCMntuHCnanzVj5ipqrw&q+p(wyJz-D#9>+Ag z2-~q}RM?_nI~LWTC+un8<{`W6`LvMZ%F zd?KpNs+vX@VL4Kb3R^TRld2l@gxzLUO{0sj9H~ZyEgF`4)qNB_VYgXT)94~BN2*a_ zi-zT1RfC?e+pMZ-bP<*#)u^yV!!oI=K~LCiR@F4R2+O2uRM?_nxz{hsJV;O2BhS62 z-y2A4?;Mi*h3RE-K-G%WY38uWxc@?Y(lMi*h3RE-K- zG%WY38uWxc^4zOwbP<+s)u^yV!`=yN|A^mU<-g$Je}Tc?-KM8GAHk@w+i5%z{xqrw&qd&8@Jke;xo{hhFBbP@K3SEIrf4SOf78uWzSzPmMzE`ndV30pMM z$RO{8RfC?e+rKwq8eN3F;nk?HMZ@0k>R3Wg*wg+_IJJCfyIq96;nk?HMZ@0kY9FL0 z>}h`|Y#LpJz2ViUutme(@TvwqVNd%zVbka$>gdx(qEO6u|1Vazr=OrdR%V5~U};%H{u_pWx5m_x`E-U+_-V zaF1NeZHcnqG%d{r9QzH92s`WN4NJrZu`sQfoHvIYtJ>b|Pih)m!2tCW_d zkZ@a~{FnZw0fL?yku}n@=%*UiwoAfoiSjQNWDOGZ)QGH++EhQa6xAT%wnX_?^RosC zdTK=0NPVN9TD<1^NVuJ&@;7U;1_}QHjd*HAp`jT_5^kd$<3d9TyRLcS>pA}KS;I;` zCB57|xT}=8YoEvJtUBeF*7f6{h!J}2R}L|Lme z4HER!2-C=YP&G)nEm79HTmu9>H6m-+$eM>NVqLg zHriP^NR*!V+a><*S;IzZ)o_p8uiFx3qqb>~pr=M;4V!UPgM`~TD*x&`*A)qy$yB{Y zv>G=^&z1f`!flE2U$3_sEm3;n_vilaSwqGu=~bfO9=Vp=66L?b&l)7?sS#O2#$4%D zqCvv#9F_k@K-M5(-=5dHsu7u%xkGxDXpnGQqWrHIWDOFfC*KK)tRZut%xt1S!flE2 zZ$o4a67jX0`aBQk9x zoNAD8TcT{VvvQCqJ^4;ZWDOgsRfB}v5@n;dX^^0&Mq~|Hhf1%KXHLTH9K}5x3E$C4 zE!K!krz1F4PolDI+7JHInlmn6oc^nJ13UfuqV(@|LOc^hqBB8iy=A@L3r*uiiE`Wj zy_*mZ3AZyLU)}TnZJIQs9O6;i?!^CH%9qMfA;dF5BsvqMRNXv!?`HeIqa3C~4+*z} za2+QWr@vvbTQhpd4yN(KbeB&q?kW>^Zn|r8=<9Y<&*&k`67}>scNOKB)FAQlO`qSq z;(VtiHvezfFFm_9&)(6a;%+@!{wuXiPY`>5Z`bC6GoMx|2MI=9aOMk|mwoT46+%3p z-S!D<JW=i5aD&tqo{??b*04{4QKGlv4ck?SZ*8#tvfY07B=tyL?YHH& z7PWrTcyfj4^}<6!u9Ti;g?Q9=9=2@zUq7Lda-8$}hb`OV3NP(OqM`qeVx-z-o#c`` z!CDWdd>$lTasF=2@=c#o(ctr7RM{%2ap_;yUzXaBmXIZX*)AI_ORZA>J>sR6&_hDn z+j$3iO$SpFMO5cA=W{NI-mcA;Z>wpLNZI8!s=Jl2o4>1 z%4)iimVe5dH(d7i(|1+7ysN^KpR-0?u}0g~0z?_L@v^Ny(^QCFFFYjnTW>>Y(+d!c z`oLQ@S+?hArYeN>oHbHf>rra=dOipW-V)^77hF?Yp%m7^#L>1jR_ zMZA=QEu*(|Lm3$wdH&t4r0{_F))5=Z$e?toL4r}6U-FP;+g-b)Lgapz$3AK8F{}AH zXl_enjY^;Q@w~fs=^@eUHEE`<&CVnkb?r;1nlv(0o?z*T>+bfurR^P-bw#3#dQOu@ zhKfe77akIq{JJlzr3DB^eQ)<2n=~?12(}*?+hZ-VHuHHwq}iuqR%5F!qI@kn_nF&R z(nx!iIm)jqvt505Cc!9~=cA3q6Up;=@~B1;rQ>}5_lVb#0Ui?8j`Q6D8TQ#Hw!d&g znJqP{yMNF_;v-+#P-fAJ1_?%Oc*#Q(u~UVhhs0g?Z76f?0tBPVHDeTg*r$iY4u9HE z)}j>+5@l4^TGZzAHJHQIE>}^!EB1+AuP?g^CA#}Z=?UVBZKq^6k@Z3%jk_cmbA!aq*#pArZ~=l*_G~HyJ@(8k zYHjX{gtfPdhLv1BjIy>{A=tN9ykQr~6lhd;Kc|Ppmv4JsT9?%JQ6w03?~3gcu~X%) z=pk|5fzOlO_5uW>KK!O9G$|iYA?P8o-i?J*l6Z@#rQ> zPY`k?&!a?Jm-(DT8O6+GFw#H5Lqcl7*YgoC8nSMS^+)6^WhSbxWJ*sEGGF;RsMKJ4 zwV6R{w7c!nL&8Sz%JU$>D4Vq_MCsAFM59En-bzR?%GN6t4SGmOjnrE^2}ao}s?-?D z6XYtRTv^0^w|pM<%o`b<%jYlqgxYM7_Z-_&9~R?3K^F4CZin_ncYFbQ|)qG%Cmvz8DbnO365|i zWWK8B8Ay~-9J@lL9YwYMkdPTQ_Mcru8Pzo=+EY^v_9&}q{r6CimPii?>zkG5L86T6 zdShZw&D3=?(CadnS>6?iGHPx1=Op+(VXj78i&4x{l>}?odY6`|thZpwd60y?7qJ@Y zA{b@4@Cs3SG<*Ix+?D0qm9T7mMS~?|RQE{D(bBRldfl}fsYzJguX0zs7NhJ5RtS3R zng0!UMZ(@XRWx{4Wz<^beR}#fORp<>^{fH&K8%v`)pHq~Gi3kayZG+;gB}u=Rb7*J zVQjl3$|%kCR|tCxkUeQ1<(UcDw{_+E;#!QdcNP^5dPvC5(zB{j3KjRwha)>no2c-a0{~ zU0F_CSNcu7OAn+Zim3cN^hyygPte9I_1MlrZH{AAVvUrRgzZ1NHIyi$)@B7j!shmh zhOIKx!zf!nR0w)(C1X)*b5|s66;;vTT`|gbmKB0gwu98DZh{^Xwkxh^kYJSU+bcxr z(Y>=qiC%r&CBZ1mKU6g6At5zVAE`+&%CaIA4MycBm`9&(f*ummdg`MO2}W7ow{lmE zlD6w(R5w8n3F#{_c16E!v(Bc@D1C=ixhs3SG(kw8_pvJ!WGo@UD0{P2(V&Nfj6U@d zjs&CZ4P8Zp9uoE*Zvlc)vWBbP)i^Tdi;$sDC#aUnnE%+MG3PYZIMzOke7C(uqdEy* zE8bwG>$dN|=4y~&l&v_k9v61M63WxB31))?}|hjWa^UQMT5u5cJrZ`fs?ag2=1oiU#j0PKYgP z-ke(En!oH;Axe**DO=Ro`g#F^QMMYa5PWK}LSE#j6DmaUY}*xbx~p~#KlhoFU{qv~ z<`UBSa<*1H{w`z@-k!`Qq#QYqTN3sbs8SBzN$f=yHQjeb4~fW^&AlrUjEd~%T!J1F zkXA4=HHA~dWhWjPpCjQLUUbP}5$61KCbXpktPFqc3gY4EAVdxJ&( zPPn2`K3jipu&9wM<=pGsRzjkT^7n&tiFn&rURPRW&JNEd=*j&b@(koXVLf82L>A zN{AKGGym^l%RakKZGBaEK-k?@?urDXYy__mg(ugKM)68finKx=7akB+(-jR8jIyU$ zA?UGo^*7uV32W084c--_tfvJr%;g`BZLU?1%|2?&-R6CiwX2qhj9^|_c9$bm#VuIKM0R?&mD?nj!C_<|Aw!q<3N~=gM8t zLqghd-m%QpAi*db!7Cb!vb}*ubrXfB%|PWHQgK)9Gba)Gt9C6~xhu93whUWk2GMHR z-bp>S3(HZR?TXheh&y2aa}tcQ zbyuYvrN_^Eg-m%WrU@bB#-rde6=!tj2YkOBD z;(hd74c--_;@$mRf~}gf410k-!M0t|LxS4nGbd3-`8y=Lt5zf4RF(D9U5@w_om|U* z2f3(`w$QaM@pAxWRAgA^)>WzQrye9~PC2ajveKs~2)UBaC1qWaV3a(~`usspZY4eg zP&-u0yCNYiv{=1X%TY!}9fpGJ4fs4rNMG@lY&TIx#nV(`n7QFN-q$VilV>`vOs%(V zQ{P9iHAMbn?iYA`C^-7IRliPGcmaZ+BqeQz}Pu1GK{-c!xJE4GGsSD1Dz`J}AY zbZ$}Ju6W&eo3*Iv)}V((yknbN4ib!tw}5lYK@W*|3piJU1f$|@=3EVWNW>e=xf&!G z#hNZ_mmU)F?so27kzmxs6KwkjJyMSRdy_>C+d_F)^pMCkU0acnV3a)n`ihJmX=A=3 zrG|OdK z4+$H)D&-)-C>vcXMCtM0f8<#$tt=NH6l(S#b z?DeAu?WxUqg2P0TYFqr^y+Vy*mD?VyU9w)t*16pa_i@6morh6eK=-c zlbIpjLC<;S2DNpiEu$p-RCz~TSzBTh$9&!uTcTwtw6wCmjyvok7*)=wi5O;TIA&Xt z*&ywNRHM6H(L=)4*Gk7d$#_MgjPl>tPu3MZ{;S_bdLAZ${Uq?UImLt?SKbT#HfVY!~-69B=-; zzcw%W%obY0&A0ERuTlKH+Ln2#l$;(C8*aZ&I^*?_1qeo+^W$}v?S932K@9Vq4aXc4 zPkPf{jYpNE9m_!viF;S}>)1_?%S9b9Vkdhw*Tc=vDH6>|AxgOOQH zGjys>V!J#4(5|&3UY-XDMzJ@S1U)2ry+6w{uaukwqd3Nt8a943()uh)?K0OJOezQ7 zK@>#3t4s?p%+zpf^Q(DuK3BVJp*dRq|J=441hpf6g1{Yeg;NrRry#T~L^%u_jvuxE zy32fxYa?flD(Fxt>xzVp!4(abkWqY2p^)2^wg$bHwUWQ#u1HurUf{0EsII!=%wqMX z>*%tDMoG$3VI+FPb!qEaD25fQEPPV zT003FkK=g^vr^eV%BZzjA(OC~Iy9^>GG4{C7*+1{-u}dwJnw6N(r>Y*yYn$ozLMm2 zduC#dj4{35y2q^C zFXAt44Cx7b?n!bGy@+bRxTp6X=fy?i(D+LmLwdrN(()uZh+ag=wHW2L{QFPSSGj+k z|I$XPU3%PZ&lFkhf=Ex&quOt&X;hpx77hH}j3GT?&pq)Aq8Cw%i*vztYQdghDnmcr zS!z?gAw6L)YIv@<*8|ausKrH85K@lx?dX20Vfothke;v?`Ikeju0Zr6s{OvGM#V{B z(U7m!rmnExw$;_x>Z(Ui*o&Gn6DHpzuMvz2TQuZ*;r7gX z^n|^rVJ57bU{u(mA^p$VZjYX@=jN}v2P6Y z4eNt_DF;1aFUC7zc^+Ma^+DALTQsZ>ss=q_FUI?G(dZ(q52{AkqG5edHRuUjuB*Mv z>Z*$8>$R#8QR4Ba#olX8ql>UUs8M0dm8{pQ20dXf#z_t-Qx{=b=_Xn@JxEImwIjAdu>E5E~0GKw!5-5wLK4> z1aiAwEhj?m%GT6<85wMaY@Q%&RcjiyrdACSj0)SHp#1eZCFlveT`ikNdV*EL*1j4Q zwrHewHI@3hYS0t5)U>W@O{0q_qnr?p)IVfRZM92}+wE%EG`a{|`)X9!qLKQ!{PjB3 zpeO8hwQL$)gspuwDs0h^GRU3D2uDxY?P}RHx(HkQYE;;wA;!i9R0+AO$G!jkQ}>3Qv^~jW=(wbN}D0N0A6St@?_u z{F9)kPKbt-LGDaiB8jjUHFm1po;eA6>V#;>vyd7V4H985YV2IEX^^0&PKd@gQ=2*~ zwJp&g5jKAzEzg{UoeNg=Iw2a;H>Aaj28pmG%72k98YJkc6VQ;qYBeMgcKdrQt1Ht` zLarNM!1FsHAsW*EQm>j34H9AJ=h1$NuOOs;+*2n+!=9jOkOV#<62&Wn(!seGSFeWM?<6!$e)b>tDh{ogc*gio7&F^!F1_>F@{adVcLNsi~ zQ4JDdrzo9${4cnWpr=ll#to@giAHK!@;8I*TCJVGgyDCqchwU1E3@1?tAuEzv1%rb zK&n9^Y<|~3>WYN@_Ek0NglME^K9hQtYLEy!MYX>ywrAcF^wbH_NG)-kdR49~UaPg! z=+pk*Su{u#o+=?4X$~BxnN2lFgq_B#_IKN&L4uw-AsSK!xifj>B*I?Q*spVK+$BLz zoe&Lq7V=C)gGAWrL{j@3cPR%6dg_E|q_KURdX;LB2%EpD7Y!2jOGYhWoe&M_8>v^x zjMF0#wnX{20YrlYJ#_*aI@gj2yZs%cJrC1RLav+73yQkm2?^1V{^x535@F}(kx%c* zl}JeaxTj8thCRV4sVfp;d%N;)d6US`IeY4aXjn_^iw23XbN|R^2c;Y&q`kVQPKZXD z)!M(wN+Rss&+`c}(I6rH&OLQPG;Czha*zl+MWs=~zrI)!^wbH_urX0JNQB+~Hr(13 z2^k05ok@EqBt*kTYSkbSHov4KbwxtP^Ym*MRj(7GA^k74c-0^gc8b#3$N!=Z33}>; zY0TLV+Sjr3tky^##%9rEOF3+=)w?P@RYEju1u#Jb-L5iBgM_UU)Ke!!BR#=lKbTfB zN(7yv@~Xx(NYGO!L?gA`Vn67AV}iU6Ba8UGJI(30r@v zr%s4Q8X1cHVE$!D%2VQZyS7?34HER!3DHO++?@Sj{<|VUxBCy%AYuCf_0$Q`usx2B zyClMHcSWW_!uB=lsS~0h{ZCrFjJqVlmZA9Nz<{5;ZZXLUtF>c>5GLNx3Nss@R$eLv`5q$QD`bN18;(Xf^{ zmU55?yUmwaIY>x*&A%pH>=};~MM5+z!=f4_!p^-m|7KL42MOtS?x_=^VIzZTkO(_P zrBNcjHA#Y=Iw2Z1!l?#{u-iPG)fEXD2lKC#QwiHUAt4%%o3kHuBIq`sXc{DBJkP)S z%zqIf(~@u5 z8YFC;pq@G*8tDnPyE_tLr>MNDF%1&*)Cti@EwR`Swr#Y%Zo5u24HC9)%bqGB8n&{O zXWkHbav}^5xpr=lVhK+ElK_cun4`V#>;eo+5ft6wWltH-%_dFD3PYVDSu8ew%c zC96wmyClNSzw>HqU23-_?3Zj>S9L-((i3d=gCxS1DE}?Gl!F94bwX%ck>z$(T+6SU zo_YJ5deIhYQ1U+>^G;D>e8YIGAl>Y9S{GQjx zD-!h73DK~XzK)3`!d{eq>+D}ekaCcqr%s3lcXuShPW`<7!iH#&pr=lV2KR#`!j`D` zet${OQzxLIyE_tL=W_TQ+-fKx*A0)~2?^2Q?v6y*`FZ%RuOy^?+*2n+!=9k5ONJ!E z_I6d<59a5bJ#|7ftR;>`gGAW5fB4$2B&5B%r%s55Wmr^$MA*5X`>wAfq~E!xPKbt$ z45~pQY>D!((O@i5f}T1dw2g2RM9}T;YhxaiQB(;T2Yq)}Cq%Ioufe(OidK|;oJ z-w)Oa(ctcmMA#A~v(GcE93<$e6QPKbuBsa1nS*o)HN{@5)=`glcxo;o2K(wn4) zr5q%}UX*&7e^*V)L4uw-AsXD>kqA3waoVrFi3SOJ>V#-;KS&~MiSn<@i3SOJ>I5`w zKgesjoy!rsKGRS_t{a{jAsXD>kqA3K58w5bgw&6F>V#<66V$a2iLkw0`TB}Pe$Lrb zCq%VY6tmO`|1BPmK@_?(Rs0-L6YagM_UU)Ke!! zBR#=lKbTfBN(3!Y{+$si2MK!WgwVEzvv$R6x!tZ4tsEq5-DaK|AsV(8RSgnhx9eTI z5(!&>s;5qfhOMbpgGAWvy4^HL*g9H0bwV`K2-m(JBoTJI|1b>_wjWSWoe&M%oD-@=l1MS`9>0S)d4?SB2b?Y`Fj-89<$V44T# zAwfHc7JYHA|dtT=SAy;XxI}}4H98{yQ-ZR&CfY|>V#-mOB|!qMh4X&5w=A2@%QLS&{HRb zwh>M>NQB+y;jA1aWE@QMpn3dGNQee^cO=4YzmscMA|c~>ng`WWCq#q0I}%|_l+J^u zL4uw-VH$JxgI;pKZabfcMoZZIYMvS)8r^ILT9?MftU{i&Wh zAsT69Xx|T#2z!z32YtLEVe4qss1u@LD}5OgZ9kZ=6?D7*uyT;F{eXJvglO0vM>R-< z-R`4IgM{sC)Ke!!!**UW`Em67)GYt~-)Cp+l?v6y*?Y_3uP(rTjvvZvg4ciG% zc{!X2y4|0f1_`O3lowS`oe&Lsf~r9xY;RY!^P>4VXHT6F4Qq*gDF=zL+kA8guu9P6XX%2Tg;7jOTt{v`&ZycXuShmMGtaNnMekr%ni+mQ`c< z|M`FUn}AQ-|CWJ&ITUvL)uBm3c8wLH_!g4qMh^!fXFxT`hU=6Ch199F~h=)D_}?OY=w5Y$!8 z8&3Y$(hw*TpB``7-m9tlPrv20ay-SjziB1>plq8uf0ZF-`gGTOpLDwQRO z^koY~u}mdFPY@sc;^%RPBtGz#FE$50?j1{W39px0Fk7$Gv?Vu4?kb{AdGko>YC$5d zMZ)gNXx^25eNWZPD6Ns|U4^G4v=*uwL0Ii-ls%gY;a>~Pb)sKc)OPjGQ?8UcTs>J= zr6-7=?{`JB{Z%in5WQZsL_YuWO028Wqh->&@~?Eye^-nu%SVkzeP`Tkvg<4QdM)HbTaA_|JRr__{kS>pN8b%1OQat4qbFQ0 zm&XY&F`uBEhK5FS$YbN2L$aL&Cmo zSs58fFv`DF+1^!Ka<-D!o^?6e5}!Xy&Ka4+pZ5D~8nyqa+Rx)!jPkGSws+Om6+I;Q zWaFNsC6Zv2e~WiggB}tSt)#sx&MY>zTWL8H#eKEyO2?>@(0Qd=SG-n4SsT+Ug@Tm4 z^aNq;t)jsZ&c=`2Q#p1)B$Wdm5*uDJBhP&4WbKk*lz%yLlAwn~*{0*R;)|qmEk^mb zMq7W|Gt5E{41nlv-Q~J z^*_TgJtX{lrjr^Z7{$9SHRvJXUs;{hAi*fsLaD))=wH^A>#~iN1U)3IKUPLj5{$Aw zUnA^m^?E1v75lZnEB_{SuAlrx>ujfz40CDPv1Ik!sP3`7^u%>-{ZJ_f2}YIkO4M(B z<2T<`{sOz$e6kTQqiE>~!oTI-mfWzCU{u-DLS;DizP)1Qp#vW!#FqWe_kT9rA=@PA znMeBfM-$zN5@4_Yt?@{9MTF6mrb5|vi$CXJ9mcz#@iDHdJx#fBIs4r1I8?60Z zk?`4P{<~rnYoxp@yY5)7rWE)3|5QB?p^J&)}tgcf5fvT zVYOg%7r`jjNW{w%wDzjkvgiCa+*L{BUHD|lSq|T;OB8FQyenVhN|djb^L3*}lo)2N ztgE?%WQrELt7|n=BvGu9@~(Vrmna|Ys&{2rc~>Qo*VhZ(RYb8y%DeI%y)Oh*Z1ggTQoRd^?F@I85Qg6Uhls2 zUFYBU*Y|Qh(N^0rTb8qE7r`jEb2;pta9^G~J#I@m%2}<8V3gaYk=`PwJ5vpM+!hVa zqUqgs2f-+}vqpLr<5a`?Mv)%3MT2vDuh&H|%I&Pd?;+FUwrFtmQGRpTqvTqQayx6J zmOf4`UfoyRBT}e7goJm3Nm~$%2Ya`WULM-q}Q0%>7W`TuBi9Z%;(O(@JkB)%lk@kqkqG%S_ z9_bmzqa$F~PtTS%MbDPN_DBym9?!^~H~nMEu_>AbwnuvE@#qLxESF^xZUFj>$XPj{m#W^cw)*bT>pjpQD(Ac3?<+|#~ zt$5C4OL0WEqFG>joKa2Rbsmq7fK`s?%(4{ctdv9FH@Wt5vBS9RbUuXRwvX^Cjqc=RF?H0^1{BX&#S`faTG@0In}V zPfra?xtayG$9dAvsaJ;Qi(1nl~m9wQ!`qJOb~?U6olJf4v| zZ+gCXY>H-q?U9~(JURkaInsm2V^cH>Y>$jMuN@#cx;M{S7BLkd3^nK*NTk0 zQS0=UALpzTJ&C<;0M@P`Rs_65Xj3!`?5oOLbXrtLz{<;tfIT)vv%vP~lTSJVR$kT+ z?6E1D1-8e(XVm;Bt+pdzH-q?QzQR^IX|Hi5&qu zuiw2JZ;C!I6>N{^$tU-Fd|1lM+j@I!ie`cBk-6xUqa$GDWfj04o1$6Zl*1<+jYmho z&im(?m;RDHg{L*?Or#G5tBb98c>Hu5oLpIbF|Kl)y`0+V7>^G{u4-7|M_rAgBVgrC zy~QJS^`U4MIOV8QtvUkswa>FaITl5qMhmt_p2U>gxg5Fk<~feXrf3$}nbM-hqa$FI zBkeIBo1$4@d!%O=kB)%lk$xo}o1$4@d!&c^ThCQT!174{7>`ZSEU-P&Q;$bS!172x zpM9^JqFG>jWW<>_EFA&MgS|$^o8rm3_ZrQ)eQ&j@X@k9QAy|1?UA{cNDw+kp>WWhl zUmXD}FKf{DICb?^(Jb(F&pF-k)e*4rvTALQbI-pjngzCp#tyYA)m2Bp%FAlFJvK$N z!1g#TieHegj)2FbPK3Yy$vRgBOSxD-Z-qTh8QyADDhI6pEBbWk^EJFh@nqd=>DNh3 z;{nU=X6dR}OLtx6q^1u=v%t=jx#%c50#;tu= zN<212v%vO94>!L*Is%qQ`p0-|ie`cBk)C=yIs%qQ`uY5uV^cH>Y!A&U)ehA make_patch(;scale=1/1000,color=:mediumpurple4) + load(RB.assetpath("零件1 - 副本.STL")) |> RB.make_patch(;scale=1/1000,color=:mediumpurple4) else - load(RB.assetpath("零件1.STL")) |> make_patch(;scale=1/1000,color=:slategray4) + load(RB.assetpath("零件1.STL")) |> RB.make_patch(;scale=1/1000,color=:slategray4) end end body = RB.RigidBody(prop,state,coords,trimesh) diff --git a/examples/bodies/make_3d_tri.jl b/examples/bodies/make_3d_tri.jl index 6335306..cab66d4 100644 --- a/examples/bodies/make_3d_tri.jl +++ b/examples/bodies/make_3d_tri.jl @@ -92,7 +92,7 @@ if loadmesh else trimesh = GB.merge( [ - endpoints2mesh(loci_positions[i],loci_positions[j]; + RB.endpoints2mesh(loci_positions[i],loci_positions[j]; radius,color) for (i,j) in [ [1,2],[1,3],[1,4], diff --git a/yard/EWei/define.jl b/examples/robots/EWei.jl similarity index 81% rename from yard/EWei/define.jl rename to examples/robots/EWei.jl index a2832e7..c4acce8 100644 --- a/yard/EWei/define.jl +++ b/examples/robots/EWei.jl @@ -40,7 +40,7 @@ function BuildTail() function Get_apsAB(r̄, mass_locus) ri = r̄ rj = r̄ + 2* [mass_locus[2], mass_locus[1]] - aps = [[0.0, 0.0], 2r̄g, [15.1, 0.0]] + aps = [[0.0, 0.0], 2r̄, [15.1, 0.0]] return ri, rj, aps end @@ -161,7 +161,8 @@ function BuildTail() α = atan(u[2], u[1]) mass_locus = rdsi.mass_locus m = rdsi.m*1e-3 - I = rdsi.i + ## I = rdsi.i + @show m nrp = length(aps) ṙo = zeros(2); ω = 0.0 prop = RB.RigidBodyProperty( @@ -169,8 +170,8 @@ function BuildTail() contactable, m, SMatrix{2, 2}([ - I 0 - 0 0 + m 0 + 0 m ]), SVector{2}(mass_locus), [SVector{2}(aps[i]) for i in 1:nrp], @@ -178,34 +179,20 @@ function BuildTail() ) ro = SVector{2}(ri) if i in rigidIndex - nmcs = RB.NCF.NC2P1V(SVector{2}(ri), SVector{2}(rj), ro, α) + @show i, "NC2P1V", ri, rj + nmcs = RB.NCF.NC2P1V(SVector{2}(ri), SVector{2}(rj), ro, RB.rotation_matrix(α)) else - nmcs = RB.NCF.NC2D2P(SVector{2}(ri), SVector{2}(rj), ro, α) + @show i, "NC2D2P" + nmcs = RB.NCF.NC2D2P(SVector{2}(ri), SVector{2}(rj), ro, RB.rotation_matrix(α)) end - state = RB.RigidBodyState(prop, nmcs, ri, α, ṙo, ω, ci, cstr_idx) - body = RB.RigidBody(prop, state) + state = RB.RigidBodyState(prop, ri, α, ṙo, ω, ) + coords = RB.NonminimalCoordinates(nmcs, ci, cstr_idx) + body = RB.RigidBody(prop, state,coords) end rbs = [rigidbody(i, rds[i], r̄s[i]) for i in 1:nb] rigdibodies = TypeSortedCollection(rbs) - numbered = RB.number(rigdibodies) - matrix_sharing_raw = Vector{Matrix{Int}}() - for i in 1:nb-1 - s = zeros(2, nb) - if i == 1 - s[1:2, 1] = 3:4 - s[1:2, 2] = 1:2 - elseif i in 2:2:16 - s[1:2, i] = 1:2 - s[1:2, i+1] = 1:2 - else - s[1:2, i] = 3:4 - s[1:2, i+1] = 1:2 - end - push!(matrix_sharing_raw, s) - end - matrix_sharing = reduce(vcat, matrix_sharing_raw) - indexed = RB.index(rigdibodies, matrix_sharing) + nstrings = 8 * 4 + 8 * 2 ks = zeros(nstrings); restlens = zeros(nstrings) for i in 1:4*8 @@ -217,8 +204,7 @@ function BuildTail() restlens[i] = 25 ks[i] = 0.3 end - cables = [RB.DistanceSpringDamper2D( restlens[i], ks[i], 0.0) for i in 1:nstrings] - apparatuses = (cables=cables,) + spring_dampers = [RB.DistanceSpringDamper2D( restlens[i], ks[i], 0.0) for i in 1:nstrings] matrix_cnt_raw = Vector{Matrix{Int}}() s = zeros(4, nb) @@ -245,11 +231,45 @@ function BuildTail() s[2, i] = 2; s[2, i+1] = -2 push!(matrix_cnt_raw, s) end - matrix_cnt = reduce(vcat, matrix_cnt_raw) - tensiled = (connected=RB.connect(rigdibodies, matrix_cnt),) - cnt = RB.Connectivity(numbered, indexed, tensiled) + connecting_matrix = reduce(vcat, matrix_cnt_raw) + spring_dampers = RB.connect(rigdibodies, spring_dampers;connecting_matrix) + apparatuses = TypeSortedCollection( + spring_dampers + ) + + numbered = RB.number(rigdibodies, apparatuses) + + matrix_sharing_raw = Vector{Matrix{Int}}() + for i in 1:nb-1 + s = zeros(2, nb) + if i == 1 + s[1:2, 1] = 3:4 + s[1:2, 2] = 1:2 + elseif i in 2:2:16 + s[1:2, i] = 1:2 + s[1:2, i+1] = 1:2 + else + s[1:2, i] = 3:4 + s[1:2, i+1] = 1:2 + end + push!(matrix_sharing_raw, s) + end + sharing_matrix = reduce(vcat, matrix_sharing_raw) + indexed = RB.index(rigdibodies, apparatuses; sharing_matrix) + cnt = RB.Connectivity( + numbered, + indexed, + ) st = RB.Structure(rigdibodies, apparatuses, cnt) - bot = RB.Robot(st,) + gauges = Int[] + actuators = Int[] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + bot = RB.Robot(st,hub) end """ @@ -291,7 +311,7 @@ function BuildTail(type; β=1.0, μ=0.02) function Get_apsAB(r̄, mass_locus) ri = r̄ rj = r̄ + 2* [mass_locus[2], mass_locus[1]] - aps = [[0.0, 0.0], 2r̄g, [15.1, 0.0]] + aps = [[0.0, 0.0], 2r̄, [15.1, 0.0]] return ri, rj, aps end @@ -325,23 +345,23 @@ function BuildTail(type; β=1.0, μ=0.02) 4 => Get_apsC() end end - asbMid = load("STL/装配体-中间部分.STL") |> make_patch(;trans=[0.0,0,0],rot=RotZ(deg2rad(-77))) - crSec1 = load("STL/截面形状-1.STL") |> make_patch(;trans=[0.0,-5,0]) |> (x)->merge([x,asbMid]) - crSec2 = load("STL/截面形状-2.STL") |> make_patch(;trans=[0.0,-5,0]) |> (x)->merge([x,asbMid]) - crSec3 = load("STL/截面形状-3.STL") |> make_patch(;trans=[0.0,-5,0]) |> (x)->merge([x,asbMid]) - crSec4f = load("STL/截面形状-4-随动段.STL") |> make_patch(;trans=[40,0,0.],rot=RotZ(-π/2)) - crSec5f = load("STL/截面形状-5-随动段.STL") |> make_patch(;trans=[40,0,0.],rot=RotZ(-π/2)) - crSec6f = load("STL/截面形状-6-随动段.STL") |> make_patch(;trans=[30,0,0.],rot=RotZ(-π/2)) - crSec7f = load("STL/截面形状-7-随动段.STL") |> make_patch(;trans=[25,0,0.],rot=RotZ(-π/2)) - crSec8f = load("STL/截面形状-8-随动段.STL") |> make_patch(;trans=[25,0,0.],rot=RotZ(-π/2)) - crSec9f = load("STL/截面形状-9-随动段.STL") |> make_patch(;trans=[25,0,0.],rot=RotZ(-π/2)) - crSec10f = load("STL/截面形状-10-随动段.STL") |> make_patch(;trans=[30,0,0.],rot=RotZ(-π/2)) - - asbMot = load("STL/装配体-电机.STL") |> make_patch(;trans=[45.0,0,0],rot=RotZ(π)) - - asbB32 = load("STL/装配体-中间梁6.0-32.STL") |> make_patch(;trans=[25.0,0,0]) - asbB40 = load("STL/装配体-中间梁6.0-40.STL") |> make_patch(;trans=[25.0,0,0]) - asbLF = load("STL/装配体-主动-随动.STL") |> make_patch(;trans=[55,0,0.],rot=RotZ( π/2)) + asbMid = load(RB.assetpath("EWei_STL/装配体-中间部分.STL")) |> RB.make_patch(;trans=[0.0,0,0],rot=RotZ(deg2rad(-77))) + crSec1 = load(RB.assetpath("EWei_STL/截面形状-1.STL")) |> RB.make_patch(;trans=[0.0,-5,0]) |> (x)->merge([x,asbMid]) + crSec2 = load(RB.assetpath("EWei_STL/截面形状-2.STL")) |> RB.make_patch(;trans=[0.0,-5,0]) |> (x)->merge([x,asbMid]) + crSec3 = load(RB.assetpath("EWei_STL/截面形状-3.STL")) |> RB.make_patch(;trans=[0.0,-5,0]) |> (x)->merge([x,asbMid]) + crSec4f = load(RB.assetpath("EWei_STL/截面形状-4-随动段.STL")) |> RB.make_patch(;trans=[40,0,0.],rot=RotZ(-π/2)) + crSec5f = load(RB.assetpath("EWei_STL/截面形状-5-随动段.STL")) |> RB.make_patch(;trans=[40,0,0.],rot=RotZ(-π/2)) + crSec6f = load(RB.assetpath("EWei_STL/截面形状-6-随动段.STL")) |> RB.make_patch(;trans=[30,0,0.],rot=RotZ(-π/2)) + crSec7f = load(RB.assetpath("EWei_STL/截面形状-7-随动段.STL")) |> RB.make_patch(;trans=[25,0,0.],rot=RotZ(-π/2)) + crSec8f = load(RB.assetpath("EWei_STL/截面形状-8-随动段.STL")) |> RB.make_patch(;trans=[25,0,0.],rot=RotZ(-π/2)) + crSec9f = load(RB.assetpath("EWei_STL/截面形状-9-随动段.STL")) |> RB.make_patch(;trans=[25,0,0.],rot=RotZ(-π/2)) + crSec10f = load(RB.assetpath("EWei_STL/截面形状-10-随动段.STL")) |> RB.make_patch(;trans=[30,0,0.],rot=RotZ(-π/2)) + + asbMot = load(RB.assetpath("EWei_STL/装配体-电机.STL")) |> RB.make_patch(;trans=[45.0,0,0],rot=RotZ(π)) + + asbB32 = load(RB.assetpath("EWei_STL/装配体-中间梁6.0-32.STL")) |> RB.make_patch(;trans=[25.0,0,0]) + asbB40 = load(RB.assetpath("EWei_STL/装配体-中间梁6.0-40.STL")) |> RB.make_patch(;trans=[25.0,0,0]) + asbLF = load(RB.assetpath("EWei_STL/装配体-主动-随动.STL")) |> RB.make_patch(;trans=[55,0,0.],rot=RotZ( π/2)) rds = [ RigidData(r̄gC, mC, iC, r̄lC, asbMot), #1 @@ -447,34 +467,18 @@ function BuildTail(type; β=1.0, μ=0.02) ) ro = SVector{2}(ri) if i in rigidIndex - nmcs = RB.NCF.NC2P1V(SVector{2}(ri), SVector{2}(rj), ro, α) + nmcs = RB.NCF.NC2P1V(SVector{2}(ri), SVector{2}(rj), ro, RB.rotation_matrix(α)) else - nmcs = RB.NCF.NC2D2P(SVector{2}(ri), SVector{2}(rj), ro, α) + nmcs = RB.NCF.NC2D2P(SVector{2}(ri), SVector{2}(rj), ro, RB.rotation_matrix(α)) end - state = RB.RigidBodyState(prop, nmcs, ri, α, ṙo, ω, ci, cstr_idx) - body = RB.RigidBody(prop, state, rdsi.mesh) + state = RB.RigidBodyState(prop, ri, α, ṙo, ω, ) + coords = RB.NonminimalCoordinates(nmcs, ci, cstr_idx) + body = RB.RigidBody(prop, state, coords, rdsi.mesh) end rbs = [rigidbody(i, rds[i], r̄s[i]) for i in 1:nb] rigdibodies = TypeSortedCollection(rbs) - numbered = RB.number(rigdibodies) - matrix_sharing_raw = Vector{Matrix{Int}}() - for i in 1:nb-1 - s = zeros(2, nb) - if i == 1 - s[1:2, 1] = 3:4 - s[1:2, 2] = 1:2 - elseif i in 2:2:16 - s[1:2, i] = 1:2 - s[1:2, i+1] = 1:2 - else - s[1:2, i] = 3:4 - s[1:2, i+1] = 1:2 - end - push!(matrix_sharing_raw, s) - end - matrix_sharing = reduce(vcat, matrix_sharing_raw) - indexed = RB.index(rigdibodies, matrix_sharing) + nstrings = 8 * 4 + 8 * 2 ks = zeros(nstrings); restlens = zeros(nstrings) for i in 1:4*8 @@ -486,7 +490,7 @@ function BuildTail(type; β=1.0, μ=0.02) restlens[i] = 25 ks[i] = 0.3 end - cables = [RB.DistanceSpringDamper2D( restlens[i], ks[i], 0.0) for i in 1:nstrings] + spring_dampers = [RB.DistanceSpringDamper2D( restlens[i], ks[i], 0.0) for i in 1:nstrings] @match type begin 1 => begin lens = [44.71, 50, 50] @@ -494,7 +498,7 @@ function BuildTail(type; β=1.0, μ=0.02) c_section = StructArray([RB.DistanceSpringDamperSegment(i, lens[i], 0.2, prestress=pre[i]) for i in 1:3]) cs1 = RB.ClusterDistanceSpringDampers(1, 2, deepcopy(c_section); μ=μ) cs2 = RB.ClusterDistanceSpringDampers(2, 2, deepcopy(c_section); μ=μ) - apparatuses = (cables=cables, clustercables=[cs1, cs2]) + apparatuses = (spring_dampers=spring_dampers, clustercables=[cs1, cs2]) s = zeros(Int, 2, nb) s[1, 1] = 3; s[1, 2] = 2; s[1, 4] = 2; s[1, 6] = 2 s[2, 1] = 2; s[2, 2] = 1; s[2, 4] = 1; s[2, 6] = 1 @@ -506,7 +510,7 @@ function BuildTail(type; β=1.0, μ=0.02) c_section = StructArray([RB.DistanceSpringDamperSegment(i, lens[i], 0.2, prestress=pre[i]) for i in 1:8]) cs1 = RB.ClusterDistanceSpringDampers(1, 7, deepcopy(c_section); μ=μ) cs2 = RB.ClusterDistanceSpringDampers(2, 7, deepcopy(c_section); μ=μ) - apparatuses = (cables=cables, clustercables=[cs1, cs2]) + apparatuses = (spring_dampers=spring_dampers, clustercables=[cs1, cs2]) s = zeros(Int, 2, nb) s[1, 1] = 3; s[2, 1] = 2 for i in 1:8 @@ -523,7 +527,7 @@ function BuildTail(type; β=1.0, μ=0.02) c_section2 = StructArray([RB.DistanceSpringDamperSegment(i, lens2[i], 0.2, prestress=pre2[i]) for i in 1:2]) cs1 = [RB.ClusterDistanceSpringDampers(i, 1, deepcopy(c_section1); μ=μ) for i in 1:2] cs2 = [RB.ClusterDistanceSpringDampers(i, 1, deepcopy(c_section2); μ=μ) for i in 3:8] - apparatuses = (cables=cables, clustercables=vcat(cs1, cs2)) + apparatuses = (spring_dampers=spring_dampers, clustercables=vcat(cs1, cs2)) s = zeros(Int, 8, nb) s[1, 1] = 3; s[1, 2] = 2; s[1, 4] = 2; s[2, 1] = 2; s[2, 2] = 1; s[2, 4] = 1; @@ -543,7 +547,7 @@ function BuildTail(type; β=1.0, μ=0.02) c_section2 = StructArray([RB.DistanceSpringDamperSegment(i, lens2[i], 0.2, prestress=pre2[i]) for i in 1:3]) cs1 = [RB.ClusterDistanceSpringDampers(i, 2, deepcopy(c_section1); μ=μ) for i in 1:2] cs2 = [RB.ClusterDistanceSpringDampers(i, 2, deepcopy(c_section2); μ=μ) for i in 3:6] - apparatuses = (cables=cables, clustercables=vcat(cs1, cs2)) + apparatuses = (spring_dampers=spring_dampers, clustercables=vcat(cs1, cs2)) s = zeros(Int, 6, nb) s[1, 1] = 3; s[1, 2] = 2; s[1, 4] = 2; s[1, 6] = 2 s[2, 1] = 2; s[2, 2] = 1; s[2, 4] = 1; s[2, 6] = 1 @@ -584,9 +588,42 @@ function BuildTail(type; β=1.0, μ=0.02) s[2, i] = 2; s[2, i+1] = -2 push!(matrix_cnt_raw, s) end - matrix_cnt = reduce(vcat, matrix_cnt_raw) - cc = RB.connect_and_cluster(rigdibodies, matrix_cnt, matrix_cnt2) - cnt = RB.Connectivity(numbered, indexed, cc) + connecting_matrix = reduce(vcat, matrix_cnt_raw) + + cc = RB.connect_and_cluster(rigdibodies, connecting_matrix, matrix_cnt2) + + matrix_sharing_raw = Vector{Matrix{Int}}() + for i in 1:nb-1 + s = zeros(2, nb) + if i == 1 + s[1:2, 1] = 3:4 + s[1:2, 2] = 1:2 + elseif i in 2:2:16 + s[1:2, i] = 1:2 + s[1:2, i+1] = 1:2 + else + s[1:2, i] = 3:4 + s[1:2, i+1] = 1:2 + end + push!(matrix_sharing_raw, s) + end + matrix_sharing = reduce(vcat, matrix_sharing_raw) + + numbered = RB.number(rigdibodies, apparatuses;) + indexed = RB.index(rigdibodies, apparatuses; matrix_sharing) + + cnt = RB.Connectivity(numbered, indexed) + st = RB.Structure(rigdibodies, apparatuses, cnt) - bot = RB.Robot(st,) + + gauges = Int[] + actuators = Int[] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + + bot = RB.Robot(st,hub) end diff --git a/examples/robots/Tbars.jl b/examples/robots/Tbars.jl index 92f063e..a1b8476 100644 --- a/examples/robots/Tbars.jl +++ b/examples/robots/Tbars.jl @@ -132,14 +132,6 @@ function Tbars(;θ = 0, coordsType = RB.NCF.NC) rbs = [base,slider1,slider2,bar] rigdibodies = TypeSortedCollection(rbs) - j1 = RB.PrismaticJoint(1,RB.Hen2Egg(RB.Signifier(base,5,1),RB.Signifier(slider1,1,1))) - j2 = RB.PrismaticJoint(2,RB.Hen2Egg(RB.Signifier(base,5,2),RB.Signifier(slider2,1,1))) - - j3 = RB.PinJoint(3,RB.Hen2Egg(RB.Signifier(bar,1,1),RB.Signifier(slider1,2,1))) - j4 = RB.PinJoint(4,RB.Hen2Egg(RB.Signifier(bar,2,1),RB.Signifier(slider2,2,1))) - - js = [j1,j2,j3,j4] - ncables = 4 original_restlens = zeros(ncables) original_restlens = zeros(ncables) @@ -148,7 +140,7 @@ function Tbars(;θ = 0, coordsType = RB.NCF.NC) cs = zeros(ncables) spring_dampers = [RB.DistanceSpringDamper3D(original_restlens[i],ks[i],cs[i];slack=false) for i = 1:ncables] - cm = [ + connecting_matrix = [ 1 -1 0 0; 2 -1 0 0; # 3 0 -1 0; @@ -157,10 +149,19 @@ function Tbars(;θ = 0, coordsType = RB.NCF.NC) 7 -1 0 0; ] - cables = RB.connect(rigdibodies, spring_dampers, cm, 4) + cables = RB.connect(rigdibodies, spring_dampers; connecting_matrix,) + + + j1 = RB.PrismaticJoint(ncables+1,RB.Hen2Egg(RB.Signifier(base,5,1),RB.Signifier(slider1,1,1))) + j2 = RB.PrismaticJoint(ncables+2,RB.Hen2Egg(RB.Signifier(base,5,2),RB.Signifier(slider2,1,1))) + + j3 = RB.PinJoint(ncables+3,RB.Hen2Egg(RB.Signifier(bar,1,1),RB.Signifier(slider1,2,1))) + j4 = RB.PinJoint(ncables+4,RB.Hen2Egg(RB.Signifier(bar,2,1),RB.Signifier(slider2,2,1))) + + js = [j1,j2,j3,j4] apparatuses = TypeSortedCollection( - vcat(js,cables) + vcat(cables,js) ) # sm = [ @@ -173,5 +174,14 @@ function Tbars(;θ = 0, coordsType = RB.NCF.NC) # ] # indexed = RB.index(rigdibodies,sm) st = RB.Structure(rigdibodies,apparatuses,) - RB.Robot(st,) + gauges = Int[] + actuators = Int[] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + + RB.Robot(st,hub) end \ No newline at end of file diff --git a/examples/robots/bai.jl b/examples/robots/bai.jl new file mode 100644 index 0000000..499f0b0 --- /dev/null +++ b/examples/robots/bai.jl @@ -0,0 +1,180 @@ + +# 定义一个函数来新建机器人 +function make_bai(meshes,质心,质量,惯量) + + nb = 6 + ver_lengths_raw = [ + # 0 43; + # 18 18; + 0 43+18+18-10; + 18 16; + 19.1 9; + 18 8; + 18 8; + 0 16.29; + 0 150 + ] + ver_lengths = sum(ver_lengths_raw,dims=2) + hor_lengths = [ + 32.61, + 26.21, + 20.64, + 14.71, + 13.24, + # 13.24, + 2.5 + ] + nhor = length(hor_lengths) + + θs = zeros(nhor+1) + for i = 2:nhor-1 + θs[i] = π/48*i + end + P = [ + zeros(2,) + for i = 1:nhor+1 + ] + for i = 2:nhor+1 + P[i] = P[i-1] + RB.rotation_matrix(θs[i])*[0.0,-ver_lengths[i-1]] + end + + function rigidbody(i,P) + if i == 1 + contactable = false + visible = true + ci = collect(1:6) + cstr_idx = Int[] + elseif i in [2,nb] + contactable = true + visible = true + ci = collect(1:2) + cstr_idx = collect(1:3) + else + contactable = true + visible = true + ci = Int[] + cstr_idx = collect(1:3) + end + α = -π/2 + θs[i] + if i == 1 + ri = SVector{2}(0.0, 0.0) + rj = SVector{2}(P[i+1] ) + elseif i < nb + ri = SVector{2}(P[i]) + rj = SVector{2}(P[i+1]) + else + ri = SVector{2}(0.0, 0.0) + rj = SVector{2}(0.0,-150.0) + end + b = hor_lengths[i] + offset_fix = begin + if i == 1 + ret = 43 + 10 + elseif i == nb + ret = 150 + else + ret = 0 + end + ret + end + offset = ver_lengths_raw[i,1] + ro = ri + SVector{2}(0.0,-offset) + mass_locus = SVector{2}(质心[i]) + m = 质量[i] + inertia = 惯量[i]/2 + Ī = SMatrix{2,2}([ + inertia 0 + 0 inertia + ]) + r̄p1 = SVector{2}(offset_fix,-b,) + r̄p2 = SVector{2}(offset_fix, b,) + r̄p3 = SVector{2}(-offset, 0.0) + r̄p4 = SVector{2}(norm(rj-ri)-offset, 0.0) + loci = [r̄p1,r̄p2,r̄p3,r̄p4] + nr̄p = length(loci) + ṙo = zeros(2); ω = 0.0 + prop = RB.RigidBodyProperty( + i, + contactable, + m, + Ī, + SVector{2}(mass_locus), + loci; + visible = visible, + ) + @show i, ri, rj + nmcs = RB.NCF.NC2P1V(ri, rj, ro, RB.rotation_matrix(α)) + state = RB.RigidBodyState(prop, ro, α, ṙo, ω, ) + coords = RB.NonminimalCoordinates(nmcs, ci, cstr_idx) + mesh_rigid = meshes[i] + body = RB.RigidBody(prop, state, coords, mesh_rigid) + end + rbs = [ + rigidbody(i, P) for i = 1:nb + ] + rigdibodies = TypeSortedCollection(rbs) + + ncables = 2(nb-1) + original_restlens = zeros(ncables) + ks = zeros(ncables) + for i = 1:ncables + original_restlens[i] = 22.0 + ks[i] = 1000.0 + end + spring_dampers = [RB.DistanceSpringDamper2D( original_restlens[i], ks[i], 0.0;slack=true) for i = 1:ncables] + + matrix_cnt_raw = Vector{Matrix{Int}}() + for i = 1:nb-2 + s = zeros(2, nb) + s[1, i ] = 1 + s[1, i+1] = -1 + s[2, i ] = 2 + s[2, i+1] = -2 + push!(matrix_cnt_raw, s) + end + connecting_matrix = reduce(vcat, matrix_cnt_raw) + # display(connecting_matrix) + cables = RB.connect(rigdibodies, spring_dampers; connecting_matrix) + apparatuses = TypeSortedCollection( + cables + ) + + numbered = RB.number(rigdibodies,apparatuses) + matrix_sharing_raw = Vector{Matrix{Int}}() + for i = 1:nb-2 + s = zeros(2, nb) + s[1:2, i] = 3:4 + s[1:2, i+1] = 1:2 + push!(matrix_sharing_raw, s) + end + s = zeros(2, nb) + s[1:2, 1] = 1:2 + s[1:2, nb] = 1:2 + push!(matrix_sharing_raw, s) + sharing_matrix = reduce(vcat, matrix_sharing_raw) + # display(sharing_matrix) + indexed = RB.index(rigdibodies, apparatuses; sharing_matrix) + + cnt = RB.Connectivity(numbered, indexed,) + + st = RB.Structure(rigdibodies, apparatuses, cnt) + + gauges = Int[] + actuators = Int[] + # + ## acs = [ + ## RB.RegisterActuator(1, + ## [1:2(nb-1)], + ## original_restlens, + ## ) + ## ] + + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + + bot = RB.Robot(st, hub) +end \ No newline at end of file diff --git a/examples/robots/cube.jl b/examples/robots/cube.jl new file mode 100644 index 0000000..92e8f62 --- /dev/null +++ b/examples/robots/cube.jl @@ -0,0 +1,65 @@ +function make_cube(origin_position = [0.0,0.0,0.5], + R = one(RotMatrix{3}), + origin_velocity = [2.0,0.0,0.0], + ω = [0.0,0.0,5.0]; + μ = 0.9, + e = 0.0 + ) + m = 1.0 + mass_locus = zeros(3) + inertia = SMatrix{3,3}(Matrix(1.0I,3,3)) + h = 5.0 + loci = [h.*[x,y,z] for z = [-1,1] for y = [-1,1] for x = [-1,1]] + axes = [SVector(1.0,0,0) for _ = 1:length(loci)] + friction_coefficients = [μ for _ = 1:length(loci)] + restitution_coefficients = [e for _ = 1:length(loci)] + pts = Point3.(loci) + fcs = GB.QuadFace.([ + [1,3,4,2], + [3,7,8,4], + [7,5,6,8], + [5,1,2,6], + [2,4,8,6], + [1,5,7,3] + ]) + nls = GB.normals(pts,fcs) + cube_mesh = GB.Mesh(GB.meta(pts,normals=nls),fcs) |> RB.make_patch(;color=:snow) + prop = RB.RigidBodyProperty( + 1,true,m,inertia, + mass_locus,loci,axes, + friction_coefficients,restitution_coefficients, + ) + ri = copy(origin_position) + state = RB.RigidBodyState(prop,origin_position,R,origin_velocity,ω) + + nmcs = RB.NCF.NC1P3V(ri,origin_position,R) + coords = RB.NonminimalCoordinates(nmcs,) + rb1 = RB.GravitationalRigidBody(prop,state,coords,cube_mesh) + rbs = TypeSortedCollection((rb1,)) + + apparatuses = Int[] + sharing_matrix = zeros(Int,0,0) + indexed = RB.index(rbs,apparatuses;sharing_matrix) + numbered = RB.number(rbs,apparatuses) + + cnt = RB.Connectivity(numbered,indexed,) + + st = RB.Structure(rbs,apparatuses,cnt,) + + gauges = Int[] + actuators = Int[] + ## actuators = [ + ## RB.RegisterActuator( + ## 1, + ## collect(1:ncables_prism), + ## zeros(ncables_prism) + ## ), + ## ] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + bot = RB.Robot(st,hub) +end \ No newline at end of file diff --git a/examples/robots/pointmass.jl b/examples/robots/pointmass.jl index 1606140..7255608 100644 --- a/examples/robots/pointmass.jl +++ b/examples/robots/pointmass.jl @@ -36,5 +36,22 @@ function new_pointmass(; numbered = RB.number(rbs,apparatuses) cnt = RB.Connectivity(indexed,numbered,) st = RB.Structure(rbs,apparatuses,cnt,) - bot = RB.Robot(st) + + + gauges = Int[] + actuators = Int[] + ## actuators = [ + ## RB.RegisterActuator( + ## 1, + ## collect(1:ncables_prism), + ## zeros(ncables_prism) + ## ), + ## ] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + bot = RB.Robot(st,hub) end diff --git a/examples/robots/prism.jl b/examples/robots/prism.jl index 38c7769..9d0488f 100644 --- a/examples/robots/prism.jl +++ b/examples/robots/prism.jl @@ -1,266 +1,276 @@ function prisms(; - κ = nothing, - r = 1.0, - r1 = 1.0, - b = 2.0, - m = 4, - α = 2π/m, - h = nothing, - n = 1, - θ = 1.25α, - hasplate = true, -) -if h isa Nothing - @assert θ>α - c = sqrt( - r^2 + r1^2 -2*r*r1*cos(θ) + κ = nothing, + r = 1.0, + r1 = 1.0, + b = 2.0, + m = 4, + α = 2π/m, + h = nothing, + n = 1, + θ = 1.25α, + hasplate = true, ) - h² = b^2-c^2 - @assert h² > 0 - h = sqrt(h²) -end -@show r,r1 -d, l = divrem(n,2) -@show θ |> rad2deg -bps = [ - begin - if j |> iseven - ps = [ - [r*cos(i*α),r*sin(i*α),j*h] - for i = 1:m - ] - else - ps = [ - [r1*cos(i*α+θ),r1*sin(i*α+θ),j*h] - for i = 1:m - ] - end - ps .|> SVector{3} |> CircularArray + if h isa Nothing + @assert θ>α + c = sqrt( + r^2 + r1^2 -2*r*r1*cos(θ) + ) + h² = b^2-c^2 + @assert h² > 0 + h = sqrt(h²) end - for j = 0:n -] -# fig = Figure() -# ax = Axis3(fig[1,1]) -# scatter!(ax,reduce(vcat,bps)) -# scatter!(ax,reduce(vcat,midps)) -# fig -# @myshow length(bps), length(midps) -bars = [ - begin - if j |> iseven - [ - make_3d_bar( - m*(j-1)+i, - bps[j][i], - bps[j+1][i]; - #ci = ifelse(j==1,[1,2,3],Int[]), - radius_ratio = 1/60, - ) for i = 1:m - ] - else - [ - make_3d_bar( - m*(j-1)+i, - bps[j][i-1], - bps[j+1][i-1]; - radius_ratio = 1/60, - ) for i = 1:m - ] + @show r,r1 + d, l = divrem(n,2) + @show θ |> rad2deg + bps = [ + begin + if j |> iseven + ps = [ + [r*cos(i*α),r*sin(i*α),j*h] + for i = 1:m + ] + else + ps = [ + [r1*cos(i*α+θ),r1*sin(i*α+θ),j*h] + for i = 1:m + ] + end + ps .|> SVector{3} |> CircularArray end - end - for j = 1:n -] + for j = 0:n + ] + # fig = Figure() + # ax = Axis3(fig[1,1]) + # scatter!(ax,reduce(vcat,bps)) + # scatter!(ax,reduce(vcat,midps)) + # fig + # @myshow length(bps), length(midps) + bars = [ + begin + if j |> iseven + [ + make_3d_bar( + m*(j-1)+i, + bps[j][i], + bps[j+1][i]; + #ci = ifelse(j==1,[1,2,3],Int[]), + radius_ratio = 1/60, + ) for i = 1:m + ] + else + [ + make_3d_bar( + m*(j-1)+i, + bps[j][i-1], + bps[j+1][i-1]; + radius_ratio = 1/60, + ) for i = 1:m + ] + end + end + for j = 1:n + ] -nbars = length.(bars) |> sum -nb = nbars + 1 + nbars = length.(bars) |> sum + nb = nbars + 1 -ro = SVector(0.0,0.0,0.0) -nodes_raw = bps[1] |> Array -loci = vcat(nodes_raw,) -# nodes_ext = [ -# SVector(3r̄p[1],3r̄p[2],0.0) -# for r̄p in nodes_raw -# ] -# loci = vcat(nodes_raw,nodes_ext) -if hasplate - plate = make_3d_plate( - nb, - loci, - ro, - RotZ(0.0), - ro; - radius=r, - contactable = true, - m=3, - height=1e-2, - ci = collect(1:12), - cstr_idx = Int[], - loadmesh = false, - meshvisible = true, - ) - rbs = vcat( - reduce(vcat,bars), - plate - ) |> TypeSortedCollection -else - rbs = vcat( - reduce(vcat,bars), - ) |> TypeSortedCollection -end -numbered = RB.number(rbs) -cm = CircularArray(collect(1:m)) -# sharing_elas = ElasticArray{Int}(undef, nb, 0) -# for j = 1:n -# is = 2m*(j-1) -# for i = 1:m -# for k = 1:p -# row = zeros(Int,nb) -# row[is+cm[i] ] = k+3 -# row[is+m+cm[i+1]] = k -# append!(sharing_elas,row) -# end -# end -# end -# for j = 2:n -# is = 2m*(j-2)+m -# for i = 1:m -# for k = 1:p -# row = zeros(Int,nb) -# row[is+cm[i] ] = k+3 -# row[is+m+cm[i+2]] = k -# append!(sharing_elas,row) -# end -# end -# end -# sharing = Matrix(sharing_elas') -# display(sharing) -# indexed = RB.index(rbs,sharing) -indexed = RB.index(rbs,) - -@myshow nb -connecting_elas = ElasticArray{Int}(undef, nb, 0) -for j = 0:n-1 - is = m*j - - # # lower - # for i = 1:m - # row = zeros(Int,nb) - # row[is+cm[i ]] = 1 - # row[is+cm[i+1]] = -1 - # append!(connecting_elas,row) + ro = SVector(0.0,0.0,0.0) + nodes_raw = bps[1] |> Array + loci = vcat(nodes_raw,) + # nodes_ext = [ + # SVector(3r̄p[1],3r̄p[2],0.0) + # for r̄p in nodes_raw + # ] + # loci = vcat(nodes_raw,nodes_ext) + if hasplate + plate = make_3d_plate( + nb, + loci, + ro, + RotZ(0.0), + ro; + radius=r, + contactable = true, + m=3, + height=1e-2, + ci = collect(1:12), + cstr_idx = Int[], + loadmesh = false, + meshvisible = true, + ) + rbs = vcat( + reduce(vcat,bars), + plate + ) |> TypeSortedCollection + else + rbs = vcat( + reduce(vcat,bars), + ) |> TypeSortedCollection + end + numbered = RB.number(rbs) + cm = CircularArray(collect(1:m)) + # sharing_elas = ElasticArray{Int}(undef, nb, 0) + # for j = 1:n + # is = 2m*(j-1) + # for i = 1:m + # for k = 1:p + # row = zeros(Int,nb) + # row[is+cm[i] ] = k+3 + # row[is+m+cm[i+1]] = k + # append!(sharing_elas,row) + # end + # end + # end + # for j = 2:n + # is = 2m*(j-2)+m + # for i = 1:m + # for k = 1:p + # row = zeros(Int,nb) + # row[is+cm[i] ] = k+3 + # row[is+m+cm[i+2]] = k + # append!(sharing_elas,row) + # end + # end # end - - # cross - if j |> iseven - for i = 1:m - row = zeros(Int,nb) - row[is+cm[i ]] = 1 - row[is+cm[i-1]] = -2 - append!(connecting_elas,row) - end - # additional cross + # sharing = Matrix(sharing_elas') + # display(sharing) + # indexed = RB.index(rbs,sharing) + indexed = RB.index(rbs,) + + @myshow nb + connecting_elas = ElasticArray{Int}(undef, nb, 0) + for j = 0:n-1 + is = m*j + + # # lower # for i = 1:m - # row = zeros(Int,nb) - # row[is+cm[i ]] = 1 - # row[is+cm[i-2]] = -2 - # append!(connecting_elas,row) + # row = zeros(Int,nb) + # row[is+cm[i ]] = 1 + # row[is+cm[i+1]] = -1 + # append!(connecting_elas,row) # end - else + + # cross + if j |> iseven + for i = 1:m + row = zeros(Int,nb) + row[is+cm[i ]] = 1 + row[is+cm[i-1]] = -2 + append!(connecting_elas,row) + end + # additional cross + # for i = 1:m + # row = zeros(Int,nb) + # row[is+cm[i ]] = 1 + # row[is+cm[i-2]] = -2 + # append!(connecting_elas,row) + # end + else + for i = 1:m + row = zeros(Int,nb) + row[is+cm[i+1]] = -2 + row[is+cm[i ]] = 1 + append!(connecting_elas,row) + end + # addtional cross + # for i = 1:m + # row = zeros(Int,nb) + # row[is+cm[i+1]] = -2 + # row[is+m+cm[i+1]] = 2 + # append!(connecting_elas,row) + # end + end + + # upper for i = 1:m row = zeros(Int,nb) + row[is+cm[i ]] = 2 row[is+cm[i+1]] = -2 - row[is+cm[i ]] = 1 append!(connecting_elas,row) end - # addtional cross - # for i = 1:m - # row = zeros(Int,nb) - # row[is+cm[i+1]] = -2 - # row[is+m+cm[i+1]] = 2 - # append!(connecting_elas,row) - # end end + ncables_prism = size(connecting_elas,2) + connecting_matrix = Matrix(connecting_elas') + ncables = size(connecting_matrix,1) + # @assert ncables == ncables_prism + ncables_outer + @show ncables + mat_cable = filter( + row->row.name == "Nylon 66", + RB.material_properties + )[1] + diameter = 1e-3Unitful.m + cable_length = 0.1Unitful.m + κ = (mat_cable.modulus_elas)*π*(diameter/2)^2/cable_length + # @show κ + @show uconvert(Unitful.N/Unitful.m,κ),ustrip(Unitful.N/Unitful.m,κ) + spring_dampers = [RB.DistanceSpringDamper3D(0.0, ustrip(Unitful.N/Unitful.m,κ),0.0;slack=true) for i = 1:ncables_prism] - # upper - for i = 1:m - row = zeros(Int,nb) - row[is+cm[i ]] = 2 - row[is+cm[i+1]] = -2 - append!(connecting_elas,row) - end -end -ncables_prism = size(connecting_elas,2) -connecting = Matrix(connecting_elas') -# display(connecting) -connected = RB.connect(rbs,connecting) - -ncables = size(connecting,1) -# @assert ncables == ncables_prism + ncables_outer -@show ncables -mat_cable = filter( - row->row.name == "Nylon 66", - material_properties -)[1] -diameter = 1e-3Unitful.m -cable_length = 0.1Unitful.m -κ = (mat_cable.modulus_elas)*π*(diameter/2)^2/cable_length -# @show κ -@show uconvert(Unitful.N/Unitful.m,κ),ustrip(Unitful.N/Unitful.m,κ) -cables_prism = [RB.DistanceSpringDamper3D(0.0, ustrip(Unitful.N/Unitful.m,κ),0.0;slack=true) for i = 1:ncables_prism] -cables = cables_prism -acs = [ - RB.RegisterActuator( - 1, - collect(1:ncables_prism), - zeros(ncables_prism) - ), -] -apparatuses = (cables = cables,) -hub = (actuators = acs,) + # display(connecting_matrix) + cables = RB.connect(rbs,spring_dampers;connecting_matrix,) + csts_bar2bar = [ + begin + hen = bars[j+1][cm[i+2]] + @show hen.prop.id + egg = bars[j][cm[i]] + @show egg.prop.id + RB.PinJoint( + ncables+i+m*(j-1), + RB.Hen2Egg( + RB.Signifier(hen,1,1), + RB.Signifier(egg,2,1) + ) + ) + end + for j = 1:d for i = 1:m + ] -csts_bar2bar = [ - begin - hen = bars[j+1][cm[i+2]] - @show hen.prop.id - egg = bars[j][cm[i]] - @show egg.prop.id - RB.PinJoint( - i+m*(j-1), - RB.Hen2Egg( - i+m*(j-1), - RB.Signifier(hen,1,1), - RB.Signifier(egg,2,1) + if hasplate + csts_bar2plate = [ + RB.PinJoint( + ncables+m*d+i, + RB.Hen2Egg( + RB.Signifier(plate,i,1), + RB.Signifier(bars[1][cm[i]],1,1), + ) ) + for i = 1:m + ] + csts = vcat( + csts_bar2plate, + csts_bar2bar, ) + else + csts = csts_bar2bar end - for j = 1:d for i = 1:m -] -if hasplate - csts_bar2plate = [ - RB.PinJoint( - m*d+i, - RB.Hen2Egg( - m*d+i, - RB.Signifier(plate,i,1), - RB.Signifier(bars[1][cm[i]],1,1), - ) - ) - for i = 1:m - ] - csts = vcat( - csts_bar2plate, - csts_bar2bar, + apparatuses = TypeSortedCollection( + vcat(cables,csts) ) -else - csts = csts_bar2bar -end -jointedmembers = RB.join(csts,indexed) + indexed = RB.index(rbs, apparatuses) + numbered = RB.number(rbs, apparatuses) + cnt = RB.Connectivity( + numbered, + indexed, + ) + st = RB.Structure(rbs,apparatuses,cnt) -cnt = RB.Connectivity(numbered,indexed,@eponymtuple(connected,),jointedmembers) + gauges = Int[] + actuators = Int[] + ## actuators = [ + ## RB.RegisterActuator( + ## 1, + ## collect(1:ncables_prism), + ## zeros(ncables_prism) + ## ), + ## ] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) -st = RB.Structure(rbs,apparatuses,cnt) -bot = RB.Robot(st,hub) + bot = RB.Robot(st,hub) end \ No newline at end of file diff --git a/examples/robots/superball.jl b/examples/robots/superball.jl index 235f509..e198da9 100644 --- a/examples/robots/superball.jl +++ b/examples/robots/superball.jl @@ -10,7 +10,8 @@ function superball(c=0.0; l = 1.7/2, d = l/2, k = 4000.0, - constrained = true, + visible = true, + constrained = false, loadmesh = true, ) @@ -40,7 +41,7 @@ function superball(c=0.0; m = 5.0, μ, e, - visible = ifelse(i==1 && constrained,true,false), + visible, ci = ifelse(i==1 && constrained,collect(1:6),Int[]), cstr_idx = ifelse(i==1 && constrained,Int[],[1]), loadmesh, @@ -81,19 +82,19 @@ function superball(c=0.0; [5,6] ] ) - matrix_cnt = zeros(Int,ncables,6) + connecting_matrix = zeros(Int,ncables,6) for lev = 1:3 - matrix_cnt[8(lev-1)+1, [nb[lev][1],nb[lev+1][1]]] = [1, -1] - matrix_cnt[8(lev-1)+2, [nb[lev][1],nb[lev+1][1]]] = [2, -1] - matrix_cnt[8(lev-1)+3, [nb[lev][1],nb[lev+1][2]]] = [1, -2] - matrix_cnt[8(lev-1)+4, [nb[lev][1],nb[lev+1][2]]] = [2, -2] - matrix_cnt[8(lev-1)+5, [nb[lev][2],nb[lev+1][2]]] = [1, -1] - matrix_cnt[8(lev-1)+6, [nb[lev][2],nb[lev+1][2]]] = [2, -1] - matrix_cnt[8(lev-1)+7, [nb[lev][2],nb[lev+1][1]]] = [1, -2] - matrix_cnt[8(lev-1)+8, [nb[lev][2],nb[lev+1][1]]] = [2, -2] + connecting_matrix[8(lev-1)+1, [nb[lev][1],nb[lev+1][1]]] = [1, -1] + connecting_matrix[8(lev-1)+2, [nb[lev][1],nb[lev+1][1]]] = [2, -1] + connecting_matrix[8(lev-1)+3, [nb[lev][1],nb[lev+1][2]]] = [1, -2] + connecting_matrix[8(lev-1)+4, [nb[lev][1],nb[lev+1][2]]] = [2, -2] + connecting_matrix[8(lev-1)+5, [nb[lev][2],nb[lev+1][2]]] = [1, -1] + connecting_matrix[8(lev-1)+6, [nb[lev][2],nb[lev+1][2]]] = [2, -1] + connecting_matrix[8(lev-1)+7, [nb[lev][2],nb[lev+1][1]]] = [1, -2] + connecting_matrix[8(lev-1)+8, [nb[lev][2],nb[lev+1][1]]] = [2, -2] end - # display(matrix_cnt) - cables = RB.connect(rigdibodies, spring_dampers, matrix_cnt, 0) + # display(connecting_matrix) + cables = RB.connect(rigdibodies, spring_dampers; connecting_matrix, istart=0) apparatuses = TypeSortedCollection( cables @@ -106,7 +107,14 @@ function superball(c=0.0; numbered, indexed, ) - st = RB.Structure(rigdibodies, apparatuses, cnt, ) - bot = RB.Robot(st,) + gauges = Int[] + actuators = Int[] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + bot = RB.Robot(st,hub) end \ No newline at end of file diff --git a/examples/robots/tower.jl b/examples/robots/tower.jl index 0abe091..30a39b4 100644 --- a/examples/robots/tower.jl +++ b/examples/robots/tower.jl @@ -98,43 +98,49 @@ function tower(;k=nothing) end display(cnt_matrix_elas) - cnt_matrix = Matrix(cnt_matrix_elas') - ncables = size(cnt_matrix,1) + connecting_matrix = Matrix(cnt_matrix_elas') + ncables = size(connecting_matrix,1) if k isa Nothing - cables = [RB.DistanceSpringDamper3D(0.0,100.0,0.0;slack=false) for i = 1:ncables] + spring_dampers = [RB.DistanceSpringDamper3D(0.0,100.0,0.0;slack=false) for i = 1:ncables] else - cables = [RB.DistanceSpringDamper3D(0.0,k[i],0.0;slack=false) for i = 1:ncables] + spring_dampers = [RB.DistanceSpringDamper3D(0.0,k[i],0.0;slack=false) for i = 1:ncables] end - apparatuses = (cables = cables,) - connected = RB.connect(rbs,cnt_matrix) + cables = RB.connect(rbs,spring_dampers;connecting_matrix) cst1 = RB.PinJoint( - 1, + ncables+1, RB.Hen2Egg( - 1, RB.Signifier(base,1), RB.Signifier(bar,1), ) ) cst2 = RB.PinJoint( - 2, + ncables+2, RB.Hen2Egg( - 2, RB.Signifier(bar,2), RB.Signifier(top,1) ) ) - jointedmembers = RB.join((cst1,cst2,),indexed) + apparatuses = TypeSortedCollection( + vcat(cables,cst1,cst2) + ) + indexed = RB.index(rbs, apparatuses) + numbered = RB.number(rbs, apparatuses) cnt = RB.Connectivity( - numbered, - indexed, - @eponymtuple(connected,), - jointedmembers - ) - + numbered, + indexed, + ) st = RB.Structure(rbs,apparatuses,cnt) - bot = RB.Robot(st,) + gauges = Int[] + actuators = Int[] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) + bot = RB.Robot(st,hub) end \ No newline at end of file diff --git a/examples/robots/two_tri.jl b/examples/robots/two_tri.jl index 97098b9..6f4e3cb 100644 --- a/examples/robots/two_tri.jl +++ b/examples/robots/two_tri.jl @@ -15,23 +15,15 @@ function two_tri(;k=100.0,c=0.0,ratio=0.8) ) rbs = TypeSortedCollection((rb1,rb2)) - numbered = RB.number(rbs) - matrix_sharing = [ - 1 1; - 2 2; - ] - indexed = RB.index(rbs,matrix_sharing) # ncables = 4 restlen1 = 0.05 restlens = fill(restlen1,ncables) ks = fill(k,ncables) cs = fill(c,ncables) - cables = [RB.DistanceSpringDamper2D(restlens[i],ks[i],cs[i];slack=true) for i = 1:ncables] - acs = [RB.RegisterActuator(1,1:ncables,restlens,RB.Uncoupled())] - apparatuses = (cables = cables,) - hub = (actuators = acs,) - cnt_matrix_cables = [ + spring_dampers = [RB.DistanceSpringDamper2D(restlens[i],ks[i],cs[i];slack=true) for i = 1:ncables] + + connecting_matrix = [ 3 -2 ; -2 3 ; 5 -2 ; @@ -39,7 +31,7 @@ function two_tri(;k=100.0,c=0.0,ratio=0.8) # 5 -2 ; # 4 -3 ; ] - connected = RB.connect(rbs,cnt_matrix_cables) + cables = RB.connect(rbs,spring_dampers;connecting_matrix) # # cst1 = RB.PinJoint( # 1, @@ -63,13 +55,32 @@ function two_tri(;k=100.0,c=0.0,ratio=0.8) # jointedmembers = RB.join((cst1,),indexed) + apparatuses = TypeSortedCollection( + cables + ) + + numbered = RB.number(rbs,apparatuses) + sharing_matrix = [ + 1 1; + 2 2; + ] + indexed = RB.index(rbs,apparatuses;sharing_matrix) + cnt = RB.Connectivity( numbered, indexed, - @eponymtuple(connected,), - # jointedmembers ) st = RB.Structure(rbs,apparatuses,cnt) + ## acs = [RB.RegisterActuator(1,1:ncables,restlens,RB.Uncoupled())] + ## hub = (actuators = acs,) + gauges = Int[] + actuators = Int[] + hub = RB.ControlHub( + st, + gauges, + actuators, + RB.Coalition(st,gauges,actuators) + ) bot = RB.Robot(st,hub) end \ No newline at end of file diff --git a/src/Rible.jl b/src/Rible.jl index d072d5c..5a7431b 100644 --- a/src/Rible.jl +++ b/src/Rible.jl @@ -70,6 +70,8 @@ include("utils.jl") include("members/loci.jl") +include("members/forces/gravitational.jl") + function get_num_of_cstr end function get_num_of_coords end function get_num_of_dof end @@ -97,6 +99,7 @@ function get_joint_forces_jacobian! end function get_joint_velocity_jacobian! end function find_independent_free_idx end function nullspace_mat end +function kinetic_energy_coords end include("members/rigids/natural_coordinates/NCF.jl") # using .NCF diff --git a/src/control/control.jl b/src/control/control.jl index 1f0bf18..75d3435 100644 --- a/src/control/control.jl +++ b/src/control/control.jl @@ -191,7 +191,7 @@ function cost_jacobian!(∂ϕ∂qᵀ,∂ϕ∂q̇ᵀ,∂ϕ∂pᵀ,bot::Robot,q::A update_bodies!(structure) update_apparatuses!(structure) if gravity - apply_gravity!(structure) + apply_field!(structure) end assemble_forces!(structure) M⁻¹ = assemble_M⁻¹(structure) @@ -233,7 +233,7 @@ function generalized_force_jacobian!(∂F∂θ,structure::Structure,hub,policy:: update_bodies!(structure) update_apparatuses!(structure) if gravity - apply_gravity!(structure) + apply_field!(structure) end control = (x) -> Lux.apply(policy.nt.actor,x,policy.nt.ps,policy.nt.st)[1] actuate!(bot,control,q,q̇,t) @@ -288,6 +288,9 @@ end function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure::Structure,hub,policy::NoPolicy,q,q̇,t::Real,∂F∂s=nothing,s=nothing;gravity=false) end +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure::Structure,hub,policy::NoPolicy,q::AbstractVector,q̇::AbstractVector,t::Real;gravity=false) +end + function set_restlen!(structure,u) for (i,s) in enumerate(structure.apparatuses.apparatuses) s.state.restlen = u[i] @@ -322,4 +325,8 @@ end function get_num_of_params(policy::AbstractPolicy) (;ps) = policy.nt length(ps) +end + +function get_num_of_params(policy::NoPolicy) + 0 end \ No newline at end of file diff --git a/src/get.jl b/src/get.jl index cbaf256..c96e04e 100644 --- a/src/get.jl +++ b/src/get.jl @@ -76,7 +76,7 @@ function get_local_coords(bodies,numbered::Numbered) ret end -function get_local_coords(body::RigidBody,r̄p) +function get_local_coords(body::AbstractRigidBody,r̄p) to_local_coords(body.coords.nmcs,r̄p) end @@ -210,6 +210,8 @@ get_bodies(bot::Robot) = get_bodies(bot.structure) get_bodies(st::AbstractStructure) = sort(st.bodies) get_apparatuses(bot::Robot) = get_apparatuses(bot.structure) get_apparatuses(st::AbstractStructure) = sort(st.apparatuses) +get_cables(bot::Robot) = get_cables(bot.structure) +get_cables(st::AbstractStructure) = filter!((x)->x.joint isa CableJoint, sort(st.apparatuses)) get_rigidbars(bot::Robot) = get_rigidbars(bot.structure) @@ -233,7 +235,8 @@ Return System DistanceSpringDamper stiffness coefficients $(TYPEDSIGNATURES) """ function get_cables_stiffness(st::Structure) - [s.k for s in st.apparatuses.cables] + cables = get_cables(st) + [s.force.k for s in cables] end """ @@ -241,11 +244,13 @@ Return System DistanceSpringDamper current Length. $(TYPEDSIGNATURES) """ function get_cables_len(st::Structure) - [s.state.length for s in st.apparatuses.cables] + cables = get_cables(st) + [s.force.state.length for s in cables] end function get_cables_len_dot(st::Structure) - [s.state.lengthdot for s in st.apparatuses.cables] + cables = get_cables(st) + [s.force.state.lengthdot for s in cables] end """ @@ -253,7 +258,8 @@ Return System DistanceSpringDamper deformation。 $(TYPEDSIGNATURES) """ function get_cables_deform(st::Structure) - [s.state.length - s.state.restlen for s in st.apparatuses.cables] + cables = get_cables(st) + [s.force.state.length - s.force.state.restlen for s in cables] end """ @@ -261,7 +267,8 @@ Return System DistanceSpringDamper Restlength。 $(TYPEDSIGNATURES) """ function get_cables_restlen(st::Structure) - [s.state.restlen for s in st.apparatuses.cables] + cables = get_cables(st) + [s.force.state.restlen for s in cables] end """ @@ -269,7 +276,8 @@ Return System DistanceSpringDamper Tension. $(TYPEDSIGNATURES) """ function get_cables_tension(st::Structure) - [s.state.tension for s in st.apparatuses.cables] + cables = get_cables(st) + [s.force.state.tension for s in cables] end """ @@ -277,8 +285,9 @@ Set cables' tension $(TYPEDSIGNATURES) """ function set_cables_tension!(st::Structure,fs) - for (s,f) in zip(st.apparatuses.cables,fs) - s.state.tension = f + cables = get_cables(st) + for (s,f) in zip(cables,fs) + s.force.state.tension = f end end @@ -288,7 +297,8 @@ Return System DistanceSpringDamper force density。 $(TYPEDSIGNATURES) """ function get_cables_force_density(st::Structure) - [s.state.tension/s.state.length for s in st.apparatuses.cables] + cables = get_cables(st) + [s.force.state.tension/s.force.state.length for s in cables] end """ @@ -303,13 +313,14 @@ function get_original_restlen(botinput::Robot) end function force_densities_to_restlen(st::Structure,γs) + cables = get_cables(st) [ begin - l = s.state.length - l̇ = s.state.lengthdot + l = s.force.state.length + l̇ = s.force.state.lengthdot k = s.k c = s.c u = l-(γ*l-c*l̇)/k end - for (γ,s) in zip(γs,st.apparatuses.cables)] + for (γ,s) in zip(γs,cables)] end diff --git a/src/mechanics/contact.jl b/src/mechanics/contact.jl index 2be7947..9e04743 100644 --- a/src/mechanics/contact.jl +++ b/src/mechanics/contact.jl @@ -1,17 +1,24 @@ abstract type AbstractField end +struct NoField <: AbstractField end abstract type AbstractGravity <: AbstractField end -struct NoGravity <: AbstractGravity end struct EarthSurfaceGravity{T} <: AbstractGravity acceleration::T + function EarthSurfaceGravity(g=9.81) + new{typeof(g)}(g) + end end -Gravity(g=9.81) = EarthSurfaceGravity(g) - +struct EarthGravitation{T} <: AbstractGravity + std_gra::T +end -has_gravity(::NoGravity) = false +has_gravity(::NoField) = false has_gravity(::EarthSurfaceGravity) = true +has_gravity(::EarthGravitation) = true abstract type AbstractGeometry end +struct NoGeometry <: AbstractGeometry end + abstract type AbstractEnvironment end @@ -21,7 +28,23 @@ struct StaticEnvironment{geometryType,fieldType} <: AbstractEnvironment geometry::geometryType field::fieldType end -function StaticContactSurfaces(surfaces,gravity=Gravity()) + +GravityEnv(g=9.81) = StaticEnvironment( + NoGeometry(), + EarthSurfaceGravity(g), +) + +EmptyEnv() = StaticEnvironment( + NoGeometry(), + NoField(), +) + +GravitationalEnv(std_gra=std_gra) = StaticEnvironment( + NoGeometry(), + EarthGravitation(std_gra), +) + +function StaticContactSurfaces(surfaces,gravity=EarthSurfaceGravity(9.81)) StaticEnvironment( surfaces, gravity @@ -52,7 +75,7 @@ end function Contact(id,μ,e) active = false - persistent = false + persistent = true i = one(μ) o = zero(μ) gap = i diff --git a/src/mechanics/dynamic_relax.jl b/src/mechanics/dynamic_relax.jl index 470274e..5aefaac 100644 --- a/src/mechanics/dynamic_relax.jl +++ b/src/mechanics/dynamic_relax.jl @@ -27,7 +27,7 @@ function initialize_GDR(structure,F::Nothing;gravity=true) update_bodies!(structure,x) update_apparatuses!(structure) if gravity - apply_gravity!(structure) + apply_field!(structure) end assemble_forces!(F,structure) # @show abs.(F-Q) |> maximum diff --git a/src/mechanics/dynamics.jl b/src/mechanics/dynamics.jl index 136908e..5c3265e 100644 --- a/src/mechanics/dynamics.jl +++ b/src/mechanics/dynamics.jl @@ -53,7 +53,7 @@ function generalized_force!(F,bot::Robot,::NoPolicy,q,q̇,t,s=nothing;gravity=tr lazy_update_bodies!(structure,q,q̇) update_apparatuses!(structure, s) if gravity - apply_gravity!(structure;factor=1) + apply_field!(structure;factor=1) end ## actuate!(bot,q,q̇,t) assemble_forces!(F,structure) @@ -67,27 +67,13 @@ function generalized_force!(F,bot::Robot,policy::AbstractPolicy,q,q̇,t,s=nothin lazy_update_bodies!(structure,q,q̇) update_apparatuses!(structure, s) if gravity - apply_gravity!(structure;factor=1) + apply_field!(structure;factor=1) end assemble_forces!(F,structure) user_defined_force!(F,t) end -function generalized_force_hole!(F,bot::Robot,policy::AbstractPolicy,q,q̇,t,s,s_temp;gravity=true,(user_defined_force!)=(F,t)->nothing) - (;structure) = bot - clear_forces!(structure) - actuate!(bot,policy,q,q̇,t) - lazy_update_bodies!(structure,q,q̇) - # update_apparatuses!(structure) - update_apparatuses_hole!(structure, s, s_temp) - if gravity - apply_gravity!(structure;factor=1) - end - assemble_forces!(F,structure) - user_defined_force!(F,t) -end - -function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t,∂F∂s,s=nothing) +function generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot::Robot,q,q̇,t,∂F∂s=nothing,s=nothing) generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,NoPolicy(),q,q̇,t,∂F∂s,s) end @@ -136,23 +122,6 @@ function generalized_force_jacobian!(∂F∂s,structure::AbstractStructure,q,q̇ end end -function generalized_force_jacobian_hole!(∂F∂q̌,∂F∂q̌̇,∂F∂s̄,∂ζ∂q,ζ,bot::Robot,policy::AbstractPolicy,q,q̇,t,cluster_cache,s=nothing) - (;structure,hub) = bot - ∂F∂q̌ .= 0 - ∂F∂q̌̇ .= 0 - ∂F∂s̄ .= 0 - ∂ζ∂q .= 0 - ζ .= 0 - clear_forces!(structure) - lazy_update_bodies!(structure,q,q̇) - update_apparatuses!(structure) - generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,structure,hub,policy,q,q̇,t) - build_tangent_stiffness_matrix!(∂F∂q̌,structure) - build_tangent_damping_matrix!(∂F∂q̌̇,structure) - build_ζ_hole!(ζ, cluster_cache, structure) - build_∂ζ∂q!(∂ζ∂q, cluster_cache, structure) -end - struct ContactCache{cacheType} cache::cacheType end @@ -327,7 +296,7 @@ function activate_frictional_contacts!(structure,contact_env::StaticEnvironment, (;indexed,numbered) = structure.connectivity (;bodyid2sys_loci_idx) = numbered (;num_of_bodies) = indexed - (;geometry) = contact_env + surfaces = contact_env.geometry T = eltype(q) nq = length(q) na = 0 @@ -342,7 +311,7 @@ function activate_frictional_contacts!(structure,contact_env::StaticEnvironment, for pid in eachindex(loci_states) locus_state = loci_states[pid] (;frame,contact_state) = locus_state - gap, normal = contact_gap_and_normal(frame.position,geometry) + gap, normal = contact_gap_and_normal(frame.position,surfaces) if !checkpersist contact_state.active = false end @@ -489,7 +458,7 @@ function activate_contacts!(structure,contact_env::StaticEnvironment,solver_cach (;indexed,numbered) = structure.connectivity (;bodyid2sys_loci_idx) = numbered (;num_of_bodies) = indexed - (;geometry) = contact_env + surfaces = contact_env.geometry T = eltype(q) nq = length(q) na = 0 diff --git a/src/mechanics/dynamics_solvers/Moreau_family/Moreau_CCP_constant_mass.jl b/src/mechanics/dynamics_solvers/Moreau_family/Moreau_CCP_constant_mass.jl index 60c1a3a..3c14580 100644 --- a/src/mechanics/dynamics_solvers/Moreau_family/Moreau_CCP_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Moreau_family/Moreau_CCP_constant_mass.jl @@ -6,6 +6,7 @@ end function generate_cache( simulator::Simulator{<:DynamicsProblem{ RobotType, + policyType, EnvType, RestitutionFrictionCombined{NewtonRestitution,CoulombFriction} }}, @@ -15,12 +16,17 @@ function generate_cache( }, ::Val{true}; dt,kargs... - ) where {RobotType,EnvType} + ) where {RobotType,policyType,EnvType} (;prob) = simulator - (;bot,env) = prob + (;bot,policy,env) = prob (;structure) = bot - F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t;gravity=true) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + options = merge( + (gravity=true,factor=1,checkpersist=true), #default + prob.options, + solver.options, + ) + F!(F,q,q̇,t) = generalized_force!(F,bot,policy,q,q̇,t;gravity=options.gravity) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t) M = Matrix(assemble_M(structure)) Φ = make_cstr_function(bot) diff --git a/src/mechanics/dynamics_solvers/Moreau_family/Moreau_constant_mass.jl b/src/mechanics/dynamics_solvers/Moreau_family/Moreau_constant_mass.jl index 7d58b17..7717f25 100644 --- a/src/mechanics/dynamics_solvers/Moreau_family/Moreau_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Moreau_family/Moreau_constant_mass.jl @@ -30,7 +30,7 @@ function generate_cache( A = make_cstr_jacobian(structure) Φ = make_cstr_function(structure) F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) ∂Aᵀλ∂q(q::AbstractVector,λ) = cstr_forces_jacobian(structure,q,λ) ∂Aq̇∂q(q::AbstractVector,q̇) = cstr_velocity_jacobian(structure,q,q̇) q̌0 = traj.q̌[begin] diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_constant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_constant_mass.jl index c5a4573..ab67e38 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_constant_mass.jl @@ -199,7 +199,7 @@ function generate_cache( ∂Fₘ∂θ = zeros(T,nq,nθ) Jacᵏ⁺¹ₘ = zeros(T,nx,nθ) function ∂f∂θ!(Jacᵏ⁺¹ₘ,∂Fₘ∂θ,q,q̇,t,h) - generalized_force_jacobian!(∂Fₘ∂θ,bot,policy,q,q̇,t;gravity=options.gravity) + generalized_force_jacobian!(∂Fₘ∂θ,structure,policy,q,q̇,t;gravity=options.gravity) Jacᵏ⁺¹ₘ[ 1: nq,1:nθ] .= -h^2/2*∂Fₘ∂θ Jacᵏ⁺¹ₘ[ nq+1:2nq,1:nθ] .= -h^2/2*∂Fₘ∂θ Jacᵏ⁺¹ₘ[2nq+1:end,1:nθ] .= 0.0 diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_nonconstant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_nonconstant_mass.jl index 947ee3c..1c21431 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_nonconstant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Adjoint_Zhong06_nonconstant_mass.jl @@ -19,7 +19,7 @@ function generate_cache( Φ = make_cstr_function(structure) A = make_cstr_jacobian(structure) F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) ∂Aᵀλ∂q(q,λ) = cstr_forces_jacobian(structure,q,λ) adjoint_traj = StructArray( [ diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_mono.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_mono.jl index 1bbbe24..cda64b8 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_mono.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_constant_mass_mono.jl @@ -6,6 +6,7 @@ end function generate_cache( simulator::Simulator{<:DynamicsProblem{ RobotType, + policyType, EnvType, RestitutionFrictionCombined{NewtonRestitution,CoulombFriction} }}, @@ -15,12 +16,18 @@ function generate_cache( }, ::Val{true}; dt,kargs... - ) where {RobotType,EnvType} + ) where {RobotType,policyType,EnvType} (;prob) = simulator - (;bot,env) = prob + (;bot,policy,env) = prob (;structure) = bot - F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t;gravity=true) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + options = merge( + (gravity=true,factor=1,checkpersist=true), #default + prob.options, + solver.options, + ) + F!(F,q,q̇,t) = generalized_force!(F,bot,policy,q,q̇,t;gravity=options.gravity) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,policy,q,q̇,t) + ## ∂F∂θ!(∂Fₘ∂θ,q,q̇,t) = generalized_force_jacobian!(∂Fₘ∂θ,structure,policy,q,q̇,t;) M = Matrix(assemble_M(structure)) Φ = make_cstr_function(bot) @@ -45,13 +52,14 @@ function generate_cache( ) = prepare_contacts(bot,env) cache = @eponymtuple( - F!,Jac_F!, + F!,Jac_F!,#∂F∂θ!, M,Φ,A,Ψ,B,∂Ψ∂q,∂Aᵀλ∂q,∂Bᵀμ∂q, contacts_bits, persistent_bits, μs_sys, es_sys, - gaps_sys + gaps_sys, + options ) Zhong06_CCP_Constant_Mass_Mono_Cache(cache) end @@ -59,19 +67,19 @@ end function make_step_k( solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cache, nq,nλ,na, - qₖ₋₁,vₖ₋₁,pₖ₋₁,tₖ₋₁, + step_data,tₖ₋₁, pₖ,vₖ, invM, h,mass_norm) (;F!,Jac_F!,M,Φ,A,∂Aᵀλ∂q) = solver_cache.cache - + (;qₖ₋₁,vₖ₋₁,pₖ₋₁) = step_data n1 = nq n2 = nq+nλ nΛ = 3na nx = n2 function ns_stepk!( - 𝐫𝐞𝐬,𝐉, - Fₘ,∂F∂q,∂F∂q̇, + 𝐫𝐞𝐬,𝐉,𝐉_data, + Fₘ,∂F∂q,∂F∂q̇,#∂Fₘ∂θ, 𝐰,x,Λₖ,y,∂y∂x, Λ_split,y_split, structure, @@ -91,6 +99,7 @@ function make_step_k( Aₖ₋₁ = A(qₖ₋₁) Aₖ = A(qₖ) + # pₖ₋₁ = M*vₖ₋₁ 𝐫𝐞𝐬[ 1:n1] .= -h.*pₖ₋₁ .+ M*(qₖ.-qₖ₋₁) .- mass_norm.*transpose(Aₖ₋₁)*λₘ .- (h^2)/2 .*Fₘ @@ -101,6 +110,18 @@ function make_step_k( 𝐉[ 1:n1,n1+1:n2] .= -mass_norm.*transpose(Aₖ₋₁) 𝐉[n1+1:n2, 1:n1] .= -mass_norm.*Aₖ + 𝐉_data .= 0.0 + #position + 𝐉_data[ 1:nq, 1:nq] .= -M .-h^2/2 .*(1/2 .*∂F∂q .- 1/h.*∂F∂q̇) .- mass_norm.*∂Aᵀλ∂q(qₖ₋₁,λₘ) + #velocity + 𝐉_data[ 1:nq,nq+1:2nq] .= -h*M + #control + ## ∂F∂θ!(∂Fₘ∂θ,qₘ,q̇ₘ,tₘ) + ## 𝐉_data[ 1:nq,2nq+1:nθ] .= -h^2/2*∂Fₘ∂θ + #structural + ## 𝐉_data[ 1:n1,n1+1:n2] + #contact + ## 𝐉_data[ 1:n1,n1+1:n2] if na != 0 get_distribution_law!(structure,contact_cache,qₖ) @@ -130,7 +151,7 @@ function make_step_k( ∂y∂x[is+1:is+3, 1:n1] .= ∂v́⁺∂qₖ[is+1:is+3,:] ∂y∂x[is+1:is+3,n1+1:n2] .= Dⁱₖ*∂vₖ∂λₘ end - ∂y∂x .= (I+Lv)*∂y∂x + ## ∂y∂x .= (I+Lv)*∂y∂x for i = 1:na is = 3(i-1) vⁱₖ₋₁ = @view v́ₖ₋₁[is+1:is+3] @@ -143,15 +164,15 @@ function make_step_k( 𝐰[is+1:is+3] .= [v́ₜⁱ,0,0] ∂y∂x[is+1 , 1:n1] .+= 1/(norm(v́⁺[is+2:is+3])+1e-14)*(v́⁺[is+2]*∂v́⁺∂qₖ[is+2,:] .+ v́⁺[is+3]*∂v́⁺∂qₖ[is+3,:]) end - 𝐫𝐞𝐬[(n2 +1):(n2+ nΛ)] .= (h.*((I+Lv)*v́⁺ .+ 𝐰) .- h.*y) + 𝐫𝐞𝐬[(n2 +1):(n2+ nΛ)] .= (h.*(v́⁺ .+ 𝐰) .- h.*y) 𝐫𝐞𝐬[n2+nΛ+1:n2+2nΛ] .= reduce(vcat,Λ_split⊙y_split) 𝐉[ 1:n1 , n2+ 1:n2+ nΛ] .= -mass_norm*h .*transpose(D)*H*(I+L) 𝐉[n2+1:n2+ nΛ, 1:n2 ] .= h.*∂y∂x 𝐉[n2+1:n2+ nΛ, n2+nΛ+1:n2+2nΛ] .= -h.*I(nΛ) 𝐉[n2+nΛ+1:n2+2nΛ, n2+ 1:n2+ nΛ] .= BlockDiagonal(mat.(y_split)) 𝐉[n2+nΛ+1:n2+2nΛ, n2+nΛ+1:n2+2nΛ] .= BlockDiagonal(mat.(Λ_split)) - if timestep == 850 - @show 𝐉[n2+nΛ+1:n2+2nΛ,:] + if false + ## @show 𝐉[n2+nΛ+1:n2+2nΛ,:] end end # debug @@ -164,14 +185,14 @@ function make_step_k( end function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cache; - dt, - ftol=1e-14,xtol=ftol, - verbose=false,verbose_contact=false, - maxiters=50, - max_restart=3, - progress=true,exception=true) + dt, + ftol=1e-14,xtol=ftol, + verbose=false,verbose_contact=false, + maxiters=50,max_restart=3, + progress=true,exception=true + ) (;prob,controller,tspan,restart,totalstep) = sim - (;bot,env) = prob + (;bot,policy,env) = prob (;structure,traj,contacts_traj) = bot (;M,A,contacts_bits) = solver_cache.cache q0 = traj.q[begin] @@ -187,11 +208,9 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cach F = zeros(T,nq) ∂F∂q = zeros(T,nq,nq) ∂F∂q̇ = zeros(T,nq,nq) + nθ = get_num_of_params(policy) + ∂Fₘ∂θ = zeros(T,nq,nθ) nx = nq + nλ - Δx = zeros(T,nx) - x = zero(Δx) - Res = zero(Δx) - Jac = zeros(T,nx,nx) mr = norm(M,Inf) mass_norm = mr @@ -231,6 +250,7 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cach x = zero(Δx) Res = zero(Δx) Jac = zeros(T,nx,nx) + Jac_data = zeros(T,nx,nq+nq+nθ) Λₖ = @view x[(n2+1):n2+nΛ] y = @view x[n2+nΛ+1:n2+2nΛ] 𝐰 = zeros(T,nΛ) @@ -252,13 +272,17 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cach ΔΛc_split = split_by_lengths(ΔΛc,3) Δyc_split = split_by_lengths(Δyc,3) get_frictional_directions_and_positions!(structure, contact_cache, qₖ₋₁, q̇ₖ₋₁, Λₖ) + step_data = ComponentArray( + @eponymtuple( + qₖ₋₁,vₖ₋₁=q̇ₖ₋₁,pₖ₋₁, + ) + ) ns_stepk! = make_step_k( solver_cache, nq,nλ,na, - qₖ₋₁,q̇ₖ₋₁,pₖ₋₁,tₖ₋₁, + step_data,tₖ₋₁, pₖ,q̇ₖ, - invM, - dt,mass_norm + invM,dt,mass_norm ) restart_count = 0 Λ_guess = 0.1 @@ -269,8 +293,8 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cach x[ nq+1:nq+nλ] .= 0.0 for iteration = 1:maxiters ns_stepk!( - Res,Jac, - F,∂F∂q,∂F∂q̇, + Res,Jac,Jac_data, + F,∂F∂q,∂F∂q̇,#∂Fₘ∂θ, 𝐰,x,Λₖ,y,∂y∂x, Λ_split,y_split, structure, @@ -290,6 +314,9 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cach else # na!=0 μ = transpose(y)*Λₖ/nΛ Δxp .= lu𝐉\(-Res) + ## @show Res[n2+1:n2+2nΛ] + ## @show (Jac*Δxp)[n2+1:n2+2nΛ] + ## @show Δxp[n2+1:n2+2nΛ] αp_Λ = find_cone_step_length(Λ_split,ΔΛp_split,J) αp_y = find_cone_step_length(y_split,Δyp_split,J) αpmax = min(αp_Λ,αp_y) @@ -302,7 +329,15 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cach break end τ = σ*μp - 𝐫𝐞𝐬_c_split = -τ.*𝐞_split.+((Δyp_split)⊙(ΔΛp_split)) + 𝐫𝐞𝐬_c_split = -τ.*𝐞_split#.+((Δyp_split)⊙(ΔΛp_split)) + if false + ## @show Λₖ, normRes, μ, cond(Jac) + ## @show qr(Jac).R |> diag + @show Res[1:n1] |> norm + @show Res[n1+1:n2] |> norm + @show Res[n2+1:n2+nΛ] |> norm + @show Res[n2+nΛ+1:n2+2nΛ] |> norm + end Res[n2+nΛ+1:n2+2nΛ] .+= reduce(vcat,𝐫𝐞𝐬_c_split) normRes = norm(Res) if normRes < ftol @@ -326,18 +361,25 @@ function solve!(sim::Simulator,solver_cache::Zhong06_CCP_Constant_Mass_Mono_Cach # α_record[iteration] = α x .+= α.*Δxc μ = transpose(y)*Λₖ/nΛ - if timestep == 850 - @show Λₖ, normRes, μ, cond(Jac) - @show qr(Jac).R |> diag + if false + ## @show Λₖ, normRes, μ, cond(Jac) + ## @show qr(Jac).R |> diag + @show Res[n2+nΛ+1:n2+2nΛ] |> norm + @show (y_split)⊙(Λ_split) + @show (Δyp_split)⊙(ΔΛp_split) end + @show lu𝐉\(-Jac_data) + ## @show Λₖ, μ end end if isconverged break end restart_count += 1 - Λ_guess /= 10 - # @warn "restarting step: $timestep, count: $restart_count, Λ_guess = $Λ_guess" + if na > 0 + Λ_guess = max(Λ_guess/10,maximum(abs.(Λₖ[begin:3:end]))) + end + ## @warn "restarting step: $timestep, count: $restart_count, Λ_guess = $Λ_guess" end qₖ .= x[ 1:nq] λₘ .= x[ nq+1:nq+nλ] diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_nonconstant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_nonconstant_mass.jl index 116823a..0a3686d 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_nonconstant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_CCP_nonconstant_mass.jl @@ -19,7 +19,7 @@ function generate_cache( (;bot,env) = simulator.prob (;structure) = bot F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) Mₘ = assemble_M(structure) M⁻¹ₖ = assemble_M⁻¹(structure) ∂Mₘhq̇ₘ∂qₘ = assemble_∂Mq̇∂q(structure) diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl index 51bf1e8..922e5b0 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_constant_mass.jl @@ -162,17 +162,19 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; ## FiniteDiff.finite_difference_jacobian!(Jac_ref,Res_stepk!,xₖ) ## Jac_my = zeros(nx,nx) ## Jac_stepk!(Jac_my,xₖ) - ## diff_Jac = Jac_my .- Jac_ref - ## diff_Jac[abs.(diff_Jac).<1e-5] .= 0.0 - ## diff_rowidx = findall((x)-> x>1e-5,norm.(eachrow(diff_Jac))) - ## @show diff_rowidx .- length(q̌ₖ) - ## @show diff_Jac[end-4:end-3,:] - ## @show findall((x)->abs(x)>0,diff_Jac[114+length(q̌ₖ),:]) - ## @show findall((x)->abs(x)>0,diff_Jac[115+length(q̌ₖ),:]) - ## @show Jac_my[ 1:nq̌, nq̌+nλ+1:nx] - ## @show Jac_ref[ 1:nq̌, nq̌+nλ+1:nx] + ## diff_Jac = Jac_my .- Jac_ref .|> abs + ## diff_Jac[(diff_Jac).<1e-8] .= 0.0 + ## diff_rowidx = findall((x)-> x>1e-5,norm.(eachrow(diff_Jac))) + ## @show diff_rowidx .- length(q̌ₖ) + ## @show diff_Jac[end-4:end-3,:] + ## @show findall((x)->abs(x)>0,diff_Jac[114+length(q̌ₖ),:]) + ## @show findall((x)->abs(x)>0,diff_Jac[115+length(q̌ₖ),:]) + ## @show Jac_my + ## @show Jac_ref + @show diff_Jac |> maximum ## end - ## @show maximum(abs.(diff_Jac))for iteration = 1:maxiters + ## @show maximum(abs.(diff_Jac)) + ## for iteration = 1:maxiters ## @show iteration,D,ηs,restitution_coefficients,gaps for iteration = 1:maxiters Res_stepk!(Res,xₖ) @@ -201,7 +203,7 @@ function solve!(sim::Simulator,cache::Zhong06_Constant_Mass_Cache; q̌ₖ .= xₖ[ 1:nq̌ ] λₖ .= xₖ[nq̌+1:nq̌+nλ] sₖ .= xₖ[nq̌+nλ+1:nx] - @show timestep, sₖ, sₖ₋₁ + ## @show timestep, sₖ, sₖ₋₁ Momentum_k!(p̌ₖ,p̌ₖ₋₁,qₖ,qₖ₋₁,λₖ,Ḿ,A,Aᵀₖ₋₁,mass_norm,h) q̌̇ₖ .= M̌⁻¹*(p̌ₖ.-M̄*q̃̇ₖ ) #---------Step k finisher----------- diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass.jl index 1a95783..0c5970f 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass.jl @@ -19,7 +19,7 @@ function generate_cache( (;bot,env) = simulator.prob (;structure) = bot F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) Mₘ = assemble_M(structure) M⁻¹ₖ = assemble_M⁻¹(structure) ∂Mₘq̇ₘ∂qₘ = assemble_∂Mq̇∂q(structure) diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass_mono.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass_mono.jl index bac4e71..27660e7 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass_mono.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_frictionless_nonconstant_mass_mono.jl @@ -19,7 +19,7 @@ function generate_cache( (;bot,env) = simulator.prob (;structure) = bot F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) Mₘ = assemble_M(structure) ∂Mₘhq̇ₘ∂qₘ = assemble_∂Mq̇∂q(structure) M⁻¹ₖ = assemble_M⁻¹(structure) diff --git a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_nonconstant_mass.jl b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_nonconstant_mass.jl index a2ea54b..a19673c 100644 --- a/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_nonconstant_mass.jl +++ b/src/mechanics/dynamics_solvers/Zhong06_family/Zhong06_nonconstant_mass.jl @@ -19,7 +19,7 @@ function generate_cache( Φ = make_cstr_function(structure) A = make_cstr_jacobian(structure) F!(F,q,q̇,t) = generalized_force!(F,bot,q,q̇,t) - Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobain!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) + Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) = generalized_force_jacobian!(∂F∂q̌,∂F∂q̌̇,bot,q,q̇,t) cache = @eponymtuple( F!,Jac_F!, Mₘ,M⁻¹ₖ, diff --git a/src/mechanics/inverse_statics.jl b/src/mechanics/inverse_statics.jl index 9350cba..45d94e1 100644 --- a/src/mechanics/inverse_statics.jl +++ b/src/mechanics/inverse_statics.jl @@ -25,7 +25,7 @@ function build_Q̃(structure) foreach(structure.apparatuses) do appar j = appar.id if appar.joint isa CableJoint - (;hen,egg) = appar.joint + (;hen,egg) = appar.joint.hen2egg C1 = hen.body.cache.Cps[hen.pid] C2 = egg.body.cache.Cps[egg.pid] uci1 = hen.body.coords.free_idx @@ -62,16 +62,14 @@ end function build_L̂(st) (;connectivity,num_of_dim) = st - (;connected) = connectivity.tensioned - (;cables) = st.apparatuses - ncables = length(cables) + cables = get_cables(st) + num_of_cables = length(cables) T = get_numbertype(st) - L̂ = spzeros(T, ncables*num_of_dim, ncables) - foreach(connected) do scnt - j = scnt.id - scable = cables[j] + L̂ = spzeros(T, num_of_cables*num_of_dim, num_of_cables) + foreach(cables) do cable + j = cable.id js = (j-1)*num_of_dim - L̂[js+1:js+num_of_dim,j] = scable.state.direction + L̂[js+1:js+num_of_dim,j] = cable.force.state.direction end L̂ end @@ -121,7 +119,7 @@ end function build_Ǧ(tginput;factor=1.0) st = deepcopy(tginput) clear_forces!(st) - apply_gravity!(st;factor) + apply_field!(st;factor) assemble_forces!(Ǧ,st) end @@ -452,7 +450,7 @@ function check_static_equilibrium(tg_input,q,λ,F=nothing;gravity=false) update_cables_apply_forces!(st) check_restlen(st,get_cables_restlen(st)) if gravity - apply_gravity!(st) + apply_field!(st) end generalized_forces = assemble_forces(st) if !isnothing(F) @@ -483,17 +481,16 @@ function check_static_equilibrium_output_multipliers!(st,q,F=nothing; # stpt = nothing ) clear_forces!(st) - update_bodies!(st) + update_bodies!(st,q) update_apparatuses!(st) # check_restlen(st,get_cables_restlen(st)) if gravity - apply_gravity!(st) + apply_field!(st) end - assemble_forces!(generalized_forces,st) + generalized_forces = assemble_forces!(st) if !isnothing(F) generalized_forces .+= F[:] end - q = get_coords(st) c = get_local_coords(st) q̌ = get_free_coords(st) A = make_cstr_jacobian(st,q)(q̌,c) diff --git a/src/mechanics/stiffness.jl b/src/mechanics/stiffness.jl index 2821a37..6d102d1 100644 --- a/src/mechanics/stiffness.jl +++ b/src/mechanics/stiffness.jl @@ -219,7 +219,7 @@ end # # μ = l .- (f./k) # λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f # # @show f,λ -# Ǩa = - RB.cstr_forces_jacobian(bot.structure,λ) +# Ǩa = RB.cstr_forces_jacobian(bot.structure,λ) # 𝒦a = transpose(Ň)*Ǩa*Ň |> sparse # D_𝒦a = ldl(𝒦a).D.diag |> sort diff --git a/src/members/abstract_body.jl b/src/members/abstract_body.jl index 2db2eab..1a524b1 100644 --- a/src/members/abstract_body.jl +++ b/src/members/abstract_body.jl @@ -17,6 +17,8 @@ update_state!(body::AbstractBody,q,q̇) = update_state!(body.state,body.coords,b update_loci_states!(body::AbstractBody,q,q̇) = update_loci_states!(body.state,body.coords,body.cache,body.prop,q,q̇) stretch_loci!(body::AbstractBody,c) = stretch_loci!(body.coords,body.cache,body.prop,c) update_transformations!(body::AbstractBody,q) = update_transformations!(body.coords,body.cache,body.state,body.prop,q) +kinetic_energy_coords(body::AbstractBody,q,q̇) = kinetic_energy(body.coords,body.cache,body.state,body.prop,q,q̇) + function body_state2coords_state(body::AbstractBody) body_state2coords_state(body.state,body.coords) end @@ -98,7 +100,6 @@ function cstr_velocity_jacobian(coords::NonminimalCoordinates,q̇) cstr_velocity_jacobian(coords.nmcs,coords.free_idx,coords.cstr_idx,q̇) end - struct InertiaCache{MType,JType,GType} M::MType M⁻¹::MType diff --git a/src/members/forces/gravitational.jl b/src/members/forces/gravitational.jl new file mode 100644 index 0000000..9bcef7f --- /dev/null +++ b/src/members/forces/gravitational.jl @@ -0,0 +1,2 @@ +const std_gra = 3.986e14#(m^3/s^-2) + diff --git a/src/members/loci.jl b/src/members/loci.jl index b75c609..4452113 100644 --- a/src/members/loci.jl +++ b/src/members/loci.jl @@ -108,6 +108,10 @@ end to_3D(frame::CartesianFrame{3}) = frame +function CartesianFrame{3}(frame::CartesianFrame{2}) + to_3D(frame) +end + function to_3D(frame::CartesianFrame{2,M,T}) where {M,T} (;position,velocity,axes,angular_velocity) = frame o = zero(T) diff --git a/src/members/rigids/natural_coordinates/NCF.jl b/src/members/rigids/natural_coordinates/NCF.jl index 4eea8df..7d86ddf 100644 --- a/src/members/rigids/natural_coordinates/NCF.jl +++ b/src/members/rigids/natural_coordinates/NCF.jl @@ -10,7 +10,7 @@ using EponymTuples using ForwardDiff using DocStringExtensions -import ..Rible: HouseholderOrthogonalization, skew, Axes, GECP, CartesianFrame +import ..Rible: HouseholderOrthogonalization, skew, Axes, GECP, CartesianFrame, rotation_matrix import ..Rible: get_num_of_cstr, get_num_of_coords import ..Rible: get_num_of_dof, get_num_of_local_dims @@ -27,8 +27,10 @@ import ..Rible: build_joint_cache, get_joint_violations! import ..Rible: get_joint_jacobian! import ..Rible: get_joint_forces_jacobian! import ..Rible: get_joint_velocity_jacobian! +import ..Rible: kinetic_energy_coords import ..Rible: find_independent_free_idx import ..Rible: nullspace_mat +import ..Rible: std_gra include("./LNC.jl") diff --git a/src/members/rigids/natural_coordinates/functions.jl b/src/members/rigids/natural_coordinates/functions.jl index e91500c..cd8bd19 100644 --- a/src/members/rigids/natural_coordinates/functions.jl +++ b/src/members/rigids/natural_coordinates/functions.jl @@ -94,7 +94,7 @@ function to_local_coords(nmcs::NC,r̄) invX̄*(r̄-r̄i) end -function to_position_jacobian(nmcs::NC,q,c) +function to_position_jacobian(nmcs::NC,c) num_of_dim = get_num_of_dims(nmcs) nlds = get_num_of_local_dims(nmcs) ncoords = get_num_of_coords(nmcs) @@ -103,6 +103,10 @@ function to_position_jacobian(nmcs::NC,q,c) SMatrix{num_of_dim,ncoords}(kron(C_raw,IMatrix(num_of_dim))*conversion) end +function to_position_jacobian(nmcs::NC,q,c) + to_position_jacobian(nmcs,c) +end + function to_velocity_jacobian(nmcs::NC,q,q̇,c) num_of_dim = get_num_of_dims(nmcs) nlds = get_num_of_local_dims(nmcs) diff --git a/src/members/rigids/natural_coordinates/mass_matrix.jl b/src/members/rigids/natural_coordinates/mass_matrix.jl index 92a8af3..c05285d 100644 --- a/src/members/rigids/natural_coordinates/mass_matrix.jl +++ b/src/members/rigids/natural_coordinates/mass_matrix.jl @@ -1,25 +1,61 @@ # Mass matrices -Ī2J̄(::Union{NC2D2C,NC3D3C,NC2D6C,NC3D6C},Ī) = Ī +Ī2J̄(::Union{NC2D2C,NC3D3C,NC2D4C,NC2D6C,NC3D6C},Ī) = Ī Ī2J̄(::NC3D12C,Ī) = 1/2*tr(Ī)*I-Ī -function Īg2az(nmcs,m,Īg,mass_center) +function Īg2z(nmcs,m,Īₘ,r̄ₘ) (;r̄i,invX̄) = nmcs.data - a = invX̄*(mass_center-r̄i) - J̄g = Ī2J̄(nmcs,Īg) - J̄o = J̄g + m*mass_center*transpose(mass_center) - J̄i = J̄o - m*r̄i*transpose(mass_center) - m*mass_center*transpose(r̄i) + m*r̄i*transpose(r̄i) + cₘ = to_local_coords(nmcs,r̄ₘ) + J̄g = Ī2J̄(nmcs,Īₘ) + J̄o = J̄g + m*r̄ₘ*transpose(r̄ₘ) + J̄i = J̄o - m*r̄i*transpose(r̄ₘ) - m*r̄ₘ*transpose(r̄i) + m*r̄i*transpose(r̄i) z = invX̄*J̄i*transpose(invX̄) #@assert issymmetric(z) - a,Symmetric(z) + Symmetric(z) end +const μ = std_gra ## Mass matrices: standard -function make_M(nmcs::NC,m::T,Īg,mass_center) where {T} # ami (area moment of inertia tensor) +function make_U(nmcs::NC,m::T,Īₘ,r̄ₘ,q) where {T} # ami (area moment of inertia tensor) num_of_dim = get_num_of_dims(nmcs) nld = get_num_of_local_dims(nmcs) ncoords = get_num_of_coords(nmcs) - a,z = Īg2az(nmcs,m,Īg,mass_center) + cₘ = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) + M̄ = zeros(T,1+nld,1+nld) + M̄[1,1] = m + M̄[2:1+nld,1] = m*cₘ + M̄[1,2:1+nld] = M̄[2:1+nld,1] + M̄[2:1+nld,2:1+nld] .= z + ## M_std = kron(M̄,IMatrix(num_of_dim)) + ## cv = nmcs.conversion_to_std + ## M = SMatrix{ncoords,ncoords}(transpose(cv)*M_std*cv) + cₘ = to_local_coords(nmcs,r̄ₘ) + ## to_position + Cₘ = to_position_jacobian(nmcs,cₘ) + 𝐜 = Cₘ*q + ## B̄ = M̄[[1],:] #\int S̄ + ## B = kron(B̄,I(3)) + ## @show size(B), size(q) + ## Bq = B*q + 𝐜ᵀ𝐜 = 𝐜'*𝐜 + + D = 3𝐜*𝐜' - 𝐜ᵀ𝐜*I + A = kron(M̄,D) + ## U_gra0 = -3m*μ/𝐜ᵀ𝐜^(1/2) + ## U_gra1 = 3m*μ/𝐜ᵀ𝐜^(3/2)*𝐜'*Bq + ## @show U_gra0, U_gra1, U_gra0+U_gra1 + U_gra2 =-1/2*μ/𝐜ᵀ𝐜^(5/2)*q'*A*q + ## @show U_gra2 + U_gra = U_gra2 +end + +function make_M(nmcs::NC,m::T,Īₘ,r̄ₘ) where {T} # ami (area moment of inertia tensor) + num_of_dim = get_num_of_dims(nmcs) + nld = get_num_of_local_dims(nmcs) + ncoords = get_num_of_coords(nmcs) + a = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) M_raw = zeros(T,1+nld,1+nld) M_raw[1,1] = m M_raw[2:1+nld,1] = m*a @@ -29,3 +65,227 @@ function make_M(nmcs::NC,m::T,Īg,mass_center) where {T} # ami (area moment of cv = nmcs.conversion_to_std M = SMatrix{ncoords,ncoords}(transpose(cv)*M_std*cv) end + +function gravitational_force(nmcs::NC,m::T,Īₘ,r̄ₘ,q) where {T} + nld = get_num_of_local_dims(nmcs) + a = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) + M̄ = zeros(T,1+nld,1+nld) + M̄[1,1] = m + M̄[2:1+nld,1] = m*a + M̄[1,2:1+nld] = M̄[2:1+nld,1] + M̄[2:1+nld,2:1+nld] .= z + + cₘ = to_local_coords(nmcs,r̄ₘ) + ## to_position + Cₘ = to_position_jacobian(nmcs,cₘ) + 𝐜 = Cₘ*q + 𝐜ᵀ𝐜 = 𝐜'*𝐜 + D = 3𝐜*𝐜' - 𝐜ᵀ𝐜*I + A = kron(M̄,D) + + B̄ = M̄[[1],:] #\int S̄ + B = kron(B̄,I(3)) + + FBᵀ = -3*(𝐜ᵀ𝐜)*𝐜'*B + ## @show size(A), size(FBᵀ) + F = μ/𝐜ᵀ𝐜^(5/2)*(A*q+FBᵀ') +end + +function gravitational_force_jacobian(nmcs::NC,m::T,Īₘ,r̄ₘ,q) where {T} + nld = get_num_of_local_dims(nmcs) + a = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) + M̄ = zeros(T,1+nld,1+nld) + M̄[1,1] = m + M̄[2:1+nld,1] = m*a + M̄[1,2:1+nld] = M̄[2:1+nld,1] + M̄[2:1+nld,2:1+nld] .= z + cₘ = to_local_coords(nmcs,r̄ₘ) + ## to_position + Cₘ = to_position_jacobian(nmcs,cₘ) + 𝐜 = Cₘ*q + 𝐜ᵀ𝐜 = 𝐜'*𝐜 + D = 3𝐜*𝐜' - 𝐜ᵀ𝐜*I + A = kron(M̄,D) + ∂F∂q = μ/𝐜ᵀ𝐜^(5/2)*A +end + +## Mass matrices: LACB + +function make_M_LACB(nmcs::NC,m::T,Īₘ,r̄ₘ) where {T} # ami (area moment of inertia tensor) + num_of_dim = get_num_of_dims(nmcs) + nld = get_num_of_local_dims(nmcs) + ncoords = get_num_of_coords(nmcs) + a = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) + M̄ = zeros(T,1+nld,1+nld) + M̄[1,1] = m + M̄[2:1+nld,1] = m*a + M̄[1,2:1+nld] = M̄[2:1+nld,1] + M̄[2:1+nld,2:1+nld] .= z + Id = IMatrix(num_of_dim) + M_std = kron(M̄,Id) + cv = nmcs.conversion_to_std + M = SMatrix{ncoords,ncoords}(transpose(cv)*M_std*cv) + B̄ = M̄[[1],:] + B = kron(B̄,Id) + M_LACB = [ + m*Id B; + B' M; + ] + M_LACB[4:6,4:6] .+= Id + M_LACB +end + +## Gravitational Potential: LACB +function make_U_LACB(nmcs::NC,m::T,Īₘ,r̄ₘ,ro,q̂) where {T} # ami (area moment of inertia tensor) + num_of_dim = get_num_of_dims(nmcs) + nld = get_num_of_local_dims(nmcs) + ncoords = get_num_of_coords(nmcs) + cₘ = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) + M̄ = zeros(T,1+nld,1+nld) + M̄[1,1] = m + M̄[2:1+nld,1] = m*cₘ + M̄[1,2:1+nld] = M̄[2:1+nld,1] + M̄[2:1+nld,2:1+nld] .= z + ## M_std = kron(M̄,IMatrix(num_of_dim)) + ## cv = nmcs.conversion_to_std + ## M = SMatrix{ncoords,ncoords}(transpose(cv)*M_std*cv) + B̄ = M̄[[1],:] #\int S̄ + B = kron(B̄,I(3)) + ## to_position + Cₘ = to_position_jacobian(nmcs,cₘ) + rc = Cₘ*q̂ + 𝐜 = ro + rc + 𝐜ᵀ𝐜 = 𝐜'*𝐜 + D = 3𝐜*𝐜' - 𝐜ᵀ𝐜*I + + ## FBᵀ = -3*(𝐜ᵀ𝐜)*𝐜'*B + + C = ro'*D*B + + A = kron(M̄,D) + + ## d = 3*m*𝐜ᵀ𝐜*𝐜'*rc + + e = 1/2*m*ro'*D*ro + U_gra2 = -μ/𝐜ᵀ𝐜^(5/2)*( + 1/2*q̂'*A*q̂ + + C*q̂ + + e + ) + ## @show FBᵀ*q̂ + d + ## @show U_gra2 + U_gra = U_gra2 +end + +function gravitational_force_LACB(nmcs::NC,m::T,Īₘ,r̄ₘ,ro,q̂) where {T} + num_of_dim = get_num_of_dims(nmcs) + nld = get_num_of_local_dims(nmcs) + cₘ = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) + M̄ = zeros(T,1+nld,1+nld) + M̄[1,1] = m + M̄[2:1+nld,1] = m*cₘ + M̄[1,2:1+nld] = M̄[2:1+nld,1] + M̄[2:1+nld,2:1+nld] .= z + ## to_position + Cₘ = to_position_jacobian(nmcs,cₘ) + ĉ = Cₘ*q̂ + 𝐜 = ro + ĉ + 𝐜ᵀ𝐜 = 𝐜'*𝐜 + D = 3𝐜*𝐜' - 𝐜ᵀ𝐜*I + + Id = IMatrix(num_of_dim) + ## M_std = kron(M̄,Id) + ## cv = nmcs.conversion_to_std + ## M = SMatrix{ncoords,ncoords}(transpose(cv)*M_std*cv) + B̄ = M̄[[1],:] #\int S̄ + B = kron(B̄,Id) + + ∂ĉᵀ∂q̂ᵀ = Cₘ' + + e = 1/2*m*ro'*D*ro + + C = ro'*D*B + + A = kron(M̄,D) + + Bq̂ = B*q̂ + + ∂Cq̂∂oᵀ = ( + 3ro'*𝐜*I + 3ro*𝐜' + 3𝐜*𝐜' - 2𝐜*ro' - 𝐜ᵀ𝐜*I + )*Bq̂ + + ∂Cq̂∂ĉᵀ = ( + 3ro'*𝐜*I + 3ro*𝐜' - 2𝐜*ro' + )*Bq̂ + + ∂e∂oᵀ = 3/2*m*(2(2ro+ĉ)*𝐜'*ro) - 1/2*m*(ro'*ro*2*𝐜 + 𝐜ᵀ𝐜*2*ro) + ∂e∂ĉᵀ = 3/2*m*(2( ro )*𝐜'*ro) - 1/2*m*(ro'*ro*2*𝐜) + + o = zero(𝐜) + ∂𝐜𝐜ᵀ∂x = hcat(𝐜,o,o) + vcat(𝐜',o',o') + ∂𝐜𝐜ᵀ∂y = hcat(o,𝐜,o) + vcat(o',𝐜',o') + ∂𝐜𝐜ᵀ∂z = hcat(o,o,𝐜) + vcat(o',o',𝐜') + + ∂q̂ᵀAq̂∂oᵀ = + ∂q̂ᵀAq̂∂ĉᵀ = 3*[ + q̂'*kron(M̄,∂𝐜𝐜ᵀ∂x)*q̂, + q̂'*kron(M̄,∂𝐜𝐜ᵀ∂y)*q̂, + q̂'*kron(M̄,∂𝐜𝐜ᵀ∂z)*q̂, + ] + 2𝐜*q̂'*kron(M̄,Id)*q̂ + + ∂U∂q̂ᵀ = -μ/𝐜ᵀ𝐜^(5/2)*( + A*q̂ + + C' + ) + + ∂U∂oᵀ = -μ/𝐜ᵀ𝐜^(5/2)*( + 1/2*∂q̂ᵀAq̂∂oᵀ + + ∂Cq̂∂oᵀ + + ∂e∂oᵀ + ) + 5μ*𝐜/𝐜ᵀ𝐜^(7/2)*( + 1/2*q̂'*A*q̂ + + C*q̂ + + e + ) + + ∂U∂ĉᵀ = -μ/𝐜ᵀ𝐜^(5/2)*( + 1/2*∂q̂ᵀAq̂∂ĉᵀ + + ∂Cq̂∂ĉᵀ + + ∂e∂ĉᵀ + ) + 5μ*𝐜/𝐜ᵀ𝐜^(7/2)*( + 1/2*q̂'*A*q̂ + + C*q̂ + + e + ) + ## ∂U∂qᵀ, ∂U∂oᵀ, ∂U∂ĉᵀ + + vcat( + -∂U∂oᵀ, + -∂U∂q̂ᵀ - + ∂ĉᵀ∂q̂ᵀ*∂U∂ĉᵀ + ) +end + +function gravitational_force_jacobian_LACB(nmcs::NC,m::T,Īₘ,r̄ₘ,𝐜) where {T} + nld = get_num_of_local_dims(nmcs) + a = to_local_coords(nmcs,r̄ₘ) + z = Īg2z(nmcs,m,Īₘ,r̄ₘ) + M̄ = zeros(T,1+nld,1+nld) + M̄[1,1] = m + M̄[2:1+nld,1] = m*a + M̄[1,2:1+nld] = M̄[2:1+nld,1] + M̄[2:1+nld,2:1+nld] .= z + 𝐜ᵀ𝐜 = 𝐜'*𝐜 + D = 3𝐜*𝐜' - 𝐜ᵀ𝐜*I + A = kron(M̄,D) + ## B̄ = M̄[:,1] + ## B = -3*(𝐜ᵀ𝐜)*kron(B̄,𝐜) + ∂f∂q = μ/𝐜ᵀ𝐜^(5/2)*A +end + + diff --git a/src/members/rigids/rigid_body.jl b/src/members/rigids/rigid_body.jl index 9cfc8c0..3b261e8 100644 --- a/src/members/rigids/rigid_body.jl +++ b/src/members/rigids/rigid_body.jl @@ -233,6 +233,31 @@ function RigidBody(prop,state,coords,mesh=nothing) RigidBody(prop,state,coords,cache,mesh) end +""" +通用Rigid Body Type +$(TYPEDEF) +--- +$(TYPEDFIELDS) +""" +struct GravitationalRigidBody{N,M,T,coordsType,cacheType,meshType} <: AbstractRigidBody{N,T} + "Rigid Body Property " + prop::RigidBodyProperty{N,T} + "Rigid Body State " + state::RigidBodyState{N,M,T} + "Coordinates State" + coords::NonminimalCoordinates{coordsType} + "Cache" + cache::cacheType + "Rigid Body Mesh" + mesh::meshType +end + +function GravitationalRigidBody(prop,state,coords,mesh=nothing) + (;nmcs,pres_idx,cstr_idx) = coords + cache = BodyCache(prop,nmcs,pres_idx,cstr_idx) + GravitationalRigidBody(prop,state,coords,cache,mesh) +end + function body_state2coords_state(state::RigidBodyState,coords::NonminimalCoordinates) (;origin_frame) = state cartesian_frame2coords(coords.nmcs,origin_frame) @@ -472,30 +497,83 @@ get_cstr_idx(::QCF.QC) = collect(1:1) # operations on rigid body """ -Return Rigid Body translational kinetic energy. +Return Rigid Body kinetic energy. $(TYPEDSIGNATURES) """ -function kinetic_energy_translation(body::AbstractRigidBody) +function kinetic_energy(body::AbstractRigidBody{3,T}) where {T} (;mass) = body.prop - (;mass_center_velocity) = body.state - T = 1/2*transpose(mass_center_velocity)*mass*mass_center_velocity + (;mass_locus_state) = body.state + mass_velocity = mass_locus_state.frame.velocity + Ω = to_3D(mass_locus_state.frame).local_angular_velocity + 1/2*transpose(mass_velocity)*mass*mass_velocity + 1/2*transpose(Ω)*inertia*Ω end """ -Return Rigid Body rotational kinetic energy. +Return Rigid Body kinetic energy. $(TYPEDSIGNATURES) """ -function kinetic_energy_rotation(body::AbstractRigidBody) - (;inertia) = body.prop - (;R,ω) = body.state - Ω = inv(R)*ω - T = 1/2*transpose(Ω)*inertia*Ω +function kinetic_energy(body::AbstractRigidBody{2,T}) where T + (;prop,state) = body + (;mass,mass_locus,inertia) = prop + o = zero(T) + i = one(T) + M = Diagonal(mass.*ones(3)) + c = vcat( + mass_locus.position, + o + ) + MS = M*skew(c) + + I3 = SMatrix{3,3}( + [ + inertia[1,1] inertia[1,2] o; + inertia[2,1] inertia[2,2] o; + o o inertia[1,1]+inertia[2,2]; + ] + ) + + inertia_tensor = [ + M -MS; + MS I3 + M*skew(c)*skew(c)' + ] + + origin_frame_3d = CartesianFrame{3}(state.origin_frame) + + R = origin_frame_3d.axes.X + Ω = origin_frame_3d.local_angular_velocity + v = origin_frame_3d.velocity + V = transpose(R)*v + + η = vcat( + V, + Ω + ) + + 0.5η'*inertia_tensor*η + +end + +function kinetic_energy( + coords::NonminimalCoordinates{<:NCF.NC},cache, + state::RigidBodyState, + prop::RigidBodyProperty, + q,q̇, + ) + (;M) = cache.inertia_cache + T = 1/2*transpose(q̇)*M*q̇ end """ Return Rigid Body gravity potential energy. $(TYPEDSIGNATURES) """ +function potential_energy_gravity(body::RigidBody) + (;mass) = body.prop + (;mass_locus_state) = body.state + gravity_acceleration = get_gravity(body) + -transpose(mass_locus_state.frame.position)*gravity_acceleration*mass +end + function potential_energy_gravity(body::AbstractRigidBody) (;mass) = body.prop (;mass_locus_state) = body.state diff --git a/src/postprocess/analysis.jl b/src/postprocess/analysis.jl index 819a6f0..046e339 100644 --- a/src/postprocess/analysis.jl +++ b/src/postprocess/analysis.jl @@ -143,6 +143,45 @@ function get_angular_velocity!(bot::Robot,bodyid::Int,step_range=:) angular_velocity_traj[step_range] |> VectorOfArray end +function get_kinetic_energy!(bot::Robot,bodyid::Int,step_range=:) + (; structure, traj)= bot + (; t, q, q̇) = traj + T = get_numbertype(bot) + N = get_num_of_dims(bot) + KE = [ + zero(T) + for _ in eachindex(traj) + ] + bodies = get_bodies(structure) + body = bodies[bodyid] + for (i,(qₖ,q̇ₖ)) in enumerate(zip(q, q̇)) + update_bodies!(structure,qₖ,q̇ₖ) + KE[i] = kinetic_energy(body,) + end + KE[step_range] +end + +function get_kinetic_energy_coords!(bot::Robot,bodyid::Int,step_range=:) + (; structure, traj)= bot + (; t, q, q̇) = traj + T = get_numbertype(bot) + N = get_num_of_dims(bot) + KE = [ + zero(T) + for _ in eachindex(traj) + ] + bodies = get_bodies(structure) + body = bodies[bodyid] + for (i,(qₖ,q̇ₖ)) in enumerate(zip(q, q̇)) + update_bodies!(structure,qₖ,q̇ₖ) + KE[i] = kinetic_energy_coords(body, + structure.state.members[bodyid].q, + structure.state.members[bodyid].q̇, + ) + end + KE[step_range] +end + function get_mid_times(bot::Robot) (;t) = bot.traj (t[begin+1:end] .+ t[begin:end-1])./2 diff --git a/src/postprocess/vis.jl b/src/postprocess/vis.jl index 0d0745e..397dbc4 100644 --- a/src/postprocess/vis.jl +++ b/src/postprocess/vis.jl @@ -21,10 +21,12 @@ MakieCore.@recipe(Viz, structure) do scene refcolor=:lightgrey, cablewidth=0.6, meshcolor=:slategrey, - fontsize = 15, + fontsize = 12, + linewidth = 1, ) end +# AbstractBody function MakieCore.plot!(viz::Viz{Tuple{S}}; ) where S <:AbstractBody body_ob = viz[:structure] @@ -75,7 +77,7 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; build_mesh(body_ob,color=viz.meshcolor[]) end if viz.showwire[] - strokewidth = linewidth + strokewidth = viz.linewidth[] else strokewidth = 0 end @@ -83,13 +85,14 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; MakieCore.mesh!(viz, meshes_ob; shading = MakieCore.Automatic()) else MakieCore.poly!(viz, meshes_ob; shading = MakieCore.Automatic(), - # strokewidth + strokewidth ) end end viz end +# ClusterJoint function MakieCore.plot!(viz::Viz{Tuple{S}}; ) where {S<:Apparatus{<:ClusterJoint}} cluster_cable_ob = viz[:structure] @@ -112,6 +115,7 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; end end +# CableJoint function MakieCore.plot!(viz::Viz{Tuple{S}}; ) where {S<:Apparatus{<:CableJoint}} cable_appar_ob = viz[:structure] @@ -165,6 +169,7 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; viz end +# AbstractStructure function MakieCore.plot!(viz::Viz{Tuple{S}}; ) where S <:AbstractStructure if viz.isref[] @@ -245,7 +250,7 @@ function MakieCore.plot!(viz::Viz{Tuple{S}}; meshcolor, pointcolor = viz.pointcolor[], showmesh = viz.showmesh[], - # showwire = viz.showwire[], + showwire = viz.showwire[], ) end end @@ -286,18 +291,18 @@ end function make_patch(;trans=[0.0,0,0],rot=RotX(0.0),scale=1,color=:slategrey) parsedcolor = parse(CT.RGBA{Float32},color) - function patch(mesh) + function patch(mesh::GB.Mesh{Dim,T}) where {Dim,T} ct = Translation(trans) ∘ LinearMap(rot) updated_pos = ct.(mesh.position.*scale) fac = GB.faces(mesh) - nls = GB.normals(updated_pos,fac) + nls = GB.normals(updated_pos,fac;normaltype=GB.Vec{Dim,Float32}) colors = fill(parsedcolor,length(updated_pos)) GB.Mesh(GB.meta(updated_pos,normals=nls,color=colors),fac) end end function get_groundmesh(f::Function,rect) - GeometryBasics.Mesh(f, rect, NaiveSurfaceNets()) |> make_patch(;color = :snow) + GB.Mesh(f, rect, Meshing.MarchingCubes()) |> make_patch(;color = :snow) end function get_groundmesh(plane::Plane,rect) @@ -349,16 +354,16 @@ function get_groundmesh(::Nothing,rect) end function get_linesegs_cables(structure;slackonly=false,noslackonly=false) - (;connected) = structure.connectivity.tensioned - (;cables) = structure.apparatuses + cables = get_cables(structure) ndim = get_num_of_dims(structure) T = get_numbertype(structure) - linesegs_cables = Vector{Tuple{Point{ndim,T},Point{ndim,T}}}() - foreach(connected) do scnt - scable = cables[scnt.id] - ret = (Point(scnt.hen.body.state.loci_states[scnt.hen.pid].position), - Point(scnt.egg.body.state.loci_states[scnt.egg.pid].position)) - slacking = scable.state.tension <= 0 + linesegs_cables = Vector{Tuple{GB.Point{ndim,T},GB.Point{ndim,T}}}() + foreach(cables) do cable + force = cable.force + (;hen,egg) = cable.joint.hen2egg + ret = (GB.Point(hen.body.state.loci_states[hen.pid].frame.position), + GB.Point(egg.body.state.loci_states[egg.pid].frame.position)) + slacking = force.state.tension <= 0 if (slackonly && slacking) || (noslackonly && !slacking) || (!slackonly && !noslackonly) diff --git a/src/structures/linearization.jl b/src/structures/linearization.jl index 4de3cec..23fbdea 100644 --- a/src/structures/linearization.jl +++ b/src/structures/linearization.jl @@ -217,77 +217,77 @@ end function build_material_stiffness_matrix!(st::Structure,q,k) (;num_of_dim) = st - (;indexed,tensioned) = st.connectivity + (;indexed,) = st.connectivity (;num_of_full_coords,num_of_free_coords,sys_free_coords_idx,bodyid2sys_full_coords) = indexed - (;connected) = tensioned - (;cables) = st.apparatuses update!(st,q) Jj = zeros(eltype(q),num_of_dim,num_of_full_coords) retǨm = zeros(eltype(q),num_of_free_coords,num_of_free_coords) - foreach(connected) do scnt - j = scnt.id - rb1 = scnt.hen.body - rb2 = scnt.egg.body - ap1id = scnt.hen.pid - ap2id = scnt.egg.pid - C1 = rb1.cache.Cps[ap1id] - C2 = rb2.cache.Cps[ap2id] - mfull1 = bodyid2sys_full_coords[rb1.prop.id] - mfull2 = bodyid2sys_full_coords[rb2.prop.id] - cable = cables[j] - (;state) = cable - (;length,) = state - s = 1/length - Jj .= 0 - Jj[:,mfull2] .+= C2 - Jj[:,mfull1] .-= C1 - Uj = transpose(Jj)*Jj - Ūjq = Uj[sys_free_coords_idx,:]*q - retǨm .+= k[j]*s^2*(Ūjq*transpose(Ūjq)) + foreach(st.apparatuses) do appar + if appar.joint isa CableJoint + j = appar.id + (;force,joint) = appar + (;hen,egg) = joint.hen2egg + rb1 = hen.body + rb2 = egg.body + ap1id = hen.pid + ap2id = egg.pid + C1 = rb1.cache.Cps[ap1id] + C2 = rb2.cache.Cps[ap2id] + mfull1 = bodyid2sys_full_coords[rb1.prop.id] + mfull2 = bodyid2sys_full_coords[rb2.prop.id] + (;state) = force + (;length,) = state + s = 1/length + Jj .= 0 + Jj[:,mfull2] .+= C2 + Jj[:,mfull1] .-= C1 + Uj = transpose(Jj)*Jj + Ūjq = Uj[sys_free_coords_idx,:]*q + retǨm .+= k[j]*s^2*(Ūjq*transpose(Ūjq)) + end end retǨm end function build_geometric_stiffness_matrix!(st::Structure,q,f) (;num_of_dim) = st - (;indexed,tensioned) = st.connectivity + (;indexed,) = st.connectivity (;num_of_full_coords,num_of_free_coords,sys_free_coords_idx,bodyid2sys_full_coords) = indexed - (;connected) = tensioned - (;cables) = st.apparatuses update!(st,q) Jj = zeros(eltype(q),num_of_dim,num_of_full_coords) retǨg = zeros(eltype(q),num_of_free_coords,num_of_free_coords) - foreach(connected) do scnt - j = scnt.id - rb1 = scnt.hen.body - rb2 = scnt.egg.body - ap1id = scnt.hen.pid - ap2id = scnt.egg.pid - C1 = rb1.cache.Cps[ap1id] - C2 = rb2.cache.Cps[ap2id] - mfull1 = bodyid2sys_full_coords[rb1.prop.id] - mfull2 = bodyid2sys_full_coords[rb2.prop.id] - cable = cables[j] - (;state) = cable - (;length,) = state - s = 1/length - Jj .= 0 - Jj[:,mfull2] .+= C2 - Jj[:,mfull1] .-= C1 - Uj = transpose(Jj)*Jj - Ǔj = @view Uj[sys_free_coords_idx,sys_free_coords_idx] - Ūjq = Uj[sys_free_coords_idx,:]*q - retǨg .+= f[j]/length*(Ǔj-s^2*Ūjq*transpose(Ūjq)) + foreach(st.apparatuses) do appar + if appar.joint isa CableJoint + j = appar.id + (;force,joint) = appar + (;hen,egg) = joint.hen2egg + rb1 = hen.body + rb2 = egg.body + ap1id = hen.pid + ap2id = egg.pid + C1 = rb1.cache.Cps[ap1id] + C2 = rb2.cache.Cps[ap2id] + mfull1 = bodyid2sys_full_coords[rb1.prop.id] + mfull2 = bodyid2sys_full_coords[rb2.prop.id] + (;state) = force + (;length,) = state + s = 1/length + Jj .= 0 + Jj[:,mfull2] .+= C2 + Jj[:,mfull1] .-= C1 + Uj = transpose(Jj)*Jj + Ǔj = @view Uj[sys_free_coords_idx,sys_free_coords_idx] + Ūjq = Uj[sys_free_coords_idx,:]*q + retǨg .+= f[j]/length*(Ǔj-s^2*Ūjq*transpose(Ūjq)) + end end retǨg end function make_Ǩm_Ǩg(st,q0) (;num_of_dim) = st - (;numbered,indexed,tensioned) = st.connectivity + (;numbered,indexed,) = st.connectivity (;num_of_full_coords,num_of_free_coords,sys_pres_coords_idx,sys_free_coords_idx,bodyid2sys_full_coords) = indexed - (;connected) = tensioned - (;cables) = st.apparatuses (;bodyid2sys_loci_idx,sys_loci2coords_idx) = numbered function inner_Ǩm_Ǩg(q̌,s,μ,k,c) q = Vector{eltype(q̌)}(undef,num_of_full_coords) @@ -296,14 +296,15 @@ function make_Ǩm_Ǩg(st,q0) Jj = zeros(eltype(q̌),num_of_dim,num_of_full_coords) retǨm = zeros(eltype(q̌),num_of_free_coords,num_of_free_coords) retǨg = zeros(eltype(q̌),num_of_free_coords,num_of_free_coords) - foreach(connected) do scnt - j = scnt.id - rb1 = scnt.hen.body - rb2 = scnt.egg.body + foreach(st.apparatuses) do appar + j = appar.id + (;hen,egg) = appar.joint.hen2egg + rb1 = hen.body + rb2 = egg.body rb1id = rb1.prop.id rb2id = rb2.prop.id - ap1id = scnt.hen.pid - ap2id = scnt.egg.pid + ap1id = hen.pid + ap2id = egg.pid c1 = c[sys_loci2coords_idx[bodyid2sys_loci_idx[rb1id][ap1id]]] c2 = c[sys_loci2coords_idx[bodyid2sys_loci_idx[rb2id][ap2id]]] C1 = rb1.state.cache.funcs.C(c1) @@ -328,18 +329,19 @@ function make_Ǩm_Ǩg(st,q0) Jj = zeros(eltype(q̌),num_of_dim,num_of_full_coords) retǨm = zeros(eltype(q̌),num_of_free_coords,num_of_free_coords) retǨg = zeros(eltype(q̌),num_of_free_coords,num_of_free_coords) - foreach(connected) do scnt - j = scnt.id - rb1 = scnt.hen.body - rb2 = scnt.egg.body - ap1id = scnt.hen.pid - ap2id = scnt.egg.pid + foreach(st.apparatuses) do appar + j = appar.id + (;force,joint) = appar + (;hen,egg) = joint.hen2egg + rb1 = hen.body + rb2 = egg.body + ap1id = hen.pid + ap2id = egg.pid C1 = rb1.state.cache.Cps[ap1id] C2 = rb2.state.cache.Cps[ap2id] mfull1 = bodyid2sys_full_coords[rb1.prop.id] mfull2 = bodyid2sys_full_coords[rb2.prop.id] - cable = cables[j] - (;k,c,state,slack) = cable + (;k,c,state,slack) = force (;direction,tension,length,lengthdot) = state s = 1/length Jj .= 0 @@ -357,10 +359,9 @@ end function make_S(st,q0) (;num_of_dim) = st - (;numbered,indexed,tensioned) = st.connectivity + (;numbered,indexed,) = st.connectivity (;sys_pres_coords_idx,sys_free_coords_idx,num_of_full_coords,bodyid2sys_full_coords) = indexed (;bodyid2sys_loci_idx,sys_loci2coords_idx) = numbered - (;connected) = tensioned (;cables) = st.apparatuses ncables = length(cables) function inner_S(q̌,s) @@ -369,14 +370,16 @@ function make_S(st,q0) q[sys_free_coords_idx] .= q̌ ret = zeros(eltype(q̌),ncables) Jj = zeros(eltype(q̌),num_of_dim,num_of_full_coords) - foreach(connected) do scnt - j = scnt.id - rb1 = scnt.hen.body - rb2 = scnt.egg.body + foreach(st.apparatuses) do appar + j = appar.id + (;force,joint) = appar + (;hen,egg) = joint.hen2egg + rb1 = hen.body + rb2 = egg.body rb1id = rb1.prop.id rb2id = rb2.prop.id - ap1id = scnt.hen.pid - ap2id = scnt.egg.pid + ap1id = hen.pid + ap2id = egg.pid # c1 = c[sys_loci2coords_idx[bodyid2sys_loci_idx[rb1id][ap1id]]] # c2 = c[sys_loci2coords_idx[bodyid2sys_loci_idx[rb2id][ap2id]]] # C1 = rb1.state.cache.funcs.C(c1) @@ -399,14 +402,15 @@ function make_S(st,q0) q[sys_free_coords_idx] .= q̌ ret = zeros(eltype(q̌),ncables) Jj = zeros(eltype(q̌),num_of_dim,num_of_full_coords) - foreach(connected) do scnt - j = scnt.id - rb1 = scnt.hen.body - rb2 = scnt.egg.body + foreach(st.apparatuses) do appar + j = appar.id + (;hen,egg) = appar.joint.hen2egg + rb1 = hen.body + rb2 = egg.body rb1id = rb1.prop.id rb2id = rb2.prop.id - ap1id = scnt.hen.pid - ap2id = scnt.egg.pid + ap1id = hen.pid + ap2id = egg.pid c1 = c[sys_loci2coords_idx[bodyid2sys_loci_idx[rb1id][ap1id]]] c2 = c[sys_loci2coords_idx[bodyid2sys_loci_idx[rb2id][ap2id]]] C1 = rb1.state.cache.funcs.C(c1) @@ -433,6 +437,11 @@ function build_tangent_stiffness_matrix!(∂Q̌∂q̌,appar::Apparatus,st::Abstr #default do nothing end + +function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::GravitationalRigidBody,st::AbstractStructure,q,s=nothing) + field_jacobian!(∂Q̌∂q̌,body,st) +end + function build_tangent_stiffness_matrix!(∂Q̌∂q̌,body::FlexibleBody,st::AbstractStructure,q,s=nothing) (;coords,cache) = body (;e,) = cache @@ -756,7 +765,6 @@ function build_tangent_damping_matrix!(∂Q̌∂q̌̇,st) end end - function init_cluster_matrix(st) (; bodies, apparatuses, connectivity) = st (; indexed, numbered) = connectivity @@ -948,14 +956,17 @@ end function build_Ǩ(st) _,λ = check_static_equilibrium_output_multipliers(st) - build_Ǩ(st,λ) + q = get_coords(st) + build_Ǩ(st,q,λ) end -function build_Ǩ(st,λ) +function build_Ǩ(st,q,λ) (;num_of_free_coords) = st.connectivity.indexed T = get_numbertype(st) - # Ǩ = zeros(T,num_of_free_coords,num_of_free_coords) - Ǩ = -build_tangent_stiffness_matrix(st) .- cstr_forces_jacobian(st,λ) + ǨmǨg = zeros(T,num_of_free_coords,num_of_free_coords) + build_tangent_stiffness_matrix!(ǨmǨg,st) + Ǩa = cstr_forces_jacobian(st,q,λ) + Ǩ = - ǨmǨg .- Ǩa # Ǩ .= Ǩ Ǩ end @@ -975,7 +986,7 @@ function undamped_eigen(st;gravity=false) q = get_coords(st) q̌ = get_free_coords(st) M̌ = assemble_M̌(st) - Ǩ = build_Ǩ(st,λ) + Ǩ = build_Ǩ(st,q,λ) Ǎ = make_cstr_jacobian(st)(q) Ň = nullspace(Ǎ) ℳ = transpose(Ň)*M̌*Ň diff --git a/src/structures/mutate.jl b/src/structures/mutate.jl index a88d753..029be87 100644 --- a/src/structures/mutate.jl +++ b/src/structures/mutate.jl @@ -227,7 +227,7 @@ function move_rigids!(st) (;bodies,state) = st foreach(bodies) do body bodyid = body.prop.id - (;q,q̇) = state.parts[bodyid] + (;q,q̇) = state.members[bodyid] update_loci_states!(body,q,q̇) end end @@ -314,10 +314,71 @@ end """ $(TYPEDSIGNATURES) """ -function apply_gravity!(st;factor=1) - (;bodies) = st - gravity_acceleration = factor*get_gravity(st) +function apply_field!(st::AbstractStructure;factor=1) + (;bodies,state) = st + foreach(bodies) do body + (;id) = body.prop + state.members[id].q + apply_field!( + state.members[id].F, + body, + state.members[id].q; + factor + ) + end +end + +function apply_field!(F,body::RigidBody,q;factor=1) + gravity_acceleration = factor*get_gravity(body) + (;Cps,Cg,inertia_cache) = cache + f_gra = gravity_acceleration*body.prop.mass + mul!(F,transpose(Cg),f_gra,1,1) +end + +function apply_field!(F,body::GravitationalRigidBody,q;factor=1) + nmcs = body.coords.nmcs + m = body.prop.mass + Ī = body.prop.inertia + r̄g = body.prop.mass_locus.position + rg = body.state.mass_locus_state.frame.position + + F_gra = NCF.gravitational_force(nmcs,m,Ī,r̄g,rg,q) + ## @show size(F_gra) + F .+= F_gra +end + +""" +$(TYPEDSIGNATURES) +""" +function field_jacobian!(∂F∂q, st::AbstractStructure;factor=1) + (;bodies,state,connectivity) = st + (; + bodyid2sys_free_coords_idx, + bodyid2sys_full_coords_idx, + ) = connectivity.indexed foreach(bodies) do body - body.state.mass_locus_state.force .+= gravity_acceleration*body.prop.mass + (;id) = body.prop + state.members[id].q + field_jacobian!( + (@view ∂F∂q[bodyid2sys_free_coords_idx,bodyid2sys_free_coords_idx]), + body, + state.members[id].q; + factor + ) end end + +function field_jacobian!(∂F̌∂q̌,body::RigidBody,q;factor=1) +end + +function field_jacobian!(∂F̌∂q̌,body::GravitationalRigidBody,q;factor=1) + nmcs = body.coords.nmcs + m = body.prop.mass + Ī = body.prop.inertia + r̄g = body.prop.mass_locus.position + rg = body.state.mass_locus_state.frame.position + + ## @show size(∂f∂q) + ∂F̌∂q̌ .+= NCF.gravitational_force_jacobian(nmcs,m,Ī,r̄g,rg) +end + diff --git a/src/structures/structure.jl b/src/structures/structure.jl index 0e4229f..0dd360f 100644 --- a/src/structures/structure.jl +++ b/src/structures/structure.jl @@ -39,16 +39,15 @@ function StructureState(bodies,apparatuses,cnt::Connectivity) end T = get_numbertype(bodies) t = zero(T) - q = Vector{T}(undef,num_of_full_coords) + q = zeros(T,num_of_full_coords) q̇ = zero(q) q̈ = zero(q) F = zero(q) - λ = Vector{T}(undef,num_of_cstr) - # s = Vector{T}(undef,num_of_add_var) - s = zeros(T, num_of_add_var) - c = get_local_coords(bodies,numbered) + λ = zeros(T,num_of_cstr) + s = zeros(T,num_of_add_var) p = zero(q) - p̌ = Vector{T}(undef,num_of_free_coords) + p̌ = zeros(T,num_of_free_coords) + c = get_local_coords(bodies,numbered) system = NonminimalCoordinatesState(t,q,q̇,q̈,F,p,p̌,λ,s,sys_free_coords_idx,sys_pres_coords_idx,c) members = [ begin @@ -131,7 +130,7 @@ function update!(st::AbstractStructure; gravity=false) update_bodies!(st) update_apparatuses!(st) if gravity - apply_gravity!(st) + apply_field!(st) end assemble_forces!(st) end @@ -141,7 +140,7 @@ function lazy_update!(st::AbstractStructure; gravity=false) lazy_update_bodies!(st) update_apparatuses!(st) if gravity - apply_gravity!(st) + apply_field!(st) end assemble_forces!(st) end @@ -516,8 +515,6 @@ function make_auxi_jacobian(structure::AbstractStructure,s0) # @show maximum(∂ζ∂q) ∂ζ∂s = reduce(blockdiag, A_list) - # @show Tb - # @show ∂ζ∂s ∂S∂q .= 1/2 * coζ*∂ζ∂q ∂S∂s .= 1/2 *coζ*∂ζ∂s + cos̄*I @@ -604,51 +601,6 @@ function make_cstr_jacobian(structure::AbstractStructure,q0::AbstractVector) end -function build_ψ_hole(structure::AbstractStructure) - (;apparatuses) = structure - nholes = 0 - nh = 0 - FB = FischerBurmeister(1e-14, 10., 10.) - foreach(apparatuses) do appar - if isa(appar, Apparatus{<:ClusterJoint}) - nholes += 1 - nh += length(appar.joint.sps) - end - end - function _inner_ψ(s̄) - ψ = Vector{eltype(s̄)}(undef,2nh) - ψ⁺ = @view ψ[begin:2:end] - ψ⁻ = @view ψ[begin+1:2:end] - s⁺ = @view s̄[begin:2:end] - s⁻ = @view s̄[begin+1:2:end] - ih = 0 - foreach(apparatuses) do appar - if isa(appar, Apparatus{<:ClusterJoint}) - (;sps) = appar.joint - (;segs) = appar.force - nsi = length(sps) - for (i, sp) in enumerate(sps) - Fₙ = norm(segs[i+1].force.state.force + segs[i].force.state.force) - Fᵢ₊₁ = segs[i+1].force.state.tension - Fᵢ = segs[i].force.state.tension - ζ⁺ = sp.μ*Fₙ - Fᵢ₊₁ + Fᵢ - ζ⁻ = Fᵢ₊₁ - Fᵢ + sp.μ*Fₙ - ψ⁺[ih+i] = FB(ζ⁺, s⁺[ih+i]) - ψ⁻[ih+i] = FB(ζ⁻, s⁻[ih+i]) - # @show ζ⁺, ζ⁻ - end - ih += nsi - end - end - ψ - end - - function inner_ψ(s̄) - _inner_ψ(s̄) - end - inner_ψ -end - function build_F̌(st,bodyid,pid,f) T = get_numbertype(st) (;num_of_free_coords,bodyid2sys_free_coords) = st.connectivity.indexed @@ -710,7 +662,7 @@ function check_jacobian_singularity(st) A_body = cstr_jacobian(body.coords,q_body) body_rank = rank(A_body) if body_rank < minimum(size(A_body)) - @warn "The $(bodyid)th body's Jacobian is singular: rank(A(q))=$(body_rank)<$(minimum(size(A_rb)))" + @warn "The $(bodyid)th body's Jacobian is singular: rank(A(q))=$(body_rank)<$(minimum(size(A_body)))" end end end diff --git a/test/Project.toml b/test/Project.toml index faf8308..52f1b50 100644 --- a/test/Project.toml +++ b/test/Project.toml @@ -73,6 +73,7 @@ Revise = "295af30f-e4ad-537b-8983-00126c2a3abe" Rotations = "6038ab10-8711-5258-84ad-4b1120ba62dc" RowEchelon = "af85af4c-bcd5-5d23-b03a-a909639aa875" SafeTestsets = "1bc83da4-3b8d-516f-aca4-4fe02f6d838f" +SatelliteToolbox = "6ac157d9-b43d-51bb-8fab-48bf53814f4a" Setfield = "efcf1570-3423-57d1-acb7-fd33fddbac46" SparseArrays = "2f01184e-e22b-5df5-ae63-d93ebab69eaf" StaticArrays = "90137ffa-7385-5640-81b9-e52037218182" @@ -92,5 +93,4 @@ XLSX = "fdbf4ff8-1666-58a4-91e7-1b58723a45e0" Zygote = "e88e6eb3-aa80-5325-afca-941959d7151f" [compat] -Makie = "0.20" julia = "1.9" diff --git a/test/vis.jl b/test/vis.jl index a107e66..c57ec89 100644 --- a/test/vis.jl +++ b/test/vis.jl @@ -170,11 +170,14 @@ function plot_traj!(bot::RB.Robot; xlims=(-1.0,1.0), ylims=(-1.0,1.0), zlims=(-1e-3,1.0), + show_axis = true, showground=true, ground=nothing, showback=false, actuate=false, figname=nothing, + rowgap=0, + colgap=0, showinit=false, auto=false, titleformatfunc = (subgrid_idx,tt)-> begin @@ -207,7 +210,7 @@ function plot_traj!(bot::RB.Robot; 1 for subgrid_idx in eachindex(subgrids) ] (a,b::Nothing) => [ - time2step(a[subgrid_idx],traj.t) + RB.time2step(a[subgrid_idx],traj.t) for subgrid_idx in eachindex(subgrids) ] (a::Nothing,b) => b @@ -244,44 +247,17 @@ function plot_traj!(bot::RB.Robot; aspect=:data, # tellheight=false, ) - # scale = 1e3 - # m0_yellow = load("yard/jixiebi/m0_yellow.STL") |> RB.make_patch(;rot=RotY(pi/2),trans=[-0.50, 0.0, 0.8],scale=1/scale,color=:yellow) - # m0_blue1 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2), trans=[-0.5,0.23,0.37], scale=1/scale,color=:blue) - # m0_blue2 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2), trans=[0.5,0.23,0.37], scale=1/scale,color=:blue) - # m0_blue3 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2)*RotX(-pi/2), trans=[-0.23,0.5,0.37], scale=1/scale,color=:blue) - # m0_blue4 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2)*RotX(-pi/2), trans=[-0.23,-0.5,0.37], scale=1/scale,color=:blue) - # mesh!(ax, m0_yellow) - # mesh!(ax, m0_blue1) - # mesh!(ax, m0_blue2) - # mesh!(ax, m0_blue3) - # mesh!(ax, m0_blue4) - # hidezdecorations!(ax) - # hideydecorations!(ax) - xlims!(ax,xmin,xmax) ylims!(ax,ymin,ymax) zlims!(ax,zmin,zmax) elseif AxisType <: LScene showinfo = false # ax = LScene(fig[1,1], show_axis=false, scenekw = (clear=true,)) - ax = LScene(fig[1,1],) # - cam = Makie.camera(ax.scene) - cam = cam3d!(ax.scene, projectiontype=Makie.Orthographic) - update_cam!(ax.scene, cam, pi/2, pi/8) - - # update_cam!(ax.scene, cam, pi/5, pi/12) + ax = LScene(fig[1,1], show_axis=show_axis, scenekw = (show_axis = show_axis,)) # + # cam = Makie.camera(ax.scene) + # cam = cam3d!(ax.scene, projectiontype=Makie.Orthographic) + # update_cam!(ax.scene, cam) # ax = LScene(fig[1,1],show_axis=false) # - # scale = 1e3 - # m0_yellow = load("yard/jixiebi/m0_yellow.STL") |> RB.make_patch(;rot=RotY(pi/2),trans=[-0.50, 0.0, 0.8],scale=1/scale,color=:yellow) - # m0_blue1 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2), trans=[-0.5,0.23,0.37], scale=1/scale,color=:blue) - # m0_blue2 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2), trans=[0.5,0.23,0.37], scale=1/scale,color=:blue) - # m0_blue3 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2)*RotX(-pi/2), trans=[-0.23,0.5,0.37], scale=1/scale,color=:blue) - # m0_blue4 = load("yard/jixiebi/m0_blue.STL") |> RB.make_patch(;rot=RotY(pi/2)*RotX(-pi/2), trans=[-0.23,-0.5,0.37], scale=1/scale,color=:blue) - # mesh!(ax, m0_yellow) - # mesh!(ax, m0_blue1) - # mesh!(ax, m0_blue2) - # mesh!(ax, m0_blue3) - # mesh!(ax, m0_blue4) else error("Unknown AxisType") end @@ -348,7 +324,7 @@ function plot_traj!(bot::RB.Robot; "fig. height" => map(string,ax.height), "fig. width" => map(string,ax.width) ] - if ndim == 3 && AxisType == Axis3 + if AxisType == Axis3 cam_info = [ "azimuth" => map(string,ax.azimuth), "elevation" => map(string,ax.elevation) @@ -379,7 +355,7 @@ function plot_traj!(bot::RB.Robot; framerate = 30 skipstep = round(Int,1/framerate/dt*speedup) recordsteps = 1:skipstep:length(traj.t) - record(fig, figname, recordsteps; + record(fig, figname, recordsteps; px_per_unit = 2, framerate) do this_step @show this_step / length(traj.t) if actuate @@ -422,15 +398,17 @@ function plot_traj!(bot::RB.Robot; end end end + colgap!(grid1,colgap) + rowgap!(grid1,rowgap) end - if fig isa Figure + if (fig isa Figure) && !dorecord savefig(fig,figname) DataInspector(fig) end fig end -function savefig(fig,figname=nothing;backend=GM) +function savefig(fig,figname=nothing;backend=Makie.current_backend()) if !isa(figname,Nothing) if isdefined(Main,:figdir) figpath = joinpath(figdir,figname) diff --git a/yard/DualTriangles/static_stability.jl b/yard/DualTriangles/static_stability.jl index 54e2701..94e9abf 100644 --- a/yard/DualTriangles/static_stability.jl +++ b/yard/DualTriangles/static_stability.jl @@ -103,7 +103,7 @@ function free(bot) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_strings_apply_forces!(st) - # RB.apply_gravity!(st) + # RB.apply_field!(st) RB.assemble_forces!(F,st) # @show isapprox(F,Q̃*RB.fvector(st)) end diff --git a/yard/ES/main.jl b/yard/ES/main.jl index de102e8..68a18a1 100644 --- a/yard/ES/main.jl +++ b/yard/ES/main.jl @@ -1916,7 +1916,7 @@ S,D = RB.static_kinematic_determine(ℬᵀ) ns = size(S,2) nk = size(D,2) -λ = -inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f +λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f Ǩa = RB.cstr_forces_jacobian(bot.st,λ) 𝒦a = transpose(Ň)*Ǩa*Ň |> Symmetric vals_𝒦a,vecs_𝒦a = eigen(𝒦a) diff --git a/yard/EWei/main.jl b/yard/EWei/main.jl index f6b40b2..9514b17 100644 --- a/yard/EWei/main.jl +++ b/yard/EWei/main.jl @@ -1,47 +1,38 @@ -using LinearAlgebra -using SparseArrays -using StaticArrays -using BenchmarkTools -using FileIO, MeshIO -using Printf -using Makie -import GLMakie as GM -import CairoMakie as CM -GM.activate!() -using Unitful -using NLsolve -using Revise -using StructArrays -using EponymTuples -using LaTeXStrings -using StaticArrays -using GeometryBasics -using Rotations -using CoordinateTransformations -using Meshing -using TypeSortedCollections -using Match + +using Revise #jl import Rible as RB -cd("examples/EWei") -includet("define.jl") -includet("../vis.jl") + +include(joinpath(pathof(RB),"../../yard/stability_stiffness.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = "" + +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/robots/EWei.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/EWei.jl")) #jl + bot1 = BuildTail() bot1 = BuildTail(1; β=.9) # rigid body mesh -RB.update!(bot1.st) -RB.update_orientations!(bot1.st) -rbs = RB.get_bodies(bot1.st) -rbs[5].state.R -rbs[5].state.cache.funcs.nmcs -plot_rigid(rbs[2];showmesh=true,showupdatemesh=false) +RB.update!(bot1.structure) +rbs = RB.get_bodies(bot1.structure) +rbs[5].state.origin_frame.axes +rbs[5].coords.nmcs +RB.viz(rbs[2];showmesh=true,showupdatemesh=false) # linearized dynamics -ω², δq̌ = RB.undamped_eigen(bot1.st) +ω², δq̌ = RB.undamped_eigen(bot1.structure) @show ω = [sqrt(ωi) for ωi in ω²[1:end]] +plot_traj!(bot1) + # nonlinear dynamics function dynfuncs(bot) (;st) = bot @@ -50,7 +41,7 @@ function dynfuncs(bot) RB.update_bodies!(st,q,q̇) RB.distribute_s̄!(st,s) RB.update_apparatuses!(st) - ## RB.apply_gravity!(st) + ## RB.apply_field!(st) RB.assemble_forces!(st) RB.get_force!(F,st) ## F .= 0 diff --git a/yard/EWei/t2.jl b/yard/EWei/t2.jl index 873981b..78324dc 100644 --- a/yard/EWei/t2.jl +++ b/yard/EWei/t2.jl @@ -312,7 +312,7 @@ bot = RB.Robot(st, hub) # RB.update_bodies!(st,q,q̇) # RB.distribute_s̄!(st,s) # RB.update_apparatuses!(st) -# ## RB.apply_gravity!(st) +# ## RB.apply_field!(st) # RB.assemble_forces!(st) # RB.get_force!(F,st) # ## F .= 0 diff --git a/yard/EWei/test1.jl b/yard/EWei/test1.jl index fe61ed1..aac3fd3 100644 --- a/yard/EWei/test1.jl +++ b/yard/EWei/test1.jl @@ -128,7 +128,7 @@ plot_traj!(bot) # RB.clear_forces!(st) # RB.update_bodies!(st,q,q̇) # RB.update_apparatuses!(st) -# # RB.apply_gravity!(st) +# # RB.apply_field!(st) # RB.assemble_forces!(st) # RB.get_force!(F,st) # ## F .= 0 diff --git a/yard/LC/free_copy.jl b/yard/LC/free_copy.jl index bcb85ae..334c5e3 100644 --- a/yard/LC/free_copy.jl +++ b/yard/LC/free_copy.jl @@ -40,7 +40,7 @@ function simulate_freevibra(num_of_dof;k,c,unit="mks",dt=0.01) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_cables_apply_forces!(st) - # RB.apply_gravity!(st) + # RB.apply_field!(st) RB.assemble_forces!(F,st) # @show isapprox(F,Q̃*RB.fvector(st)) end diff --git a/yard/URDF/urdf.jl b/yard/URDF/urdf.jl index 6dc38a5..9c73053 100644 --- a/yard/URDF/urdf.jl +++ b/yard/URDF/urdf.jl @@ -586,7 +586,7 @@ function dynfuncs(bot) RB.clear_forces!(st) RB.update_rigids!(st,q,q̇) # RB.update_apparatuses!(st) - RB.apply_gravity!(st) + RB.apply_field!(st) F .= RB.generate_forces!(st) end function Jac_F!(∂F∂q̌,∂F∂q̌̇,q,q̇,t) diff --git a/yard/adjoint.jl b/yard/adjoint.jl index 5ce2207..253e015 100644 --- a/yard/adjoint.jl +++ b/yard/adjoint.jl @@ -33,7 +33,8 @@ import GeometryBasics as GB using Makie import GLMakie as GM import CairoMakie as CM -GM.activate!() +import WGLMakie as WM +WM.activate!() using LaTeXStrings using Meshing import Meshes diff --git a/yard/adjoint/diffcontact.jl b/yard/adjoint/diffcontact.jl new file mode 100644 index 0000000..302a680 --- /dev/null +++ b/yard/adjoint/diffcontact.jl @@ -0,0 +1,155 @@ +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/adjoint.jl")) + +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = joinpath(pathof(RB),"../../tmp") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl +tw = 455.8843 #pt |> pt2px +scalefactor = 4 + + +#-- cube +include(joinpath(pathof(RB),"../../examples/robots/cube.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/cube.jl"))#jl + +include(joinpath(pathof(RB),"../../examples/robots/pointmass.jl")); +includet(joinpath(pathof(RB),"../../examples/robots/pointmass.jl")) #jl + +#-- cube +cubebot = make_cube() +plot_traj!(cubebot;showwire=true) + +plane_env = RB.StaticContactSurfaces( + [ + RB.HalfSpace([0,0,1.0],[0,0,0.0]) + ] +) + +ros = [[0,0,z] for z = 10.0:-0.1:0.0] +qs = [ + begin + cube = make_cube(origin_position,RotXY(π/4,π/4)) + q = RB.get_coords(cube.structure) + end + for origin_position in ros +] +# p = RB.generalized_alpha(1.0) +Ro = [ + 0.368869 -0.824063 0.429949; + 0.769524 0.011314 -0.638518; + 0.521314 0.566385 0.63831 +] +origin_velocity = [0.0,0.0,0.0] +ωo = [3.0,4.0,5.0] +# cube = make_cube() +# cube = make_cube(ros[1]) +cube = make_cube(ros[2],Ro,origin_velocity,0.1.*ωo) +tspan = (0.0,1.91) +tspan = (0.0,5.0) +dt = 1e-3 + +prob = RB.DynamicsProblem( + cube, + plane_env, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ) +) +RB.solve!(prob, + RB.DynamicsSolver( + RB.Zhong06(), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ) + ); + tspan,dt,ftol=1e-10,maxiters=50,exception=false +) +RB.solve!(prob, + RB.DynamicsSolver( + RB.Zhong06(), + RB.MonolithicContactSolver( + RB.InteriorPointMethod() + ) + ); + tspan,dt,ftol=1e-10,maxiters=50,exception=false +) + +plot_traj!(cube; + xlims = [-10,10], + ylims = [-10,10], + zlims = [-1e-3,10], + showinfo=false, + showwire=true +) + +ME = RB.mechanical_energy!(cube) +lines(cube.traj.t,ME.E) + + + +# ground plane +θ=0.0 +ground_plane = RB.StaticContactSurfaces( + [ + RB.HalfSpace([-tan(θ),0,1],zeros(3)), + ] +); + +# time +tspan = (0.0,1.5) +h = 1e-3; + +# parameters and initial conditions +restitution_coefficients = [0.5] +v0s = [1.0]; + +# pointmass +pm = new_pointmass(; + e = restitution_coefficients[1], + μ=0.1, + origin_velocity = [v0s[1],0,0] +); + +# frictional contact dynamics problem +prob = RB.DynamicsProblem( + pm, + ground_plane, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ) +); + +# simulate +RB.solve!( + prob, + RB.DynamicsSolver( + RB.Zhong06(), + RB.MonolithicContactSolver( + RB.InteriorPointMethod() + ) + ); + tspan,dt=h, + ftol=1e-14, + maxiters=50, + exception=false +); + +GM.activate!(;scalefactor=2); plot_traj!( + pm, + xlims=(-1e-3,1.0), + ylims=(-0.4,0.4), + zlims=(-1e-3,1.0), + showinfo =false, + showmesh=false, + showwire=false, + showlabels=false, + showcables=false, + showpoints=true, +) \ No newline at end of file diff --git a/yard/gravitational/cube.jl b/yard/gravitational/cube.jl new file mode 100644 index 0000000..476825e --- /dev/null +++ b/yard/gravitational/cube.jl @@ -0,0 +1,176 @@ +using Revise #jl +import Rible as RB +include(joinpath(pathof(RB),"../../yard/tensegrity.jl")) + +using ForwardDiff +import SatelliteToolbox as ST + +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = joinpath(pathof(RB),"../../tmp") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl +tw = 455.8843 #pt |> pt2px +scalefactor = 4 + + +#-- cube +include(joinpath(pathof(RB),"../../examples/robots/cube.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/cube.jl"))#jl + +include(joinpath(pathof(RB),"../../examples/robots/pointmass.jl")); +includet(joinpath(pathof(RB),"../../examples/robots/pointmass.jl")) #jl + +#-- cube +cubebot = make_cube() +plot_traj!(cubebot;showwire=true) + +plane_env = RB.StaticContactSurfaces( + [ + RB.HalfSpace([0,0,1.0],[0,0,0.0]) + ] +) + +ros = [[0,0,z] for z = 10.0:-0.1:0.0] +qs = [ + begin + cube = make_cube(origin_position,RotXY(π/4,π/4)) + q = RB.get_coords(cube.structure) + end + for origin_position in ros +] + +Ro = [ + 0.368869 -0.824063 0.429949; + 0.769524 0.011314 -0.638518; + 0.521314 0.566385 0.63831 +] +origin_velocity = [0.0,0.0,0.0] +ωo = [3.0,4.0,5.0] +# cube = make_cube() +# cube = make_cube(ros[1]) +cube = make_cube(ros[2],Ro,origin_velocity,0.1.*ωo) +tspan = (0.0,1.91) +tspan = (0.0,5.0) +dt = 1e-3 + +prob = RB.DynamicsProblem( + cube, + plane_env, + RB.RestitutionFrictionCombined( + RB.NewtonRestitution(), + RB.CoulombFriction(), + ) +) +RB.solve!(prob, + RB.DynamicsSolver( + RB.Zhong06(), + RB.InnerLayerContactSolver( + RB.InteriorPointMethod() + ) + ); + tspan,dt,ftol=1e-10,maxiters=50,exception=false +) + + +ME = RB.mechanical_energy!(cube) +lines(cube.traj.t,ME.E) + +iss_tle = ST.tle""" + ISS (ZARYA) + 1 25544U 98067A 23138.86946505 -.00404279 00000+0 -74572-2 0 9994 + 2 25544 51.6431 113.8899 0006661 357.1286 88.0982 15.49924990397244""" +orbp = ST.Propagators.init(Val(:SGP4), iss_tle) +ST.Propagators.propagate_to_epoch!(orbp, ST.date_to_jd(2023, 5, 19, 12, 0, 0)) +kepler_elems = ST.Propagators.mean_elements(orbp) + +orbital_period = ST.orbital_period(kepler_elems) + +ro, vo = ST.Propagators.mean_elements(orbp) |> ST.kepler_to_rv +ro +vo + +Ro = [ + 0.368869 -0.824063 0.429949; + 0.769524 0.011314 -0.638518; + 0.521314 0.566385 0.63831 +] +ωo = [3.0,4.0,5.0] + +cube = make_cube(ro,Ro,vo,0.1.*ωo) + +tspan = (0.0,orbital_period) +dt = 1.0 + +prob = RB.DynamicsProblem( + cube, + RB.GravitationalEnv(), + ## RB.EmptyEnv() +) + +RB.solve!(prob, + RB.DynamicsSolver( + RB.Zhong06(), + ); + dt, + tspan,# = (0.0,2dt), + ftol=1e-9,maxiters=50,verbose=true,exception=true +) + +plot_traj!(cube; + xlims = [-10,10], + ylims = [-10,10], + zlims = [-1e-3,10], + showinfo=false, + showwire=true +) + +r1 = RB.get_trajectory!(cube,1,1) +lines(Matrix(r1)) + +q = RB.get_coords(cube.structure) +body = RB.get_bodies(cube)[1] +nmcs = body.coords.nmcs +m = body.prop.mass +Īₘ = body.prop.inertia +r̄ₘ = body.prop.mass_locus.position +rₘ = body.state.mass_locus_state.frame.position + +U_gra = RB.NCF.make_U(nmcs,m,Īₘ,r̄ₘ,q) +F_gra = RB.NCF.gravitational_force(nmcs,m,Īₘ,r̄ₘ,q) +∂F∂q_gra = RB.NCF.gravitational_force_jacobian(nmcs,m,Īₘ,r̄ₘ,q) +cond(∂F∂q_gra) + +M = RB.NCF.make_M(nmcs,m,Īₘ,r̄ₘ) + +re = q[1:3] + [1000.0,2000.0,3000.0] +rc = rₘ - re +q̂ = copy(q) +q̂[1:3] .-= re +q̂ + +qs = vcat(re,q̂) + +U_gra = RB.NCF.make_U_LACB(nmcs,m,Īₘ,r̄ₘ,re,q̂) + +F_gra_fd(_x) = ForwardDiff.gradient((x)-> RB.NCF.make_U_LACB(nmcs,m,Īₘ,r̄ₘ,x[1:3],x[4:end]),_x) +F_gra_Auto = F_gra_fd(qs) + +F_gra_LACB = RB.NCF.gravitational_force_LACB(nmcs,m,Īₘ,r̄ₘ,re,q̂) + +F_gra_Auto + F_gra_LACB + +∂F∂q_gra_fd(_x) = ForwardDiff.jacobian(F_gra_fd,_x) + +∂F∂q_gra_LACB = ∂F∂q_gra_fd(qs) + +cond(∂F∂q_gra_fd(qs)) + +M_LACB = RB.NCF.make_M_LACB(nmcs,m,Īₘ,r̄ₘ) + + +rank(M) +cond(Array(M)) + diff --git a/yard/jixiebi/Group2_1.jl b/yard/jixiebi/Group2_1.jl index 7b3f74e..ea8c419 100644 --- a/yard/jixiebi/Group2_1.jl +++ b/yard/jixiebi/Group2_1.jl @@ -34,7 +34,7 @@ rigid_contacts = RB.ContactRigidBodies( # RB.RigidCube(14) # RB.RigidSphere(14) ], - gravity=RB.NoGravity() + gravity=RB.NoField() ) # parameters diff --git a/yard/jixiebi/dyfun.jl b/yard/jixiebi/dyfun.jl index 2618efc..0a2cda5 100644 --- a/yard/jixiebi/dyfun.jl +++ b/yard/jixiebi/dyfun.jl @@ -5,7 +5,7 @@ function dynfuncs1(bot) TR.update_rigids!(tg,q,q̇) TR.distribute_s̄!(tg,s) TR.update_tensiles!(tg) - # TR.apply_gravity!(tg) + # TR.apply_field!(tg) TR.generate_forces!(tg) TR.get_force!(F,tg) end diff --git a/yard/links/dynamics.jl b/yard/links/dynamics.jl index 8cad4f9..9b51f79 100644 --- a/yard/links/dynamics.jl +++ b/yard/links/dynamics.jl @@ -51,7 +51,7 @@ function simulate_linkn(;dt=0.01,k=3e1,c=0.0,tend=10.0,verbose=false) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_strings_apply_forces!(st) - RB.apply_gravity!(st) + RB.apply_field!(st) # F .= Q̃*RB.fvector(st) RB.assemble_forces!(F,st) end diff --git a/yard/links/link2.jl b/yard/links/link2.jl index fc653b9..0995762 100644 --- a/yard/links/link2.jl +++ b/yard/links/link2.jl @@ -202,7 +202,7 @@ function inverse(tgstruct,refstruct) RB.reset_forces!(tgstruct) RB.actuate!(tgstruct,u) RB.update_strings_apply_forces!(tgstruct) - RB.apply_gravity!(tgstruct) + RB.apply_field!(tgstruct) F .= 0 #F .= Q̃*RB.fvector(tgstruct) RB.assemble_forces!(F,tgstruct) @@ -241,7 +241,7 @@ function linearload(st,q0,initial_u,target_u,target_t) RB.update_strings_apply_forces!(st) # tensions = [s.state.tension for s in st.strings] # @show tensions - RB.apply_gravity!(st) + RB.apply_field!(st) #F .= Q̃*RB.fvector(st) F .= 0 RB.assemble_forces!(F,st) diff --git a/yard/manipulator/controller_Lya.jl b/yard/manipulator/controller_Lya.jl index a332584..da8211d 100644 --- a/yard/manipulator/controller_Lya.jl +++ b/yard/manipulator/controller_Lya.jl @@ -42,7 +42,7 @@ function free(bot) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_cables_apply_forces!(st) - RB.apply_gravity!(st) + RB.apply_field!(st) RB.assemble_forces!(F,st) # @show isapprox(F,Q̃*RB.fvector(st)) end diff --git a/yard/manipulator/eigen.jl b/yard/manipulator/eigen.jl index 756d8c2..ca75975 100644 --- a/yard/manipulator/eigen.jl +++ b/yard/manipulator/eigen.jl @@ -137,7 +137,7 @@ function freevibra(tgstruct,q0) RB.distribute_q_to_rbs!(tgstruct,q,q̇) RB.update_cables_apply_forces!(tgstruct) # F .= Q̃*RB.fvector(tgstruct) - # RB.apply_gravity!(tgstruct,factor=0.01) + # RB.apply_field!(tgstruct,factor=0.01) # F .= G RB.assemble_forces!(F,tgstruct) # @show isapprox(F,Q̃*RB.fvector(tgstruct)) diff --git a/yard/manipulator/free.jl b/yard/manipulator/free.jl index 9d554a4..aa950c2 100644 --- a/yard/manipulator/free.jl +++ b/yard/manipulator/free.jl @@ -48,7 +48,7 @@ function simulate_free(num_of_dof;k,c,unit="mks",dt=0.01,tend=10.0,verbose=false RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_cables_apply_forces!(st) - RB.apply_gravity!(st) + RB.apply_field!(st) RB.assemble_forces!(F,st) # @show isapprox(F,Q̃*RB.fvector(st)) end diff --git a/yard/manipulator/man_vibra.jl b/yard/manipulator/man_vibra.jl index 8b70db9..de66bc9 100644 --- a/yard/manipulator/man_vibra.jl +++ b/yard/manipulator/man_vibra.jl @@ -40,7 +40,7 @@ function dynfuncs(tgstruct,q0) RB.reset_forces!(tgstruct) # RB.distribute_q_to_rbs!(tgstruct,q,q̇) # RB.update_cables_apply_forces!(tgstruct) - RB.apply_gravity!(tgstruct) + RB.apply_field!(tgstruct) #F .= Q̃*RB.fvector(tgstruct) F .= 0.0 RB.assemble_forces!(F,tgstruct) diff --git a/yard/manipulator/planning.jl b/yard/manipulator/planning.jl index 9d8270d..256da24 100644 --- a/yard/manipulator/planning.jl +++ b/yard/manipulator/planning.jl @@ -73,7 +73,7 @@ function dynamics(tr,action) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_cables_apply_forces!(st) - RB.apply_gravity!(st;factor=0.1) + RB.apply_field!(st;factor=0.1) RB.assemble_forces!(F,st) end Jac_Γ = RB.build_Jac_Γ(st) diff --git a/yard/manipulator/static_stability.jl b/yard/manipulator/static_stability.jl index c2455ea..ca1cc9c 100644 --- a/yard/manipulator/static_stability.jl +++ b/yard/manipulator/static_stability.jl @@ -95,7 +95,7 @@ function free(bot) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_cables_apply_forces!(st) - # RB.apply_gravity!(st) + # RB.apply_field!(st) RB.assemble_forces!(F,st) # @show isapprox(F,Q̃*RB.fvector(st)) end diff --git a/yard/ming/ming.jl b/yard/ming/ming.jl index 2d66bbd..8b96896 100644 --- a/yard/ming/ming.jl +++ b/yard/ming/ming.jl @@ -171,7 +171,7 @@ function simulate_linkn(linkn;dt=0.01,tend=10.0,target_temps=[40,40,40],verbose= RB.distribute_q_to_rbs!(st,q,q̇) RB.update_strings_apply_forces!(st) RB.update_SMA_strings_apply_forces!(st) - RB.apply_gravity!(st) + RB.apply_field!(st) # F .= Q̃*RB.fvector(st) # rb3 = st.rigidbodies[end] # f = [5.0,0.0,0.0] diff --git a/yard/ming/verify.jl b/yard/ming/verify.jl index 8095a9c..87c597b 100644 --- a/yard/ming/verify.jl +++ b/yard/ming/verify.jl @@ -113,7 +113,7 @@ function dynfuncs(tgbot) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_strings_apply_forces!(st) - # RB.apply_gravity!(st) + # RB.apply_field!(st) RB.assemble_forces!(F,st) end M,Φ,A,F!,nothing diff --git a/yard/nonsmooth/cube.jl b/yard/nonsmooth/cube.jl index 1d2508c..d66fa6b 100644 --- a/yard/nonsmooth/cube.jl +++ b/yard/nonsmooth/cube.jl @@ -1,55 +1,5 @@ #-- cube -function make_cube(origin_position = [0.0,0.0,0.5], - R = one(RotMatrix{3}), - origin_velocity = [2.0,0.0,0.0], - ω = [0.0,0.0,5.0]; - μ = 0.9, - e = 0.0 -) -m = 1.0 -mass_locus = zeros(3) -inertia = SMatrix{3,3}(Matrix(1.0I,3,3)) -h = 5.0 -loci = [h.*[x,y,z] for z = [-1,1] for y = [-1,1] for x = [-1,1]] -axes = [SVector(1.0,0,0) for _ = 1:length(loci)] -friction_coefficients = [μ for _ = 1:length(loci)] -restitution_coefficients = [e for _ = 1:length(loci)] -pts = Point3.(loci) -fcs = GB.QuadFace.([ - [1,3,4,2], - [3,7,8,4], - [7,5,6,8], - [5,1,2,6], - [2,4,8,6], - [1,5,7,3] -]) -nls = GB.normals(pts,fcs) -cube_mesh = GB.Mesh(GB.meta(pts,normals=nls),fcs) -prop = RB.RigidBodyProperty( - 1,true,m,inertia, - mass_locus,loci,axes, - friction_coefficients,restitution_coefficients, - ) -ri = copy(origin_position) -nmcs = RB.NCF.NC1P3V(ri,origin_position,R) -state = RB.RigidBodyState(prop,origin_position,R,origin_velocity,ω) -rb1 = RB.RigidBody(prop,state,cube_mesh) -rbs = TypeSortedCollection((rb1,)) -numbered = RB.number(rbs) -matrix_sharing = zeros(Int,0,0) -indexed = RB.index(rbs,matrix_sharing) -ss = Int[] -apparatuses = (cables = ss,) -hub = nothing -# -connected = RB.connect(rbs,zeros(Int,0,0)) -tensioned = @eponymtuple(connected) -cnt = RB.Connectivity(numbered,indexed,tensioned) -st = RB.Structure(rbs,apparatuses,cnt,) -bot = RB.Robot(st,nothing) -end - cubebot = make_cube() plot_traj!(cubebot) diff --git a/yard/nonsmooth/make_notebooks.jl b/yard/nonsmooth/make_notebooks.jl index 9415ee1..76ce989 100644 --- a/yard/nonsmooth/make_notebooks.jl +++ b/yard/nonsmooth/make_notebooks.jl @@ -28,20 +28,20 @@ using GLMakie # ) -Literate.notebook( - joinpath(@__DIR__,"meteor_hammer.jl"), - joinpath(@__DIR__,"../../../notebooks/"); - name="meteor_hammer", - execute = true, - # documenter = false, -) - - ## Literate.notebook( -## joinpath(@__DIR__,"superball.jl"), +## joinpath(@__DIR__,"meteor_hammer.jl"), ## joinpath(@__DIR__,"../../../notebooks/"); -## name="superball", +## name="meteor_hammer", ## execute = true, ## # documenter = false, ## ) + + +Literate.notebook( + joinpath(@__DIR__,"superball.jl"), + joinpath(@__DIR__,"../../../notebooks/"); + name="superball", + execute = true, + # documenter = false, +) GLMakie.closeall() \ No newline at end of file diff --git a/yard/nonsmooth/superball.jl b/yard/nonsmooth/superball.jl index ab2dcc5..e8c0f32 100644 --- a/yard/nonsmooth/superball.jl +++ b/yard/nonsmooth/superball.jl @@ -48,9 +48,11 @@ ballbot = superball( e = 0.8, l,d, z0 = l^2/(sqrt(5)*d) + 2.0, + visible = true, constrained = false, loadmesh = false, ) + # time tspan = (0.0,5.0) h = 1e-2 @@ -125,7 +127,7 @@ GM.activate!(;scalefactor); with_theme(theme_pub; meshcolor = Makie.RGBAf(r,g,b,alphas[i])) end RB.hidey(ax) - lines!(ax,r2p1) + lines!(ax,Matrix(r2p1)) end ) ax31 = Axis(gd2[1,1], @@ -189,6 +191,37 @@ GM.activate!(;scalefactor); with_theme(theme_pub; fig end +GM.activate!(;scalefactor=4,px_per_unit=4); with_theme(theme_pub; + figure_padding = (0,0,0,-fontsize), + size = (1.0tw,0.30tw), + Axis3 = ( + azimuth = 4.7855306333269805, + elevation = 0.03269908169872391, + xlabeloffset = fontsize, + zlabeloffset = 0.6fontsize, + ) + ) do + plot_traj!(ballbot; + AxisType = Axis3, + figname = "ballbot_rolling.gif", + xlims = [-1,20], + ylims = [-1,8], + zlims = [-1e-3,3.0], + doslide = false, + dorecord = true, + showinfo = false, + showpoints = false, + showlabels = false, + showmesh = true, + showwire = true, + showtitle = false, + showcables = true, + sup! = (ax,_,_) -> begin + RB.hidey(ax) + end + ) +end + # ## Second Scenario ballbot = superball( 0.0; @@ -272,7 +305,7 @@ GM.activate!(;scalefactor); with_theme(theme_pub; cablecolor=Makie.RGBAf(db.r,db.g,db.b,Makie.N0f8(alphas[i])), meshcolor = Makie.RGBAf(r,g,b,alphas[i])) end - lines!(ax,r2p1) + lines!(ax,Matrix(r2p1)) end ) ax2 = Axis(gd2[1,1];tellheight=false,xlabel=tlabel,ylabel = "Energy (J)") @@ -295,6 +328,32 @@ GM.activate!(;scalefactor); with_theme(theme_pub; fig end +GM.activate!(;scalefactor=4,px_per_unit=4); with_theme(theme_pub; + size = (0.6tw,0.30tw), + figure_padding = (-2fontsize,0.5fontsize,0,0), + Axis3 = ( + azimuth = 4.825530633326982, + elevation = 0.6726990816987243 + ) + ) do + plot_traj!(ballbot; + AxisType = Axis3, + figname="ballbot_sliding.gif", + xlims = [-1,6], + ylims = [-1,3], + zlims = [-1e-3,1.55], + doslide = false, + dorecord = true, + showinfo = false, + showpoints = false, + showlabels = false, + showtitle = false, + showcables = true, + showmesh = true, + showwire = false, + ) +end + step_start = RB.time2step(1.6,ballbot.traj.t) #src step_stop = RB.time2step(2.5,ballbot.traj.t) #src r2p1 = RB.get_trajectory!(ballbot,2,1) #src @@ -325,7 +384,7 @@ stats_superballs_dt = [ ); tspan=(0.0,0.1),dt,ftol=ifelse(dt==5e-6,1e-14,1e-12), maxiters=500,exception=false - ).prob.bot + )[1].prob.bot end for dt in dts, solver in (RB.Zhong06(),RB.Moreau(0.5)) ]; diff --git a/yard/spine3d/main.jl b/yard/spine3d/main.jl index 7cae1ad..cfe1e73 100644 --- a/yard/spine3d/main.jl +++ b/yard/spine3d/main.jl @@ -184,7 +184,7 @@ function dynfuncs(bot) RB.reset_forces!(st) RB.distribute_q_to_rbs!(st,q,q̇) RB.update_cables_apply_forces!(st) - # RB.apply_gravity!(st,factor=0.001) + # RB.apply_field!(st,factor=0.001) # F .= Q̃*RB.fvector(st) F .= 0.0 RB.assemble_forces!(F,st) diff --git a/yard/stiffness/deps.jl b/yard/stability_stiffness.jl similarity index 100% rename from yard/stiffness/deps.jl rename to yard/stability_stiffness.jl diff --git a/yard/stiffness/Tbars.jl b/yard/stiffness/Tbars.jl index c85090d..0b94cd3 100644 --- a/yard/stiffness/Tbars.jl +++ b/yard/stiffness/Tbars.jl @@ -1,23 +1,28 @@ -include("deps.jl") + +using Revise #jl +import Rible as RB + +include(joinpath(pathof(RB),"../../yard/stability_stiffness.jl")) using AbbreviatedStackTraces #jl ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl -using Revise #jl -import Rible as RB -figdir::String = joinpath(pathof(RB),"../../tmp") -if Sys.iswindows() #src - figdir::String = raw"C:\Users\luo22\OneDrive\Papers\FrictionalContact\CMAME" #src -elseif Sys.isapple() #src - figdir::String = raw"/Users/jacob/Library/CloudStorage/OneDrive-SharedLibraries-onedrive/Papers/FrictionalContact/CMAME" #src -end #src -include("../../vis.jl") -includet("../../vis.jl") #jl + +figdir::String = "" +if Sys.iswindows() + figdir::String = raw"C:\Users\luo22\OneDrive\Papers\TensegrityStability" +elseif Sys.isapple() + figdir::String = raw"/Users/jacob/Library/CloudStorage/OneDrive-SharedLibraries-onedrive/Papers/TensegrityStability" +end + +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl #-- T bars -include("../../../examples/bodies/make_3d_bar.jl") -includet("../../../examples/bodies/make_3d_bar.jl") #jl -include("../../../examples/robots/Tbars.jl") -includet("../../../examples/robots/Tbars.jl")#jl +include(joinpath(pathof(RB),"../../examples/bodies/make_3d_bar.jl")) +includet(joinpath(pathof(RB),"../../examples/bodies/make_3d_bar.jl")) #jl +include(joinpath(pathof(RB),"../../examples/robots/Tbars.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/Tbars.jl"))#jl + tbbot = Tbars(;θ=π/4) bot = tbbot @myshow bot.structure.connectivity.indexed.num_of_dof @@ -39,8 +44,8 @@ plot_traj!(bot;showarrows = false, showground=false) #todo slider with no hook GM.activate!();with_theme(theme_pub; - size = (1tw,0.15tw), - figure_padding = (0,0,fontsize/2,0), + size = (1cw,0.6cw), + figure_padding = (0,0,-fontsize/2,0), Axis3 = ( # azimuth = -1.8701322643948965, # elevation = 0.6128666392948965, @@ -51,9 +56,10 @@ GM.activate!();with_theme(theme_pub; ) do fig = Figure() gd0 = fig[1,1] = GridLayout(;tellheight=false) - gd1 = fig[1,2] = GridLayout(;tellheight=false) + gd1 = fig[2,1] = GridLayout(;tellheight=false) # rowsize!(gd0,1,Fixed(0.15tw)) # rowsize!(gd1,1,Fixed(0.15tw)) + rowgap!(fig.layout,0) bot0 = Tbars(;θ=0) plot_traj!( bot0, @@ -75,7 +81,7 @@ GM.activate!();with_theme(theme_pub; end, sup! = (ax,tgob,sgi)-> begin # cables - hidez(ax) + RB.hidez(ax) end ) bot1 = Tbars(;θ=π/4) @@ -98,7 +104,7 @@ GM.activate!();with_theme(theme_pub; end, sup! = (ax,tgob,sgi)-> begin # cables - hidez(ax) + RB.hidez(ax) end ) savefig(fig,"Tbars") @@ -188,7 +194,7 @@ struct𝒦 = [ # @show s λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*s @show λ - Ǩa = - RB.cstr_forces_jacobian(bot.structure,q,λ) + Ǩa = RB.cstr_forces_jacobian(bot.structure,q,λ) Ǩg = RB.build_geometric_stiffness_matrix!(bot.structure,q,s) @@ -208,8 +214,9 @@ mat𝒦as = reduce(hcat,struct𝒦.𝒦a) mat𝒦ps = reduce(hcat,struct𝒦.𝒦p) GM.activate!();with_theme(theme_pub; - size = (0.95tw,0.18tw), - figure_padding = (0,0,0,0), + size = (1cw,0.72cw), + fontsize=6.5, + figure_padding = (-fontsize,-fontsize,-2fontsize,0), Axis3 = ( azimuth = -π/2-1e-10, elevation = π/2, @@ -226,7 +233,7 @@ GM.activate!();with_theme(theme_pub; bot0, fig = gd, AxisType=Axis3, - gridsize = (1,4), + gridsize = (2,2), showpoints = false, showlabels = false, showground = false, @@ -234,7 +241,7 @@ GM.activate!();with_theme(theme_pub; showcables = false, xlims = (-2.2,1.2), ylims = (-1.2,1.2), - rowgap=0, + rowgap=-fontsize, titleformatfunc = (sgi,tt)-> begin rich( rich("($(alphabet[sgi])) ", font=:bold), @@ -251,7 +258,7 @@ GM.activate!();with_theme(theme_pub; RB.hidexyz(ax) @myshow Sbool[:,sgi] linesegs_cables = @lift begin - get_linesegs_cables($tgob;)[Sbool[:,sgi]] + RB.get_linesegs_cables($tgob;)[Sbool[:,sgi]] end linesegments!(ax, linesegs_cables, @@ -259,18 +266,18 @@ GM.activate!();with_theme(theme_pub; # linewidth = cablewidth ) rcs_by_cables = @lift begin - (;tensioned) = $tgob.connectivity + cables = RB.get_cables($tgob) num_of_dim = RB.get_num_of_dims($tgob) T = RB.get_numbertype($tgob) ret = Vector{MVector{num_of_dim,T}}() mapreduce( - (scnt)-> + (cable)-> [( - scnt.hen.body.state.loci_states[scnt.hen.pid].position.+ - scnt.egg.body.state.loci_states[scnt.egg.pid].position + cable.joint.hen2egg.hen.body.state.loci_states[cable.joint.hen2egg.hen.pid].frame.position.+ + cable.joint.hen2egg.egg.body.state.loci_states[cable.joint.hen2egg.egg.pid].frame.position )./2], vcat, - tensioned.connected + cables ;init=ret ) end @@ -285,14 +292,14 @@ GM.activate!();with_theme(theme_pub; # ax, # rcs_by_cables[][Sbool[:,sgi]], # marker = :rect, - # markersize = 12 |> pt2px, + # markersize = 12 , # color = :white # ) text!( ax, Stext, position = rcs_by_cables[][Sbool[:,sgi]], - fontsize = 5 |> pt2px, + fontsize = 5 , color = :red, align = (:left, :top), offset = (fontsize/4, 0) @@ -327,7 +334,8 @@ Vals = [ ] |> VectorOfArray GM.activate!();with_theme(theme_pub; - size = (0.45tw,0.2tw), + size = (0.8cw,0.3cw), + fontsize = 6.5, figure_padding = (0,fontsize,0,fontsize), ) do fig = Figure() diff --git a/yard/stiffness/main.jl b/yard/stiffness/main.jl index db7b9d0..e2f98dc 100644 --- a/yard/stiffness/main.jl +++ b/yard/stiffness/main.jl @@ -1,3 +1,12 @@ + +using Revise #jl +import Rible as RB + +include(joinpath(pathof(RB),"../../yard/stability_stiffness.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + figdir::String = "" if Sys.iswindows() figdir::String = raw"C:\Users\luo22\OneDrive\Papers\TensegrityStability" @@ -5,14 +14,35 @@ elseif Sys.isapple() figdir::String = raw"/Users/jacob/Library/CloudStorage/OneDrive-SharedLibraries-onedrive/Papers/TensegrityStability" end -includet("deps.jl") -import Rible as RB -include("../../vis.jl") -includet("../../vis.jl") +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/bodies/rigidbar.jl")) +includet(joinpath(pathof(RB),"../../examples/bodies/rigidbar.jl")) #jl +include(joinpath(pathof(RB),"../../examples/robots/superball.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/superball.jl")) #jl -fontsize = 8 |> pt2px -tw = 468 |> pt2px -th = 622 |> pt2px + +include(joinpath(pathof(RB),"../../examples/bodies/make_3d_bar.jl")) +includet(joinpath(pathof(RB),"../../examples/bodies/make_3d_bar.jl")) #jl +include(joinpath(pathof(RB),"../../examples/bodies/make_3d_plate.jl")) +includet(joinpath(pathof(RB),"../../examples/bodies/make_3d_plate.jl")) #jl +include(joinpath(pathof(RB),"../../examples/robots/prism.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/prism.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/bodies/make_3d_tri.jl")) +includet(joinpath(pathof(RB),"../../examples/bodies/make_3d_tri.jl")) #jl +include(joinpath(pathof(RB),"../../examples/robots/tower.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/tower.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/bodies/build_2d_tri.jl")) +includet(joinpath(pathof(RB),"../../examples/bodies/build_2d_tri.jl")) #jl +include(joinpath(pathof(RB),"../../examples/robots/two_tri.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/two_tri.jl")) #jl + +fontsize = 8 +cw = 240.7103 +tw = 494.22432 #-- preamble end #-- one_tri_one_bar @@ -52,7 +82,7 @@ end function build_nullspace_on_free(st) (;sys_free_coords_idx,bodyid2sys_dof_idx) = st.connectivity.indexed q = RB.get_coords(bot.structure) - Nin = RB.make_intrinsic_nullspace(st,q)[ + Nin = RB.intrinsic_nullspace(st,q)[ sys_free_coords_idx, reduce(vcat,bodyid2sys_dof_idx[2:end]) ] @@ -75,13 +105,13 @@ f = RB.get_cables_tension(bot) function verify_lambda(st) T = RB.get_numbertype(st) - λs = zeros(T,st.num_of_bodies) + λs = zeros(T,st.connectivity.indexed.num_of_bodies) foreach(st.bodies) do body (;prop,state) = body - (;loci_states,origin_position) = state + (;loci_states,origin_frame) = state # @myshow prop.id for locus_state in loci_states - λs[prop.id] += -1/2*(locus_state.position-origin_position)'*locus_state.force + λs[prop.id] += -1/2*(locus_state.frame.position-origin_frame.position)'*locus_state.force end end λs @@ -118,7 +148,7 @@ l = RB.get_cables_len(bot.structure) λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f @myshow verify_lambda(bot.structure) @myshow λ -Ǩa = RB.cstr_forces_jacobian(bot.structure,λ) +Ǩa = RB.cstr_forces_jacobian(bot.structure,q,λ) 𝒦a = transpose(Ň)*Ǩa*Ň |> Symmetric vals_𝒦a,vecs_𝒦a = eigen(𝒦a) @myshow sort(vals_𝒦a) @@ -136,7 +166,7 @@ vec𝒦ps = [ # @show s λi = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*si # @show f,λ - Ǩai = - RB.cstr_forces_jacobian(bot.structure,λi) + Ǩai = RB.cstr_forces_jacobian(bot.structure,q,λi) Ǩgi = RB.build_geometric_stiffness_matrix!(bot.structure,q,si) @@ -171,10 +201,11 @@ v'*𝒦*v vm[:,1] = v orthovm = RB.modified_gram_schmidt(vm) -with_theme(theme_pub; - size = (0.9tw,0.3tw), - fontsize = 6.5 |> pt2px, - figure_padding = (2fontsize,fontsize,0,0), + +GM.activate!(;scalefactor=2);with_theme(theme_pub; + size = (1cw,0.9cw), + fontsize = 6.5 , + figure_padding = (0,0,-2.5fontsize,0), Axis3 = ( azimuth = 3.7555306333269844, elevation = 0.3726990816987242, @@ -190,12 +221,16 @@ with_theme(theme_pub; ratio = norm(δq̌i)/norm(q̌) botvis.traj.q̌[end] .= q̌ .+ scaling.*δq̌i/ratio end + fig = Figure() + gd1 = fig[1,1:2] = GridLayout() + gd2 = fig[2,1:2] = GridLayout() + rowgap!(fig.layout,0) plot_traj!( botvis; - figsize = (0.8tw,0.26tw), + fig = gd1, AxisType=Axis3, - gridsize=(1,nk+1), - atsteps=1:nk+1, + gridsize=(1,1), + atsteps=1:1, doslide=false, showlabels=false, showpoints=false, @@ -210,20 +245,42 @@ with_theme(theme_pub; rich("($(alphabet[sgi])) ", font=:bold), [ "Initial", + ][sgi] + ) + end, + ) + plot_traj!( + botvis; + fig = gd2, + AxisType=Axis3, + gridsize=(1,nk), + atsteps=2:nk+1, + doslide=false, + showlabels=false, + showpoints=false, + # showcables = false, + showground = false, + xlims = (-1e0,1e0), + ylims = (-1e0,1e0), + zlims = (-1e-5,2e0), + slack_linestyle = :solid, + showinit = true,titleformatfunc = (sgi,tt)-> begin + rich( + rich("($(alphabet[sgi+1])) ", font=:bold), + [ "Mechanism Mode 1", "Mechanism Mode 2" ][sgi] ) end, sup! = (ax,tgob,sgi)->begin - if sgi != 1 - hidedecorations!(ax) - xlims!(ax,-1.0e0,1.2e0) - ylims!(ax,-1.2e0,1.0e0) - end + hidedecorations!(ax) + xlims!(ax,-1.0e0,1.2e0) + ylims!(ax,-1.2e0,1.0e0) end, - figname="superball" ) + savefig(fig,"superball") + fig end Ňv = Ň*nullspace(v') @@ -254,7 +311,7 @@ vecr𝒦ps = [ # @show s λi = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*si # @show f,λ - Ǩai = RB.cstr_forces_jacobian(bot.structure,λi) + Ǩai = RB.cstr_forces_jacobian(bot.structure,q,λi) Ǩgi = RB.build_geometric_stiffness_matrix!(bot.structure,q,si) @@ -305,7 +362,7 @@ maxminmodes = hcat( ) with_theme(theme_pub; - fontsize = 6.5 |> pt2px, + fontsize = 6.5 , size = (0.8tw,0.18tw), figure_padding = (0,0,-fontsize,0), Axis3 = ( @@ -378,7 +435,7 @@ size(rρs,1) ] with_theme(theme_pub; - size = (0.3tw,0.2tw), + size = (0.6cw,0.35cw), figure_padding = (0,fontsize,0,fontsize), ) do fig = Figure() @@ -388,7 +445,7 @@ with_theme(theme_pub; ) lines!(ax,σs,rρs[1,:],) xlims!(ax,0,5500) - ylims!(ax,-400,600) + ylims!(ax,-200,600) # for i = axes(rρs,1) # lines!(ax,σs,rρs[i,:],) # end @@ -427,18 +484,17 @@ prism1 = prisms(; ) bot = prism1 rb1 = RB.get_bodies(bot)[1] -viz(rb1) + plot_traj!(bot;showground=false) RB.check_static_equilibrium_output_multipliers(bot.structure) -@myshow bot.structure.num_of_dof +@myshow bot.structure.connectivity.indexed.num_of_dof RB.update!(bot.structure) f = RB.get_cables_tension(bot) - # for use with Class-1 and the 1st rigid fixed function build_nullspace_on_free(st) (;sys_free_coords_idx,bodyid2sys_full_coords,bodyid2sys_dof_idx) = st.connectivity.indexed q = RB.get_coords(bot.structure) - Nin = RB.make_intrinsic_nullspace(st,q)[ + Nin = RB.intrinsic_nullspace(st,q)[ sys_free_coords_idx, reduce(vcat,bodyid2sys_dof_idx[begin:end-1]) ] @@ -487,10 +543,10 @@ D ns = size(S,2) nk = size(D,2) -GM.activate!();with_theme(theme_pub; - size = (0.95tw,0.24tw), - figure_padding = (2fontsize,0,0,0), - fontsize = 6.5 |> pt2px, +GM.activate!(;scalefactor=4);with_theme(theme_pub; + size = (1cw,0.30tw), + figure_padding = (0,0,-2fontsize,0), + fontsize = 6.5 , Axis3 = ( azimuth = 3.8255306333269843, elevation = 0.2026990816987241 @@ -503,7 +559,10 @@ GM.activate!();with_theme(theme_pub; fig = Figure() gd1 = fig[1,1] = GridLayout() gd2 = fig[1,2:3] = GridLayout() - gd3 = fig[1,4:5] = GridLayout() + gd3_holder = fig[2,1:3] = GridLayout() + gd3 = gd3_holder[1,1:2] = GridLayout() + colgap!(fig.layout,0) + rowgap!(fig.layout,-fontsize) botmm = deepcopy(bot) plot_traj!( bot; @@ -524,8 +583,8 @@ GM.activate!();with_theme(theme_pub; ) end, sup! = (ax,tgob,sgi)->begin - hidex(ax) - hidey(ax) + RB.hidex(ax) + RB.hidey(ax) # xlims!(ax,-1.0e0,1.2e0) # ylims!(ax,-1.2e0,1.0e0) end, @@ -560,10 +619,10 @@ GM.activate!();with_theme(theme_pub; ax.elevation = 0.18269908169872395 # azimuth = 4.665530633326984 # elevation = 0.16269908169872424 - hidexyz(ax) + RB.hidexyz(ax) @myshow Sbool[:,sgi] linesegs_cables = @lift begin - get_linesegs_cables($tgob;)[Sbool[:,sgi]] + RB.get_linesegs_cables($tgob;)[Sbool[:,sgi]] end linesegments!(ax, linesegs_cables, @@ -571,18 +630,18 @@ GM.activate!();with_theme(theme_pub; # linewidth = cablewidth ) rcs_by_cables = @lift begin - (;tensioned) = $tgob.connectivity + cables = RB.get_cables($tgob) num_of_dim = RB.get_num_of_dims($tgob) T = RB.get_numbertype($tgob) ret = Vector{MVector{num_of_dim,T}}() mapreduce( - (scnt)-> + (cable)-> [( - scnt.hen.body.state.loci_states[scnt.hen.pid].position.+ - scnt.egg.body.state.loci_states[scnt.egg.pid].position + cable.joint.hen2egg.hen.body.state.loci_states[cable.joint.hen2egg.hen.pid].frame.position.+ + cable.joint.hen2egg.egg.body.state.loci_states[cable.joint.hen2egg.egg.pid].frame.position )./2], vcat, - tensioned.connected + cables ;init=ret ) end @@ -597,14 +656,14 @@ GM.activate!();with_theme(theme_pub; # ax, # rcs_by_cables[][Sbool[:,sgi]], # marker = :rect, - # markersize = 12 |> pt2px, + # markersize = 12 , # color = :white # ) text!( ax, Stext, position = rcs_by_cables[][Sbool[:,sgi]], - fontsize = 5 |> pt2px, + fontsize = 5 , color = :red, align = (:center, :center), # offset = (-fontsize/2, 0) @@ -633,7 +692,7 @@ GM.activate!();with_theme(theme_pub; showground = false, xlims = (-8e-2,8e-2), ylims = (-8e-2,8e-2), - zlims = (-1e-5,2.5e-1), + zlims = (-1e-5,2.1e-1), slack_linestyle = :solid, showinit = true,titleformatfunc = (sgi,tt)-> begin rich( @@ -645,7 +704,7 @@ GM.activate!();with_theme(theme_pub; ) end, sup! = (ax,tgob,sgi)->begin - hidexyz(ax) + RB.hidexyz(ax) # xlims!(ax,-1.0e0,1.2e0) # ylims!(ax,-1.2e0,1.0e0) end, @@ -670,7 +729,7 @@ f = S*ᾱ λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f # @show f,λ -Ǩa = RB.cstr_forces_jacobian(bot.structure,λ) +Ǩa = RB.cstr_forces_jacobian(bot.structure,q,λ) 𝒦ain = transpose(Nin)*Ǩa*Nin 𝒦a = transpose(Ň)*Ǩa*Ň |> Symmetric vals_𝒦a,vecs_𝒦a = eigen(𝒦a) @@ -697,7 +756,7 @@ vec𝒦ps = [ # @show s λi = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*si # @show f,λ - Ǩai = RB.cstr_forces_jacobian(bot.structure,λi) + Ǩai = RB.cstr_forces_jacobian(bot.structure,q,λi) Ǩgi = RB.build_geometric_stiffness_matrix!(bot.structure,q,si) @@ -760,7 +819,8 @@ Vals = [ ] |> VectorOfArray with_theme(theme_pub; - size = (0.6tw,0.2tw), + size = (1cw,0.3cw), + fontsize = 6.5, figure_padding = (0,fontsize,0,0), ) do fig = Figure() @@ -865,7 +925,8 @@ Vals_α = [ ] |> VectorOfArray with_theme(theme_pub; - size = (0.6tw,0.2tw), + size = (1cw,0.3cw), + fontsize = 6.5, figure_padding = (0,fontsize,0,0), ) do fig = Figure() @@ -925,14 +986,14 @@ end two = two_tri() bot = two plot_traj!(bot;showground=false) -bot.structure.num_of_dof +bot.structure.connectivity.indexed.num_of_dof RB.check_static_equilibrium_output_multipliers(bot.structure) function make_nullspace_on_free(st) (;sys_free_coords_idx,bodyid2sys_dof_idx) = st.connectivity.indexed q = RB.get_coords(bot.structure) - Nin = RB.make_intrinsic_nullspace(st,q) + Nin = RB.intrinsic_nullspace(st,q) Nin[ sys_free_coords_idx, reduce(vcat,bodyid2sys_dof_idx[2:end]) @@ -985,9 +1046,9 @@ nk = size(D,2) ns = size(S,2) GM.activate!();with_theme(theme_pub; - size = (0.9tw,0.22tw), - figure_padding = (fontsize,0,0,0), - fontsize = 6.5 |> pt2px, + size = (1cw,0.6cw), + figure_padding = (-1fontsize,-1fontsize,-1fontsize,0), + fontsize = 6.5 , Axis3 = ( azimuth = -π/2-1e-10, elevation = π/2, @@ -1001,8 +1062,11 @@ GM.activate!();with_theme(theme_pub; Sbool = S.> maxS*rtol S[.!Sbool] .= 0.0 fig = Figure() - gd1 = fig[1,1] = GridLayout(;tellheight=false) - gd2 = fig[1,2:3] = GridLayout(;tellheight=false) + gd1 = fig[1,1:2] = GridLayout(;tellheight=false) + gd2 = fig[2,1:2] = GridLayout(;tellheight=false) + ## colgap!(gd2,-fontsize) + rowsize!(fig.layout,1,Relative(0.3)) + rowgap!(fig.layout,0fontsize) plot_traj!( bot, fig = gd1, @@ -1021,10 +1085,10 @@ GM.activate!();with_theme(theme_pub; end, sup! = (ax,tgob,sgi)-> begin # cables - hidez(ax) + RB.hidez(ax) end ) - rowsize!(gd1,1,Fixed(0.1tw)) + ## rowsize!(gd1,1,Fixed(0.3cw)) plot_traj!( bot, fig = gd2, @@ -1037,7 +1101,8 @@ GM.activate!();with_theme(theme_pub; showcables = false, xlims = (-0.5,0.5), ylims = (-0.15,0.15), - rowgap=0, + rowgap=-1fontsize, + colgap=-2fontsize, titleformatfunc = (sgi,tt)-> begin rich( rich("($(alphabet[sgi+1])) ", font=:bold), @@ -1051,10 +1116,10 @@ GM.activate!();with_theme(theme_pub; end, sup! = (ax,tgob,sgi)-> begin # cables - hidexyz(ax) + RB.hidexyz(ax) @myshow Sbool[:,sgi] linesegs_cables = @lift begin - get_linesegs_cables($tgob;)[Sbool[:,sgi]] + RB.get_linesegs_cables($tgob;)[Sbool[:,sgi]] end linesegments!(ax, linesegs_cables, @@ -1062,18 +1127,18 @@ GM.activate!();with_theme(theme_pub; # linewidth = cablewidth ) rcs_by_cables = @lift begin - (;tensioned) = $tgob.connectivity + cables = RB.get_cables($tgob) num_of_dim = RB.get_num_of_dims($tgob) T = RB.get_numbertype($tgob) ret = Vector{MVector{num_of_dim,T}}() mapreduce( - (scnt)-> + (cable)-> [( - scnt.hen.body.state.loci_states[scnt.hen.pid].position.+ - scnt.egg.body.state.loci_states[scnt.egg.pid].position + cable.joint.hen2egg.hen.body.state.loci_states[cable.joint.hen2egg.hen.pid].frame.position.+ + cable.joint.hen2egg.egg.body.state.loci_states[cable.joint.hen2egg.egg.pid].frame.position )./2], vcat, - tensioned.connected + cables ;init=ret ) end @@ -1088,14 +1153,14 @@ GM.activate!();with_theme(theme_pub; # ax, # rcs_by_cables[][Sbool[:,sgi]], # marker = :rect, - # markersize = 12 |> pt2px, + # markersize = 12 , # color = :white # ) text!( ax, Stext, position = rcs_by_cables[][Sbool[:,sgi]], - fontsize = 5 |> pt2px, + fontsize = 5 , color = :red, align = (:center, :center), # offset = (-fontsize/2, 0) @@ -1121,7 +1186,7 @@ struct𝒦 = [ # @show s λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*s # @show f,λ - Ǩa = RB.cstr_forces_jacobian(bot.structure,λ) + Ǩa = RB.cstr_forces_jacobian(bot.structure,q,λ) Ǩg = RB.build_geometric_stiffness_matrix!(bot.structure,q,s) @@ -1159,7 +1224,7 @@ Vals = [ ] |> VectorOfArray GM.activate!();with_theme(theme_pub; - size = (0.5tw,0.2tw), + size = (0.8cw,0.3cw), figure_padding = (0,fontsize,0,fontsize), ) do fig = Figure() @@ -1235,7 +1300,7 @@ f = sum(S,dims=2) # equivalent μ # μ = l .- (f./k) -λ = -inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f +λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f # @show f,λ Ǩa = RB.cstr_forces_jacobian(bot.structure,λ) 𝒦a = transpose(Ň)*Ǩa*Ň |> Symmetric @@ -1255,7 +1320,7 @@ vec𝒦ps = [ # @show s λi = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*si # @show f,λ - Ǩai = - RB.cstr_forces_jacobian(bot.structure,λi) + Ǩai = RB.cstr_forces_jacobian(bot.structure,λi) Ǩgi = RB.build_geometric_stiffness_matrix!(bot.structure,q,si) @@ -1380,14 +1445,14 @@ end towerbot = tower() bot = towerbot -@myshow bot.structure.num_of_dof +@myshow bot.structure.connectivity.indexed.num_of_dof plot_traj!(bot;showground=false) function build_nullspace_on_free(st) (;sys_free_coords_idx,bodyid2sys_full_coords,bodyid2sys_dof_idx) = st.connectivity.indexed q = RB.get_coords(bot.structure) - Nin = RB.make_intrinsic_nullspace(st,q)[ + Nin = RB.intrinsic_nullspace(st,q)[ sys_free_coords_idx, reduce(vcat,bodyid2sys_dof_idx[begin+1:end]) ] @@ -1416,7 +1481,7 @@ Ǎ = RB.make_cstr_jacobian(bot.structure)(q) Ň = build_nullspace_on_free(bot.structure) Q̃ = RB.build_Q̃(bot.structure) L̂ = RB.build_L̂(bot.structure) - +rank(Ň) Ǎ*Ň |> norm # Left hand side @@ -1436,9 +1501,9 @@ l = RB.get_cables_len(bot.structure) isis = [8,14,24] GM.activate!();with_theme(theme_pub; - size = (0.95tw,0.2tw), - figure_padding = (2fontsize,0,0,0), - fontsize = 6.5 |> pt2px, + size = (1cw,0.3tw), + figure_padding = (-fontsize,-fontsize,-2fontsize,0), + fontsize = 6.5 , Axis3 = ( azimuth = 3.8255306333269843, elevation = 0.2026990816987241 @@ -1450,7 +1515,10 @@ GM.activate!();with_theme(theme_pub; S[.!Sbool] .= 0.0 fig = Figure() gd1 = fig[1,1] = GridLayout() - gd2 = fig[1,2:3+1] = GridLayout() + gd2_holder = fig[2,:] = GridLayout() + gd2 = gd2_holder[1,1:3] = GridLayout() + ## rowsize!(fig.layout,1,Relative(0.3)) + rowgap!(fig.layout,-1fontsize) botmm = deepcopy(bot) plot_traj!( bot; @@ -1471,8 +1539,8 @@ GM.activate!();with_theme(theme_pub; ) end, sup! = (ax,tgob,sgi)->begin - hidex(ax) - hidey(ax) + RB.hidex(ax) + RB.hidey(ax) # xlims!(ax,-1.0e0,1.2e0) # ylims!(ax,-1.2e0,1.0e0) end, @@ -1489,12 +1557,13 @@ GM.activate!();with_theme(theme_pub; xlims = (-1.5e0,1.5e0), ylims = (-1.5e0,1.5e0), zlims = (-0.6e0,1.5e0), + colgap = -2fontsize, showground = false, showinit = true, titleformatfunc = (sgi,tt)-> begin rich( rich("($(alphabet[sgi+1])) ", font=:bold), - "Self-stress State $sgi" + "Self-stress State $(isis[sgi])" ) end, sup! = (ax,tgob,sgi_input)-> begin @@ -1504,10 +1573,10 @@ GM.activate!();with_theme(theme_pub; ax.elevation = 0.18269908169872395 # azimuth = 4.665530633326984 # elevation = 0.16269908169872424 - hidexyz(ax) + RB.hidexyz(ax) @myshow Sbool[:,sgi] linesegs_cables = @lift begin - get_linesegs_cables($tgob;)[Sbool[:,sgi]] + RB.get_linesegs_cables($tgob;)[Sbool[:,sgi]] end linesegments!(ax, linesegs_cables, @@ -1515,18 +1584,18 @@ GM.activate!();with_theme(theme_pub; # linewidth = cablewidth ) rcs_by_cables = @lift begin - (;tensioned) = $tgob.connectivity + cables = RB.get_cables($tgob) num_of_dim = RB.get_num_of_dims($tgob) T = RB.get_numbertype($tgob) ret = Vector{MVector{num_of_dim,T}}() mapreduce( - (scnt)-> + (cable)-> [( - scnt.hen.body.state.loci_states[scnt.hen.pid].+ - scnt.egg.body.state.loci_states[scnt.egg.pid] + cable.joint.hen2egg.hen.body.state.loci_states[cable.joint.hen2egg.hen.pid].frame.position.+ + cable.joint.hen2egg.egg.body.state.loci_states[cable.joint.hen2egg.egg.pid].frame.position )./2], vcat, - tensioned.connected + cables ;init=ret ) end @@ -1541,14 +1610,14 @@ GM.activate!();with_theme(theme_pub; # ax, # rcs_by_cables[][Sbool[:,sgi]], # marker = :rect, - # markersize = 12 |> pt2px, + # markersize = 12 , # color = :white # ) text!( ax, Stext, position = rcs_by_cables[][Sbool[:,sgi]], - fontsize = 5 |> pt2px, + fontsize = 5 , color = :red, align = (:center, :center), # offset = (-fontsize/2, 0) @@ -1566,9 +1635,9 @@ f = S*ᾱ # equivalent μ # μ = l .- (f./k) -λ = -inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f +λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f # @show f,λ -Ǩa = RB.cstr_forces_jacobian(bot.structure,λ) +Ǩa = RB.cstr_forces_jacobian(bot.structure,q,λ) 𝒦a = transpose(Ň)*Ǩa*Ň |> Symmetric vals_𝒦a,vecs_𝒦a = eigen(𝒦a) @myshow sort(vals_𝒦a) @@ -1588,7 +1657,7 @@ vec𝒦ps = [ # @show s λi = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*si # @show f,λ - Ǩai = - RB.cstr_forces_jacobian(bot.structure,λi) + Ǩai = RB.cstr_forces_jacobian(bot.structure,q,λi) Ǩgi = RB.build_geometric_stiffness_matrix!(bot.structure,q,si) @@ -1661,7 +1730,8 @@ Vals_alpha3 = [ with_theme(theme_pub; - size = (0.35tw,0.2tw), + size = (0.6cw,0.36cw), + fontsize = 6.5, figure_padding = (0,fontsize,0,fontsize), ) do fig = Figure() @@ -1779,7 +1849,7 @@ f = S*ᾱ GM.activate!();with_theme(theme_pub; size = (0.95tw,0.24tw), figure_padding = (2fontsize,0,0,0), - fontsize = 6.5 |> pt2px, + fontsize = 6.5 , Axis3 = ( azimuth = 3.8255306333269843, elevation = 0.2026990816987241 @@ -1844,7 +1914,7 @@ GM.activate!();with_theme(theme_pub; ax.elevation = 0.18269908169872395 # azimuth = 4.665530633326984 # elevation = 0.16269908169872424 - hidexyz(ax) + RB.hidexyz(ax) @myshow Sbool[:,sgi] linesegs_cables = @lift begin get_linesegs_cables($tgob;)[Sbool[:,sgi]] @@ -1881,14 +1951,14 @@ GM.activate!();with_theme(theme_pub; # ax, # rcs_by_cables[][Sbool[:,sgi]], # marker = :rect, - # markersize = 12 |> pt2px, + # markersize = 12 , # color = :white # ) text!( ax, Stext, position = rcs_by_cables[][Sbool[:,sgi]], - fontsize = 5 |> pt2px, + fontsize = 5 , color = :red, align = (:center, :center), # offset = (-fontsize/2, 0) @@ -1899,7 +1969,7 @@ GM.activate!();with_theme(theme_pub; fig end -λ = -inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f +λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f # @show f,λ Ǩa = RB.cstr_forces_jacobian(bot.structure,λ) 𝒦a = transpose(Ň)*Ǩa*Ň |> Symmetric @@ -1924,7 +1994,7 @@ struct𝒦p = [ # @show s λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*s # @show f,λ - Ǩa = - RB.cstr_forces_jacobian(bot.structure,λ) + Ǩa = RB.cstr_forces_jacobian(bot.structure,q,λ) 𝒦a = transpose(Ň)*Ǩa*Ň Ǩg = RB.build_geometric_stiffness_matrix!(bot.structure,q,s) @@ -2051,7 +2121,7 @@ with_theme(theme_pub; fig end -λ = -inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f +λ = inv(Ǎ*transpose(Ǎ))*Ǎ*Bᵀ*f # @show f,λ using Symbolics @variables λ[1:6] diff --git a/yard/tail/bai.jl b/yard/tail/bai.jl index 5d46ddb..fff835a 100644 --- a/yard/tail/bai.jl +++ b/yard/tail/bai.jl @@ -1,32 +1,29 @@ -using LinearAlgebra -using StaticArrays, SparseArrays, TypeSortedCollections -using EponymTuples -using Unitful, Match, Printf -using GeometryBasics, Meshing -using Rotations, CoordinateTransformations -using Unitful -using LaTeXStrings -using Makie -import GLMakie as GM -GM.activate!() -import GeometryBasics as GB -using FileIO, MeshIO -using Revise +using Revise #jl import Rible as RB -cd("examples/tail") -include("../vis.jl") -includet("../vis.jl") +include(joinpath(pathof(RB),"../../yard/stability_stiffness.jl")) +using AbbreviatedStackTraces #jl +ENV["JULIA_STACKTRACE_ABBREVIATED"] = true #jl +ENV["JULIA_STACKTRACE_MINIMAL"] = true #jl + +figdir::String = "" + +include(joinpath(pathof(RB),"../../test/vis.jl")) +includet(joinpath(pathof(RB),"../../test/vis.jl")) #jl + +include(joinpath(pathof(RB),"../../examples/robots/bai.jl")) +includet(joinpath(pathof(RB),"../../examples/robots/bai.jl")) #jl + #-- preamble -mesh_head = load("装配体头部-1.2.3.STL") |> make_patch(;trans = [10, 0, 0],rot=RotZYX(π/2,-π/2,π/2)) -mesh_rib3 = load("肋片-3.STL") |> make_patch(;trans = [43+10, 0, 0], rot=RotZYX(π/2,-π/2,π/2)) +mesh_head = load(RB.assetpath("tail/装配体头部-1.2.3.STL")) |> RB.make_patch(;trans = [10, 0, 0],rot=RotZYX(π/2,-π/2,π/2)) +mesh_rib3 = load(RB.assetpath("tail/肋片-3.STL")) |> RB.make_patch(;trans = [43+10, 0, 0], rot=RotZYX(π/2,-π/2,π/2)) mesh_headrib = GB.merge([mesh_head,mesh_rib3]) -mesh_rib4 = load("肋片-4.STL") |> make_patch(;rot=RotZYX(π/2,-π/2,π/2)) -mesh_rib5 = load("肋片-5 - 副本.STL") |> make_patch(;rot=RotZYX(π/2,-π/2,π/2)) -mesh_rib7 = load("肋片-7 - 副本.STL") |> make_patch(;rot=RotZYX(π/2,-π/2,π/2)) -mesh_fin = load("尾鳍-v1-软.STL") |> make_patch(;rot=RotZYX(π/2,-π/2,π/2)) -mesh_bar = load("摆杆-v1.2.2.STL") |> make_patch(;rot=RotZYX(π/2,-π/2,π/2)) +mesh_rib4 = load(RB.assetpath("tail/肋片-4.STL")) |> RB.make_patch(;rot=RotZYX(π/2,-π/2,π/2)) +mesh_rib5 = load(RB.assetpath("tail/肋片-5 - 副本.STL")) |> RB.make_patch(;rot=RotZYX(π/2,-π/2,π/2)) +mesh_rib7 = load(RB.assetpath("tail/肋片-7 - 副本.STL")) |> RB.make_patch(;rot=RotZYX(π/2,-π/2,π/2)) +mesh_fin = load(RB.assetpath("tail/尾鳍-v1-软.STL")) |> RB.make_patch(;rot=RotZYX(π/2,-π/2,π/2)) +mesh_bar = load(RB.assetpath("tail/摆杆-v1.2.2.STL")) |> RB.make_patch(;rot=RotZYX(π/2,-π/2,π/2)) mesh(mesh_fin,color=:slategrey) meshes = [ mesh_headrib, @@ -64,183 +61,205 @@ meshes = [ 308.454 #摆杆-v1.2.2 ] -# 定义一个函数来新建机器人 -function make_bai(meshes,质心,质量,惯量) - - nb = 6 - ver_lengths_raw = [ - # 0 43; - # 18 18; - 0 43+18+18-10; - 18 16; - 19.1 9; - 18 8; - 18 8; - 0 16.29; - 0 150 - ] - ver_lengths = sum(ver_lengths_raw,dims=2) - hor_lengths = [ - 32.61, - 26.21, - 20.64, - 14.71, - 13.24, - # 13.24, - 2.5 - ] - nhor = length(hor_lengths) - P = [ - zeros(2,) - for i = 1:nhor+1 - ] - for i = 2:nhor+1 - P[i] = P[i-1] + [0.0,-ver_lengths[i-1]] - end - - function rigidbody(i,P) - if i == 1 - contactable = false - visible = true - ci = collect(1:6) - cstr_idx = Int[] - elseif i in [2,nb] - contactable = true - visible = true - ci = collect(1:2) - cstr_idx = collect(1:3) - else - contactable = true - visible = true - ci = Int[] - cstr_idx = collect(1:3) - end - α = -π/2 - if i == 1 - ri = SVector{2}(0.0, 0.0) - rj = SVector{2}(P[i+1] ) - elseif i < nb - ri = SVector{2}(P[i]) - rj = SVector{2}(P[i+1]) - else - ri = SVector{2}(0.0, 0.0) - rj = SVector{2}(0.0,-150.0) - end - b = hor_lengths[i] - offset_fix = begin - if i == 1 - ret = 43 + 10 - elseif i == nb - ret = 150 - else - ret = 0 - end - ret - end - offset = ver_lengths_raw[i,1] - ro = ri + SVector{2}(0.0,-offset) - mass_locus = SVector{2}(质心[i]) - m = 质量[i] - inertia = 惯量[i]/2 - Ī = SMatrix{2,2}([ - inertia 0 - 0 inertia - ]) - r̄p1 = SVector{2}(offset_fix,-b,) - r̄p2 = SVector{2}(offset_fix, b,) - r̄p3 = SVector{2}(-offset, 0.0) - r̄p4 = SVector{2}(norm(rj-ri)-offset, 0.0) - loci = [r̄p1,r̄p2,r̄p3,r̄p4] - nr̄p = length(loci) - ṙo = zeros(2); ω = 0.0 - prop = RB.RigidBodyProperty( - i, - contactable, - m, - Ī, - SVector{2}(mass_locus), - loci; - visible = visible, - ) - nmcs = RB.NCF.NC2P1V(ri, rj, ro, α) - state = RB.RigidBodyState(prop, nmcs, ro, α, ṙo, ω, ci, cstr_idx) - mesh_rigid = meshes[i] - body = RB.RigidBody(prop, state, mesh_rigid) - rb - end - rbs = [ - rigidbody(i, P) for i = 1:nb - ] - rigdibodies = TypeSortedCollection(rbs) - numbered = RB.number(rigdibodies) - matrix_sharing_raw = Vector{Matrix{Int}}() - for i = 1:nb-2 - s = zeros(2, nb) - s[1:2, i] = 3:4 - s[1:2, i+1] = 1:2 - push!(matrix_sharing_raw, s) - end - s = zeros(2, nb) - s[1:2, 1] = 1:2 - s[1:2, nb] = 1:2 - push!(matrix_sharing_raw, s) - matrix_sharing = reduce(vcat, matrix_sharing_raw) - # display(matrix_sharing) - indexed = RB.index(rigdibodies, matrix_sharing) - # indexed = RB.index(rigdibodies, ) - - ncables = 2(nb-1) - original_restlens = zeros(ncables) - ks = zeros(ncables) - for i = 1:ncables - original_restlens[i] = 22.0 - ks[i] = 1000.0 - end - cables = - [RB.DistanceSpringDamper2D( original_restlens[i], ks[i], 0.0;slack=true) for i = 1:ncables] # - apparatuses = (cables = cables,) - acs = [ - RB.RegisterActuator(1, - [1:2(nb-1)], - original_restlens, - ) - ] - hub = (actuators = acs,) - - matrix_cnt_raw = Vector{Matrix{Int}}() - for i = 1:nb-1 - s = zeros(2, nb) - s[1, i ] = 1 - s[1, i+1] = -1 - s[2, i ] = 2 - s[2, i+1] = -2 - push!(matrix_cnt_raw, s) - end - matrix_cnt = reduce(vcat, matrix_cnt_raw) - # display(matrix_cnt) - connected = RB.connect(rigdibodies, matrix_cnt) - tensioned = @eponymtuple(connected,) - cnt = RB.Connectivity(numbered, indexed, tensioned) - - st = RB.Structure(rigdibodies, apparatuses, cnt) - bot = RB.Robot(st, hub) -end - tail = make_bai(meshes,质心,质量,惯量) +bot = tail +botvis = deepcopy(bot) plot_traj!( - tail; + botvis; fontsize = 14 |> pt2px, - showmesh = false, + show_axis = false, + showmesh = true, + showpoints = false, + showlabels = false, xlims = (-50,50), ylims = (-300,40), showground = false ) # 静力平衡 -RB.check_static_equilibrium_output_multipliers(tail.st;) +RB.check_static_equilibrium_output_multipliers(bot.structure;) # 刚度、稳定性分析 -RB.undamped_eigen(tail.st) +ω²,δq̌ = RB.undamped_eigen(bot.structure) + +## δq̌ = [Ň*orthovm[:,i] for i in axes(orthovm,2)] +scaling=0.2 +nk = 5 +RB.reset!(botvis) +for i = 1:nk + push!(botvis.traj,deepcopy(botvis.traj[end])) + botvis.traj.t[end] = i + δq̌i = δq̌[i] + ratio = norm(δq̌i)/norm(botvis.traj.q̌[begin]) + botvis.traj.q̌[end] .= botvis.traj.q̌[begin] .+ scaling.*δq̌i/ratio +end +with_theme(theme_pub; + fontsize = 16, + Axis3 = ( + azimuth = 4.7078743833269865, + elevation = 1.307620956698724 + ) + ) do + fig = Figure() + gd2 = fig[1,1:nk] = GridLayout() + plot_traj!( + botvis; + fig = gd2, + AxisType=Axis3, + showinfo = true, + gridsize=(1, nk), + atsteps=2:nk+1, + doslide=false, + showmesh = false, + showwire = false, + showlabels=true, + showpoints=true, + # showcables = false, + showground = false, + xlims = (-150,150), + ## ylims = (-400,300), + ylims = (-400,0), + zlims = (-1,0), + slack_linestyle = :solid, + ## showinit = true, + refcolor = Makie.RGBA{Float32}(0.5,0.5,0.5,0.5), + titleformatfunc = (sgi,tt)-> begin + rich( + rich("($(alphabet[sgi+1])) ", font=:bold), + "Mechanism Mode $sgi" + ) + end, + sup! = (ax,tgob,sgi)->begin + bodies = RB.get_bodies(tgob[]) + r1p3 = bodies[1].state.loci_states[3].frame.position + r1p4 = bodies[1].state.loci_states[4].frame.position + r2p4 = bodies[2].state.loci_states[4].frame.position + r3p4 = bodies[3].state.loci_states[4].frame.position + r4p4 = bodies[4].state.loci_states[4].frame.position + r5p4 = bodies[5].state.loci_states[4].frame.position + r5g = bodies[5].state.mass_locus_state.frame.position + @show r1p3, r1p4 + lines!(ax, + [ + r1p3,r1p4,r2p4,r3p4,r4p4,r5p4,r5g + ] + ) + ## hidedecorations!(ax) + ## xlims!(ax,-50,50) + ## RB.hidez(ax) + ## ylims!(ax,-300,40) + end, + ) + fig +end + + +# 动力学仿真问题 +prob = RB.DynamicsProblem(bot,) + +# 动力学仿真求解 +RB.solve!(prob, + RB.DynamicsSolver( + RB.Zhong06() + ); + dt=0.001,tspan=(0.0,100.0),ftol=1e-10,verbose=true +) + +plot_traj!(bot) + + +using BlockDiagonals + +body1 = RB.get_bodies(bot)[1] + +ke = RB.get_kinetic_energy!(bot,2,) +kec = RB.get_kinetic_energy_coords!(bot,2) +(ke.-kec)./kec + +β = vcat( + -Ω×(MS*Ω) + Ω×(M*V), + Ω×(I*Ω) + MS*(Ω×V) +) + +# Function for first forward recursion on kinematics +function forward_recursion_kinematics(Xsj, lj, Vj, ηj) + # Initialize velocities + Vj_plus_1 = zeros(3) + ηj_plus_1 = zeros(3) + + # Iterate over segment slices + for i in 1:size(Xsj, 2)-1 + ΔX = Xsj[:, i+1] - Xsj[:, i] + Vj_plus_1 += Vj[:, i] + cross(ΔX, ηj[:, i]) + ηj_plus_1 += ηj[:, i] + end + + return Vj_plus_1, ηj_plus_1 +end + +# Function for backward recursion on external dynamics +function backward_recursion_external(Mfj, Ifj, η, ηj, Xsj, lj, external_force) + # Initialize forces and torques + external_force = reverse(external_force, dims=2) # Reverse external force for backward recursion + F_ext = zeros(3) + τ_ext = zeros(3) + + # Iterate over segment slices in reverse order + for i in size(Xsj, 2):-1:1 + # Compute external forces and torques + ΔX = Xsj[:, i+1] - Xsj[:, i] + F_ext += external_force[:, i] * norm(ΔX) + τ_ext += cross(Xsj[:, i], external_force[:, i]) * norm(ΔX) + end + + # Compute fluid forces at endpoints + f_pres_0 = zeros(3) + f_pres_lj = cross(Xsj[:, end], Pfj[:, end]) + + # Compute linear and angular dynamics + dPf_dt = Mfj * (Vj_plus_1 - Vj[:, end]) - F_ext + f_pres_0 - f_pres_lj + dβf_dt = Ifj * (ηj_plus_1 - ηj[:, end]) - τ_ext + cross(Xsj[:, end], f_pres_lj) + + return dPf_dt, dβf_dt +end + +# Function for second forward recursion on internal dynamics +function forward_recursion_internal(dPf_dt, dβf_dt, Mfj, Ifj, Xsj, lj) + # Initialize forces and torques + Pfj = zeros(3, size(Xsj, 2)) + Pfj[:, end] = Mfj * Vj_plus_1 + βfj = zeros(3, size(Xsj, 2)) + βfj[:, end] = Ifj * ηj_plus_1 + + # Iterate over segment slices + for i in 1:size(Xsj, 2)-1 + ΔX = Xsj[:, i+1] - Xsj[:, i] + Pfj[:, i] = Pfj[:, i+1] + dPf_dt * norm(ΔX) + βfj[:, i] = βfj[:, i+1] + dβf_dt * norm(ΔX) + end + + return Pfj, βfj +end + +# Example inputs +Xsj = rand(3, 10) # Segment slice positions +lj = rand(10) # Segment lengths +Vj = rand(3, 10) # Segment velocities +ηj = rand(3, 10) # Segment angular velocities +Mfj = rand(3, 3) # Fluid added mass tensor +Ifj = rand(3, 3) # Fluid added inertia tensor +external_force = rand(3, 10) # External forces + +# First forward recursion on kinematics +Vj_plus_1, ηj_plus_1 = forward_recursion_kinematics(Xsj, lj, Vj, ηj) + +# Backward recursion on external dynamics +dPf_dt, dβf_dt = backward_recursion_external(Mfj, Ifj, η, ηj, Xsj, lj, external_force) + +# Second forward recursion on internal dynamics +Pfj, βfj = forward_recursion_internal(dPf_dt, dβf_dt, Mfj, Ifj, Xsj, lj) + +println("Linear fluid dynamics (Pfj): ", Pfj) +println("Angular fluid dynamics (βfj): ", βfj) -# 动力学分析 diff --git a/yard/tail/curve.jl b/yard/tail/curve.jl deleted file mode 100644 index 7b605da..0000000 --- a/yard/tail/curve.jl +++ /dev/null @@ -1,23 +0,0 @@ -using NLsolve -using Makie -AbstractPlotting.__init__() -n = 12 -function on_curve(n,d,f) - x = zeros(n) - y = zeros(n) - y[1] = f(x[1]) - for i = 2:n - function func!(func,unk) - xi,yi = unk - dy = yi - y[i-1] - dx = xi - x[i-1] - func[1] = dy^2 + dx^2 - d - func[2] = yi-f(xi) - end - soli = nlsolve(func!,[x[i-1]+d,f(x[i-1]+d)]) - x[i],y[i] = soli.zero - end - x,y -end -x,y = on_curve(12,0.1,sin) -plot(x,y) diff --git a/yard/tail/dynamics.jl b/yard/tail/dynamics.jl index 8fc814d..67b2dd3 100644 --- a/yard/tail/dynamics.jl +++ b/yard/tail/dynamics.jl @@ -189,7 +189,7 @@ function dynfuncs(bot) RB.clear_forces!(st) RB.update_bodies!(st,q,q̇) RB.update_apparatuses!(st) - ## RB.apply_gravity!(st) + ## RB.apply_field!(st) RB.assemble_forces!(st) RB.get_force!(F,st) end diff --git a/yard/tail/plotting.jl b/yard/tail/plotting.jl deleted file mode 100644 index b54875c..0000000 --- a/yard/tail/plotting.jl +++ /dev/null @@ -1,65 +0,0 @@ -rb_bars(body) = [Point(body.state.loci_states[1]) => Point(body.state.loci_states[2]);] - -function bars_and_cables(tgstruct) - bars = [Node(rb_bars(body)) for rb in tgstruct.rigidbodies] - cables = Node(RB.get_cables(tgstruct)) - bars, cables -end - -function plotstructure!(ax,tgstruct) - bars, cables = bars_and_cables(tgstruct) - function plot!(ax,bars,cables) - for (lineid,line) in enumerate(bars) - linesegments!(ax, line, color = :black, linewidth = 4) - end - linesegments!(ax, cables, color = :deepskyblue, linewidth = 2) - end - plot!(ax,bars,cables) - xlims!(ax,[-0.2,0.2]) - ylims!(ax,[-0.6,0.05]) - bars,cables -end - -function update_scene!(st,bars,cables,q) - cnt = st.connectivity - RB.distribute_q_to_rbs!(st,q) - for (id,rb) in enumerate(st.rigidbodies) - bars[id][] = rb_bars(body) - end - cables[] = RB.get_cables(st) - # angles = update_angles(st) - # @show angles -end - -function sliderplot(fig,tr,ax,cables) - @unpack st, traj = tr - ls_step = labelslider!(fig,"step",1:length(traj.ts)) - fig[2,1] = ls_step.layout - on(ls_step.slider.value) do this_step - # analyse_slackness(st,sol.qs[this_step]) - update_scene!(st,ax,cables,traj.qs[this_step]) - # show_camera(ax.scene) - end -end -function recordplot(fig,tr,ax,cables;record_name) - @unpack st, traj = tr - record(fig, record_name, 1:length(traj.ts); framerate = 30) do this_step - update_scene!(st,ax,cables,traj.qs[this_step]) - # update_cam!(ax.scene, eyepos,lookat) - end -end - - -function plotstructure(tr::RB.Robot;record_name="") - @unpack st, traj = tr - fig = Figure(resolution=(1000,1000)) - ax = fig[1, 1] = Axis(fig) - bars,cables = plotstructure!(ax,st) - ax.aspect = DataAspect() - if record_name=="" - sliderplot(fig,tr,ax,cables) - else - recordplot(fig,tr,ax,cables;record_name) - end - fig -end diff --git a/yard/tail/swing.jl b/yard/tail/swing.jl deleted file mode 100644 index 06f95d8..0000000 --- a/yard/tail/swing.jl +++ /dev/null @@ -1,74 +0,0 @@ -using LinearAlgebra -using SparseArrays -using Parameters -using StaticArrays -# using BenchmarkTools -# import PyPlot; const plt = PyPlot -# using LaTeXStrings -using Makie -AbstractPlotting.__init__() - -using NLsolve -using Revise -using TensegritySolvers; const TS = TensegritySolvers -using Robot -const TR = Robot -include("tail_define.jl") -include("plotting.jl") - -include("../analysis.jl") - -n = 13 -tail = make_curve_tail(n) -# Vy = make_curve_tail(n) -_,_,tailscene = plotstructure(tail) -tailscene -# @code_warntype make_tail(n) -q0,q̇0,λ0 = RB.get_initial(tail) -# q̇0[end-3:end] .= 5*[0.1,0.0,0.1,0.0] - -# RB.get_nbodycstr(tail) -# RB.get_nbodydof(tail) # RB.get_num_of_coords(tail) - - -function dynfuncs(tgstruct,q0) - - M = RB.build_massmatrix(tgstruct) - Φ = RB.build_Φ(tgstruct,q0) - A = RB.build_A(tgstruct) - - #Q̃=RB.build_Q̃(tgstruct) - - function F!(F,q,q̇,t) - # du = 0.01*sin(t) - # RB.actuate!(tgstruct.actuators[1],du) - RB.reset_forces!(tgstruct) - RB.distribute_q_to_rbs!(tgstruct,q,q̇) - RB.update_cables_apply_forces!(tgstruct) - # RB.apply_gravity!(tgstruct,factor=0.001) - # F .= Q̃*RB.fvector(tgstruct) - F .= 0.0 - RB.assemble_forces!(F,tgstruct) - end - - M,Φ,A,F!,nothing -end - -M,Φ,A,F!,Jacs = dynfuncs(tail,q0) -# Φ(q0) -# @code_warntype Φ(q0) -# A(q0) -# @code_warntype A(q0) -F = similar(q0) -# @code_warntype F!(F,q0,q̇0,0.0) -dt = 0.01 -prob = TS.DyProblem(dynfuncs(tail,q0),q0,q̇0,λ0,(0.0,10.0)) -sol = TS.solve(prob,TS.Zhong06(),dt=dt,ftol=1e-14,verbose=true) - -plotstructure(tail,sol,sliderplot) -plotstructure(tail,sol,recordplot) -# sol = TS.solve(prob,TS.ConstSPARK(1),dt=dt,ftol=1e-12,verbose=true) -@code_warntype TS.solve(prob,TS.Zhong06(),dt=dt,ftol=1e-14,verbose=true) -kes,epes,gpes,restitution_coefficients,es_err = analyse_energy(tail,sol;gravity=false,elasticity=true) -restitution_coefficients -plot(restitution_coefficients) diff --git a/yard/tail/test.jl b/yard/tail/test.jl deleted file mode 100644 index a20d694..0000000 --- a/yard/tail/test.jl +++ /dev/null @@ -1,53 +0,0 @@ -using LinearAlgebra -using SparseArrays -using Parameters -using StaticArrays -using Makie -#plot(rand(10)) -# using BenchmarkTools -# import PyPlot; const plt = PyPlot -# using LaTeXStrings -# using NLsolve -using Revise -using Rible; const TR = Rible -#cd("examples/tail") -includet("tail_define.jl") -includet("make_new_tail.jl") -includet("plotting.jl") -includet("../analysis.jl") - -n = 4 -tail = make_new_tail(n) -#plotstructure(tail) -#@code_warntype make_tail(n) -q0,q̇0,λ0 = RB.get_initial(tail.st) -q0=q =Vec{28,Float64}(0,0,2,0,0,-2,2,-2,0,-4,2,-4,0,-6,2,-6,0,-8,2,-8,0,-10,0,-12,0,-14,0,-16) -q̇0[end-3:end] .= 5*[0.1,0.0,0.1,0.0] -RB.set_new_initial!(tail,q0,q̇0) - -function dynfuncs(tr) - @unpack st = tr - M = RB.build_massmatrix(st) - Φ = RB.build_Φ(st) - A = RB.build_A(st) - - #Q̃=RB.build_Q̃(st) - - function F!(F,q,q̇,t) - RB.reset_forces!(st) - RB.distribute_q_to_rbs!(st,q,q̇) - RB.update_cables_apply_forces!(st) - # F .= Q̃*RB.fvector(tgstruct) - F .= 0.0 - RB.assemble_forces!(F,st) - end - - M,Φ,A,F!,nothing -end - -dt = 0.01 -prob = RB.DyProblem(dynfuncs(tail),tail,(0.0,20.0)) -RB.solve!(tail,prob,RB.Zhong06(),dt=dt,ftol=1e-14,verbose=true) -# sol = RB.solve(prob,RB.ConstSPARK(1),dt=dt,ftol=1e-12,verbose=true) -#@code_warntype RB.solve(prob,RB.Zhong06(),dt=dt,ftol=1e-14,verbose=true) -plotstructure(tail)